Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add documentation on ros2_control_node and make lock_memory false by default (backport #1890) #1895

Merged
merged 3 commits into from
Dec 4, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 32 additions & 0 deletions controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -262,6 +262,38 @@ The workaround for this is to specify another node name remap rule in the ``Node
auto cm = std::make_shared<controller_manager::ControllerManager>(
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 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>`_
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
-----------

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 @@ -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<bool>("lock_memory", true);
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
Loading