Skip to content

Commit 9487724

Browse files
committed
feat: Thread configuration prototype
This is a prototype implementation of RCLCPP for discussion about the thread configuration feature to receive and apply a set of scheduling parameters for the threads controlled by the ROS 2 executor. Our basic idea is as below. 1. Implement a new class rclcpp::thread and modify rclcpp to use it. This class has the same function set as the std::thread but also additional features to control its thread attributions. 2. Modify the rcl layer to receive a set of scheduling parameters. The parameters are described in YAML format and passed via command line parameters, environment variables, or files. 3. the rclcpp reads the parameters from rcl and applies them to each thread in the thread pool. There have been some discussions about this pull request, as below. [ROS Discourse] https://discourse.ros.org/t/adding-thread-attributes-configuration-in-ros-2-framework/30701 [ROS 2 Real-Time Working Group] ros-realtime/ros-realtime.github.io#18
1 parent f8072f2 commit 9487724

17 files changed

+1450
-11
lines changed

rclcpp/CMakeLists.txt

+10
Original file line numberDiff line numberDiff line change
@@ -121,6 +121,16 @@ set(${PROJECT_NAME}_SRCS
121121
src/rclcpp/waitable.cpp
122122
)
123123

124+
if(${CMAKE_SYSTEM_NAME} MATCHES "Linux")
125+
list(APPEND ${PROJECT_NAME}_SRCS
126+
src/rclcpp/threads/posix_thread.cpp
127+
)
128+
elseif(${CMAKE_SYSTEM_NAME} MATCHES "Windows")
129+
list(APPEND ${PROJECT_NAME}_SRCS
130+
src/rclcpp/threads/windows_thread.cpp
131+
)
132+
endif()
133+
124134
find_package(Python3 REQUIRED COMPONENTS Interpreter)
125135

126136
# "watch" template for changes

rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -18,10 +18,12 @@
1818
#include <chrono>
1919
#include <memory>
2020
#include <mutex>
21+
#include <vector>
2122
#include <set>
2223
#include <thread>
2324
#include <unordered_map>
2425

26+
#include "rcl_yaml_param_parser/types.h"
2527
#include "rclcpp/executor.hpp"
2628
#include "rclcpp/macros.hpp"
2729
#include "rclcpp/memory_strategies.hpp"
@@ -85,6 +87,7 @@ class MultiThreadedExecutor : public rclcpp::Executor
8587
size_t number_of_threads_;
8688
bool yield_before_execute_;
8789
std::chrono::nanoseconds next_exec_timeout_;
90+
rcl_thread_attrs_t * thread_attributes_;
8891
};
8992

9093
} // namespace executors

rclcpp/include/rclcpp/executors/single_threaded_executor.hpp

+7
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include <memory>
2323
#include <vector>
2424

25+
#include "rcl_yaml_param_parser/types.h"
2526
#include "rclcpp/executor.hpp"
2627
#include "rclcpp/macros.hpp"
2728
#include "rclcpp/memory_strategies.hpp"
@@ -65,8 +66,14 @@ class SingleThreadedExecutor : public rclcpp::Executor
6566
void
6667
spin() override;
6768

69+
protected:
70+
RCLCPP_PUBLIC
71+
void
72+
run();
73+
6874
private:
6975
RCLCPP_DISABLE_COPY(SingleThreadedExecutor)
76+
rcl_thread_attrs_t * thread_attributes_;
7077
};
7178

7279
} // namespace executors

rclcpp/include/rclcpp/threads.hpp

