From 9257ad3973e2aebf9756c7a8154efb9673ed1a43 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 8 Jul 2024 10:01:16 +0200 Subject: [PATCH] Update docs and cleanup member of `GazeboSimROS2ControlPluginPrivate` (#363) --- doc/index.rst | 25 ++++++++++++++----- .../src/gz_ros2_control_plugin.cpp | 5 ---- 2 files changed, 19 insertions(+), 11 deletions(-) diff --git a/doc/index.rst b/doc/index.rst index 1e65767e..149cd734 100644 --- a/doc/index.rst +++ b/doc/index.rst @@ -131,17 +131,30 @@ robot hardware interfaces between *ros2_control* and Gazebo. .. code-block:: xml - - robot_description - robot_state_publisher - $(find gz_ros2_control_demos)/config/cart_controller.yaml - + + $(find gz_ros2_control_demos)/config/cart_controller.yaml + The *gz_ros2_control* ```` tag also has the following optional child elements: -* ````: YAML file with the configuration of the controllers +* ````: A YAML file with the configuration of the controllers. This element can be given multiple times to load multiple files. * ````: if set to true (default), it will hold the joints' position if their interface was not claimed, e.g., the controller hasn't been activated yet. +* ````: Set controller manager name (default: ``controller_manager``) + +Additionally, one can specify a namespace and remapping rules, which will be forwarded to the controller_manager and loaded controllers. Add the following ```` section: + +.. code-block:: xml + + + + ... + + my_namespace + /robot_description:=/robot_description_full + + + Default gz_ros2_control Behavior ----------------------------------------------------------- diff --git a/gz_ros2_control/src/gz_ros2_control_plugin.cpp b/gz_ros2_control/src/gz_ros2_control_plugin.cpp index 60161d5d..f42dcf8e 100644 --- a/gz_ros2_control/src/gz_ros2_control_plugin.cpp +++ b/gz_ros2_control/src/gz_ros2_control_plugin.cpp @@ -159,11 +159,6 @@ class GazeboSimROS2ControlPluginPrivate /// \brief Timing rclcpp::Duration control_period_ = rclcpp::Duration(1, 0); - /// \brief Interface loader - std::shared_ptr> - robot_hw_sim_loader_{nullptr}; - /// \brief Controller manager std::shared_ptr controller_manager_{nullptr};