From 9633c412d5158ddd8589cb464ab7d69250982e25 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 27 Nov 2024 18:08:45 +0100 Subject: [PATCH 1/2] Add documentation on `ros2_control_node` and make lock_memory false by default (#1890) --- controller_manager/doc/userdoc.rst | 32 ++++++++++++++++++++ controller_manager/src/ros2_control_node.cpp | 2 +- 2 files changed, 33 insertions(+), 1 deletion(-) diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index 8f1c57161c..9bd1fbd191 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -262,6 +262,38 @@ The workaround for this is to specify another node name remap rule in the ``Node auto cm = std::make_shared( executor, "_target_node_name", "some_optional_namespace", options); +Launching controller_manager with ros2_control_node +--------------------------------------------------- + +The controller_manager can be launched with the ros2_control_node executable. The following example shows how to launch the controller_manager with the ros2_control_node executable: + +.. code-block:: python + + control_node = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_controllers], + output="both", + ) + +The ros2_control_node executable uses the following parameters from the ``controller_manager`` node: + +lock_memory (optional; bool; default: false) + Locks the memory of the ``controller_manager`` node at startup to physical RAM in order to avoid page faults + and to prevent the node from being swapped out to disk. + Find more information about the setup for memory locking in the following link : `How to set ulimit values `_ + The following command can be used to set the memory locking limit temporarily : ``ulimit -l unlimited``. + +cpu_affinity (optional; int; default: -1) + Sets the CPU affinity of the ``controller_manager`` node to the specified CPU core. + The value of -1 means that the CPU affinity is not set. + +thread_priority (optional; int; default: 50) + Sets the thread priority of the ``controller_manager`` node to the specified value. The value must be between 0 and 99. + +use_sim_time (optional; bool; default: false) + Enables the use of simulation time in the ``controller_manager`` node. + Concepts ----------- diff --git a/controller_manager/src/ros2_control_node.cpp b/controller_manager/src/ros2_control_node.cpp index 3200fc926e..75960a02ef 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -56,7 +56,7 @@ int main(int argc, char ** argv) cm->get_logger(), "Unable to set the CPU affinity : '%s'", affinity_result.second.c_str()); } } - const bool lock_memory = cm->get_parameter_or("lock_memory", true); + const bool lock_memory = cm->get_parameter_or("lock_memory", false); std::string message; if (lock_memory && !realtime_tools::lock_memory(message)) { From ec9a635e8a65a74010811fef793d582833c87daa Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 4 Dec 2024 08:24:17 +0100 Subject: [PATCH 2/2] Lock memory by default on a realtime system setup (#1896) --- controller_manager/doc/userdoc.rst | 2 +- controller_manager/src/ros2_control_node.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index 9bd1fbd191..af1912e4b3 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -278,7 +278,7 @@ The controller_manager can be launched with the ros2_control_node executable. Th The ros2_control_node executable uses the following parameters from the ``controller_manager`` node: -lock_memory (optional; bool; default: false) +lock_memory (optional; bool; default: false for a non-realtime kernel, true for a realtime kernel) Locks the memory of the ``controller_manager`` node at startup to physical RAM in order to avoid page faults and to prevent the node from being swapped out to disk. Find more information about the setup for memory locking in the following link : `How to set ulimit values `_ diff --git a/controller_manager/src/ros2_control_node.cpp b/controller_manager/src/ros2_control_node.cpp index 75960a02ef..d6a0b0f3dd 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -56,7 +56,8 @@ int main(int argc, char ** argv) cm->get_logger(), "Unable to set the CPU affinity : '%s'", affinity_result.second.c_str()); } } - const bool lock_memory = cm->get_parameter_or("lock_memory", false); + const bool has_realtime = realtime_tools::has_realtime_kernel(); + const bool lock_memory = cm->get_parameter_or("lock_memory", has_realtime); std::string message; if (lock_memory && !realtime_tools::lock_memory(message)) {