Skip to content

Commit 911ba28

Browse files
authored
Fix the CPU affinity of the ros2_control_node (#2509) (#2511)
1 parent affaf3b commit 911ba28

File tree

1 file changed

+24
-23
lines changed

1 file changed

+24
-23
lines changed

controller_manager/src/ros2_control_node.cpp

Lines changed: 24 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -70,29 +70,6 @@ int main(int argc, char ** argv)
7070
}
7171
}
7272

73-
rclcpp::Parameter cpu_affinity_param;
74-
if (cm->get_parameter("cpu_affinity", cpu_affinity_param))
75-
{
76-
std::vector<int> cpus = {};
77-
if (cpu_affinity_param.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER)
78-
{
79-
cpus = {static_cast<int>(cpu_affinity_param.as_int())};
80-
}
81-
else if (cpu_affinity_param.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY)
82-
{
83-
const auto cpu_affinity_param_array = cpu_affinity_param.as_integer_array();
84-
std::for_each(
85-
cpu_affinity_param_array.begin(), cpu_affinity_param_array.end(),
86-
[&cpus](int cpu) { cpus.push_back(static_cast<int>(cpu)); });
87-
}
88-
const auto affinity_result = realtime_tools::set_current_thread_affinity(cpus);
89-
if (!affinity_result.first)
90-
{
91-
RCLCPP_WARN(
92-
cm->get_logger(), "Unable to set the CPU affinity : '%s'", affinity_result.second.c_str());
93-
}
94-
}
95-
9673
// wait for the clock to be available
9774
cm->get_clock()->wait_until_started();
9875
cm->get_clock()->sleep_for(rclcpp::Duration::from_seconds(1.0 / cm->get_update_rate()));
@@ -106,6 +83,30 @@ int main(int argc, char ** argv)
10683
std::thread cm_thread(
10784
[cm, thread_priority, use_sim_time]()
10885
{
86+
rclcpp::Parameter cpu_affinity_param;
87+
if (cm->get_parameter("cpu_affinity", cpu_affinity_param))
88+
{
89+
std::vector<int> cpus = {};
90+
if (cpu_affinity_param.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER)
91+
{
92+
cpus = {static_cast<int>(cpu_affinity_param.as_int())};
93+
}
94+
else if (cpu_affinity_param.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY)
95+
{
96+
const auto cpu_affinity_param_array = cpu_affinity_param.as_integer_array();
97+
std::for_each(
98+
cpu_affinity_param_array.begin(), cpu_affinity_param_array.end(),
99+
[&cpus](int cpu) { cpus.push_back(static_cast<int>(cpu)); });
100+
}
101+
const auto affinity_result = realtime_tools::set_current_thread_affinity(cpus);
102+
if (!affinity_result.first)
103+
{
104+
RCLCPP_WARN(
105+
cm->get_logger(), "Unable to set the CPU affinity : '%s'",
106+
affinity_result.second.c_str());
107+
}
108+
}
109+
109110
if (!realtime_tools::configure_sched_fifo(thread_priority))
110111
{
111112
RCLCPP_WARN(

0 commit comments

Comments
 (0)