@@ -70,29 +70,6 @@ int main(int argc, char ** argv)
70
70
}
71
71
}
72
72
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
-
96
73
// wait for the clock to be available
97
74
cm->get_clock ()->wait_until_started ();
98
75
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)
106
83
std::thread cm_thread (
107
84
[cm, thread_priority, use_sim_time]()
108
85
{
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
+
109
110
if (!realtime_tools::configure_sched_fifo (thread_priority))
110
111
{
111
112
RCLCPP_WARN (
0 commit comments