Skip to content

Commit

Permalink
[Doc] Add specific documentation on the available fw cmd controllers (#…
Browse files Browse the repository at this point in the history
…765)

(cherry picked from commit 84d988c)
  • Loading branch information
christophfroehlich authored and mergify[bot] committed Sep 17, 2023
1 parent 7962d33 commit 9de3778
Show file tree
Hide file tree
Showing 4 changed files with 122 additions and 10 deletions.
40 changes: 37 additions & 3 deletions effort_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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 <forward_command_controller_userdoc>` 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 <forward_command_controller_userdoc>`, 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
12 changes: 11 additions & 1 deletion forward_command_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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 <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.

Expand Down
40 changes: 37 additions & 3 deletions position_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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 <forward_command_controller_userdoc>` 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 <forward_command_controller_userdoc>`, 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
40 changes: 37 additions & 3 deletions velocity_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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 <forward_command_controller_userdoc>` 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 <forward_command_controller_userdoc>`, 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

0 comments on commit 9de3778

Please sign in to comment.