Skip to content

Commit

Permalink
Lock memory by default on a realtime system setup (#1896)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Dec 4, 2024
1 parent 3052b58 commit dbee650
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 2 deletions.
2 changes: 1 addition & 1 deletion controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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 <https://access.redhat.com/solutions/61334>`_
Expand Down
3 changes: 2 additions & 1 deletion controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<bool>("lock_memory", false);
const bool has_realtime = realtime_tools::has_realtime_kernel();
const bool lock_memory = cm->get_parameter_or<bool>("lock_memory", has_realtime);
std::string message;
if (lock_memory && !realtime_tools::lock_memory(message))
{
Expand Down

0 comments on commit dbee650

Please sign in to comment.