From 193bdacdd8abd9554ba2535921b86eff21071ab1 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 27 Nov 2024 18:08:45 +0100 Subject: [PATCH] Add documentation on `ros2_control_node` and make lock_memory false by default (#1890) (cherry picked from commit abb4c688bdfd6b47a659a884f71ae8736c4a19bc) # Conflicts: # controller_manager/src/ros2_control_node.cpp --- controller_manager/doc/userdoc.rst | 32 ++++++++++++++++++++ controller_manager/src/ros2_control_node.cpp | 10 ++++++ 2 files changed, 42 insertions(+) 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..3c46de26dc 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -46,6 +46,16 @@ int main(int argc, char ** argv) const bool use_sim_time = cm->get_parameter_or("use_sim_time", false); +<<<<<<< HEAD +======= + const bool lock_memory = cm->get_parameter_or("lock_memory", false); + std::string message; + if (lock_memory && !realtime_tools::lock_memory(message)) + { + RCLCPP_WARN(cm->get_logger(), "Unable to lock the memory : '%s'", message.c_str()); + } + +>>>>>>> abb4c68 (Add documentation on `ros2_control_node` and make lock_memory false by default (#1890)) const int cpu_affinity = cm->get_parameter_or("cpu_affinity", -1); if (cpu_affinity >= 0) {