From 5c89eb3d04a24a8c6efb97b7cd033988a83022e4 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 22 Feb 2024 11:46:10 +0000 Subject: [PATCH] Update docs with instructions for multiple controller_managers --- controller_manager/doc/userdoc.rst | 45 ++++++++++++++++++++++++++++++ 1 file changed, 45 insertions(+) diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index b10f7871b8..1be9175643 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -86,6 +86,51 @@ robot_description (std_msgs/msg/String) The URDF string as robot description. This is usually published by the ``robot_state_publisher`` node. +Handling Multiple Controller Managers +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +When dealing with multiple controller managers, you can manage different robot descriptions either +using remappings or putting both, the ``robot_state_publisher`` and the ``controller_manager`` into +the same namespace. + +Using namespaces a snippet of a launchfile could look like the following: + +.. code-block:: python + + control_node = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_controllers], + output="both", + namespace="rrbot", + ) + robot_state_pub_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + namespace="rrbot", + ) + + +Using remappings: + +.. code-block:: python + + control_node = Node( + package="controller_manager", + + parameters=[robot_controllers], + output="both", + remappings=[('robot_description', '/rrbot/robot_description')] + ) + robot_state_pub_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + namespace="rrbot", + ) Helper scripts --------------