diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index 872a695d0f..fb69753ee2 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -325,7 +325,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 da79de76a3..af8d26d8b1 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -59,7 +59,8 @@ int main(int argc, char ** argv) const bool use_sim_time = cm->get_parameter_or("use_sim_time", false); - 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)) {