From 255b2f9290b7c3c83984ac285fe3572de275c21d Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Mon, 18 Sep 2023 06:48:44 +0100 Subject: [PATCH] [Doc] Add specific documentation on the available fw cmd controllers (#765) (#778) --- effort_controllers/doc/userdoc.rst | 40 ++++++++++++++++++++-- forward_command_controller/doc/userdoc.rst | 12 ++++++- position_controllers/doc/userdoc.rst | 40 ++++++++++++++++++++-- velocity_controllers/doc/userdoc.rst | 40 ++++++++++++++++++++-- 4 files changed, 122 insertions(+), 10 deletions(-) diff --git a/effort_controllers/doc/userdoc.rst b/effort_controllers/doc/userdoc.rst index 74caf63391..62e98a75f9 100644 --- a/effort_controllers/doc/userdoc.rst +++ b/effort_controllers/doc/userdoc.rst @@ -7,7 +7,41 @@ effort_controllers This is a collection of controllers that work using the "effort" joint command interface but may accept different joint-level commands at the controller level, e.g. controlling the effort on a certain joint to achieve a set position. -Hardware interface type ------------------------ +The package contains the following controllers: -These controllers work with joints using the "effort" command interface. +effort_controllers/JointGroupEffortController +------------------------------------------------- + +This is specialization of the :ref:`forward_command_controller ` that works using the "effort" joint interface. + + +ROS 2 interface of the controller +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Topics +,,,,,,,,,,,,,,,,,, + +~/commands (input topic) [std_msgs::msg::Float64MultiArray] + Joints' effort commands + + +Parameters +,,,,,,,,,,,,,,,,,, +This controller overrides the interface parameter from :ref:`forward_command_controller `, and the +``joints`` parameter is the only one that is required. + +An example parameter file is given here + +.. code-block:: yaml + + controller_manager: + ros__parameters: + update_rate: 100 # Hz + + effort_controller: + type: effort_controllers/JointGroupEffortController + + effort_controller: + ros__parameters: + joints: + - slider_to_cart diff --git a/forward_command_controller/doc/userdoc.rst b/forward_command_controller/doc/userdoc.rst index a91479c9af..01aa2492a8 100644 --- a/forward_command_controller/doc/userdoc.rst +++ b/forward_command_controller/doc/userdoc.rst @@ -16,8 +16,18 @@ Hardware interface type This controller can be used for every type of command interface. + +ROS 2 interface of the controller +--------------------------------- + +Topics +^^^^^^^ + +~/commands (input topic) [std_msgs::msg::Float64MultiArray] + Target joint commands + Parameters ------------- +^^^^^^^^^^^^^^ This controller uses the `generate_parameter_library `_ to handle its parameters. diff --git a/position_controllers/doc/userdoc.rst b/position_controllers/doc/userdoc.rst index f321e8a698..89766df9d4 100644 --- a/position_controllers/doc/userdoc.rst +++ b/position_controllers/doc/userdoc.rst @@ -7,7 +7,41 @@ position_controllers This is a collection of controllers that work using the "position" joint command interface but may accept different joint-level commands at the controller level, e.g. controlling the position on a certain joint to achieve a set velocity. -Hardware interface type ------------------------ +The package contains the following controllers: -These controllers work with joints using the "position" command interface. +position_controllers/JointGroupPositionController +------------------------------------------------- + +This is specialization of the :ref:`forward_command_controller ` that works using the "position" joint interface. + + +ROS 2 interface of the controller +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Topics +,,,,,,,,,,,,,,,,,, + +~/commands (input topic) [std_msgs::msg::Float64MultiArray] + Joints' position commands + + +Parameters +,,,,,,,,,,,,,,,,,, +This controller overrides the interface parameter from :ref:`forward_command_controller `, and the +``joints`` parameter is the only one that is required. + +An example parameter file is given here + +.. code-block:: yaml + + controller_manager: + ros__parameters: + update_rate: 100 # Hz + + position_controller: + type: position_controllers/JointGroupPositionController + + position_controller: + ros__parameters: + joints: + - slider_to_cart diff --git a/velocity_controllers/doc/userdoc.rst b/velocity_controllers/doc/userdoc.rst index fa7e36062e..469b975a97 100644 --- a/velocity_controllers/doc/userdoc.rst +++ b/velocity_controllers/doc/userdoc.rst @@ -7,7 +7,41 @@ velocity_controllers This is a collection of controllers that work using the "velocity" joint command interface but may accept different joint-level commands at the controller level, e.g. controlling the velocity on a certain joint to achieve a set position. -Hardware interface type ------------------------ +The package contains the following controllers: -These controllers work with joints using the "velocity" command interface. +velocity_controllers/JointGroupVelocityController +------------------------------------------------- + +This is specialization of the :ref:`forward_command_controller ` that works using the "velocity" joint interface. + + +ROS 2 interface of the controller +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Topics +,,,,,,,,,,,,,,,,,, + +~/commands (input topic) [std_msgs::msg::Float64MultiArray] + Joints' velocity commands + + +Parameters +,,,,,,,,,,,,,,,,,, +This controller overrides the interface parameter from :ref:`forward_command_controller `, and the +``joints`` parameter is the only one that is required. + +An example parameter file is given here + +.. code-block:: yaml + + controller_manager: + ros__parameters: + update_rate: 100 # Hz + + velocity_controller: + type: velocity_controllers/JointGroupVelocityController + + velocity_controller: + ros__parameters: + joints: + - slider_to_cart