diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index 46c46fa028..46781d461c 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -70,10 +70,6 @@ hardware_components_initial_state.unconfigured (optional; list; default: hardware_components_initial_state.inactive (optional; list; default: empty) Defines which hardware components will be configured immediately when controller manager is started. -robot_description (mandatory; string) - String with the URDF string as robot description. - This is usually result of the parsed description files by ``xacro`` command. - update_rate (mandatory; integer) The frequency of controller manager's real-time update loop. This loop reads states from hardware, updates controller and writes commands to hardware. @@ -83,6 +79,55 @@ update_rate (mandatory; integer) Name of a plugin exported using ``pluginlib`` for a controller. This is a class from which controller's instance with name "``controller_name``" is created. +Subscribers +----------- + +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 have two options for managing different robot descriptions: + +1. **Using Namespaces:** You can place both the ``robot_state_publisher`` and the ``controller_manager`` nodes into the same namespace. + +.. 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", + ) + +2. **Using Remappings:** You can use remappings to handle different robot descriptions. This involves relaying topics using the ``remappings`` tag, allowing you to specify custom topics for each controller manager. + +.. code-block:: python + + control_node = Node( + package="controller_manager", + executable="ros2_control_node", + 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 -------------- diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 2112708638..b7d2869107 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -284,7 +284,7 @@ ControllerManager::ControllerManager( RCLCPP_WARN( get_logger(), "[Deprecated] Passing the robot description parameter directly to the control_manager node " - "is deprecated. Use '~/robot_description' topic from 'robot_state_publisher' instead."); + "is deprecated. Use the 'robot_description' topic from 'robot_state_publisher' instead."); init_resource_manager(robot_description_); init_services(); } @@ -329,7 +329,7 @@ void ControllerManager::subscribe_to_robot_description_topic() // set QoS to transient local to get messages that have already been published // (if robot state publisher starts before controller manager) robot_description_subscription_ = create_subscription( - "~/robot_description", rclcpp::QoS(1).transient_local(), + "robot_description", rclcpp::QoS(1).transient_local(), std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1)); RCLCPP_INFO( get_logger(), "Subscribing to '%s' topic for robot description.",