From 189f67302f204371b6a344d1236d57467f6feca7 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Tue, 5 Nov 2024 11:08:17 +0100 Subject: [PATCH] [ros2_control_node] Add option to set the CPU affinity (#1852) --- controller_manager/src/ros2_control_node.cpp | 11 +++++++++++ doc/release_notes.rst | 1 + 2 files changed, 12 insertions(+) diff --git a/controller_manager/src/ros2_control_node.cpp b/controller_manager/src/ros2_control_node.cpp index 1cc6125dd9..dd9d71aacd 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -64,6 +64,17 @@ int main(int argc, char ** argv) RCLCPP_WARN(cm->get_logger(), "Unable to lock the memory : '%s'", message.c_str()); } + const int cpu_affinity = cm->get_parameter_or("cpu_affinity", -1); + if (cpu_affinity >= 0) + { + const auto affinity_result = realtime_tools::set_current_thread_affinity(cpu_affinity); + if (!affinity_result.first) + { + RCLCPP_WARN( + cm->get_logger(), "Unable to set the CPU affinity : '%s'", affinity_result.second.c_str()); + } + } + RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate()); const int thread_priority = cm->get_parameter_or("thread_priority", kSchedPriority); RCLCPP_INFO( diff --git a/doc/release_notes.rst b/doc/release_notes.rst index 8d94919950..23f124832f 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -78,6 +78,7 @@ controller_manager * Added support for the wildcard entries for the controller configuration files (`#1724 `_). * The ``ros2_control_node`` node now accepts the ``thread_priority`` parameter to set the scheduler priority of the controller_manager's RT thread (`#1820 `_). * The ``ros2_control_node`` node has a new ``lock_memory`` parameter to lock memory at startup to physical RAM in order to avoid page faults (`#1822 `_). +* The ``ros2_control_node`` node has a new ``cpu_affinity`` parameter to bind the process to a specific CPU core. By default, this is not enabled. (`#1852 `_). hardware_interface ******************