+26
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
// Copyright 2023 eSOL Co.,Ltd.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef RCLCPP__THREADS_HPP_
16+
#define RCLCPP__THREADS_HPP_
17+
18+
#if defined(__linux__)
19+
#include "rclcpp/threads/posix/thread.hpp"
20+
#elif defined(_WIN32)
21+
#include "rclcpp/threads/win32/thread.hpp"
22+
#else
23+
#include "rclcpp/threads/std/thread.hpp"
24+
#endif
25+
26+
#endif // RCLCPP__THREADS_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,158 @@
1+
// Copyright 2023 eSOL Co.,Ltd.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef RCLCPP__THREADS__POSIX__LINUX__CPU_SET_HPP_
16+
#define RCLCPP__THREADS__POSIX__LINUX__CPU_SET_HPP_
17+
18+
#include <pthread.h>
19+
#include <vector>
20+
#include <utility>
21+
#include <memory>
22+
23+
#include "rclcpp/visibility_control.hpp"
24+
25+
namespace rclcpp
26+
{
27+
28+
namespace detail
29+
{
30+
31+
struct CpuSet
32+
{
33+
using NativeCpuSetType = cpu_set_t;
34+
CpuSet() = default;
35+
explicit CpuSet(std::size_t cpu)
36+
{
37+
init_cpu_set();
38+
CPU_ZERO_S(alloc_size(), cpu_set_.get());
39+
CPU_SET_S(cpu, alloc_size(), cpu_set_.get());
40+
}
41+
CpuSet(const CpuSet & other)
42+
{
43+
if (other.cpu_set_) {
44+
init_cpu_set();
45+
memcpy(cpu_set_.get(), other.cpu_set_.get(), alloc_size());
46+
}
47+
}
48+
CpuSet & operator=(const CpuSet & other)
49+
{
50+
if (other.cpu_set_) {
51+
init_cpu_set();
52+
memcpy(cpu_set_.get(), other.cpu_set_.get(), alloc_size());
53+
} else {
54+
clear();
55+
}
56+
return *this;
57+
}
58+
CpuSet(CpuSet && other)
59+
: CpuSet()
60+
{
61+
swap(other);
62+
}
63+
CpuSet & operator=(CpuSet && other)
64+
{
65+
CpuSet tmp;
66+
other.swap(tmp);
67+
tmp.swap(*this);
68+
return *this;
69+
}
70+
void swap(CpuSet & other)
71+
{
72+
using std::swap;
73+
swap(cpu_set_, other.cpu_set_);
74+
swap(num_proc_, other.num_proc_);
75+
}
76+
void set(std::size_t cpu)
77+
{
78+
init_cpu_set();
79+
valid_cpu(cpu);
80+
CPU_SET_S(cpu, alloc_size(), cpu_set_.get());
81+
}
82+
void unset(std::size_t cpu)
83+
{
84+
init_cpu_set();
85+
valid_cpu(cpu);
86+
CPU_CLR_S(cpu, alloc_size(), cpu_set_.get());
87+
}
88+
void clear()
89+
{
90+
if (cpu_set_) {
91+
CPU_ZERO_S(alloc_size(), cpu_set_.get());
92+
}
93+
}
94+
bool is_set(std::size_t cpu) const
95+
{
96+
if (cpu_set_) {
97+
valid_cpu(cpu);
98+
return CPU_ISSET_S(cpu, alloc_size(), cpu_set_.get());
99+
} else {
100+
return false;
101+
}
102+
}
103+
104+
std::size_t max_processors() const
105+
{
106+
return num_proc_;
107+
}
108+
std::size_t alloc_size() const
109+
{
110+
return CPU_ALLOC_SIZE(num_proc_);
111+
}
112+
NativeCpuSetType * native_cpu_set() const
113+
{
114+
return cpu_set_.get();
115+
}
116+
117+
private:
118+
void init_cpu_set()
119+
{
120+
if (cpu_set_) {
121+
return;
122+
}
123+
auto num_proc = sysconf(_SC_NPROCESSORS_ONLN);
124+
if (num_proc == -1) {
125+
return;
126+
}
127+
auto p = CPU_ALLOC(CPU_ALLOC_SIZE(num_proc));
128+
cpu_set_ = std::unique_ptr<NativeCpuSetType, CpuSetDeleter>(p);
129+
num_proc_ = num_proc;
130+
}
131+
void valid_cpu(std::size_t cpu) const
132+
{
133+
if (num_proc_ <= cpu) {
134+
auto ec = std::make_error_code(std::errc::invalid_argument);
135+
throw std::system_error{ec, "cpu number is invaild"};
136+
}
137+
}
138+
struct CpuSetDeleter
139+
{
140+
void operator()(NativeCpuSetType * cpu_set) const
141+
{
142+
CPU_FREE(cpu_set);
143+
}
144+
};
145+
std::unique_ptr<NativeCpuSetType, CpuSetDeleter> cpu_set_;
146+
std::size_t num_proc_;
147+
};
148+
149+
inline void swap(CpuSet & a, CpuSet & b)
150+
{
151+
a.swap(b);
152+
}
153+
154+
} // namespace detail
155+
156+
} // namespace rclcpp
157+
158+
#endif // RCLCPP__THREADS__POSIX__LINUX__CPU_SET_HPP_

0 commit comments

Comments
 (0)