Skip to content

Commit

Permalink
Let sphinx add parameter description with nested structures to docume…
Browse files Browse the repository at this point in the history
…ntation (backport #652) (#1005)
  • Loading branch information
mergify[bot] committed Feb 19, 2024
1 parent 6c1fe34 commit 0cfe23e
Show file tree
Hide file tree
Showing 15 changed files with 204 additions and 254 deletions.
10 changes: 7 additions & 3 deletions admittance_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,14 @@ ROS 2 interface of the controller
Parameters
^^^^^^^^^^^

The admittance controller's uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.
The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/admittance_controller/src/admittance_controller_parameters.yaml>`_ contains descriptions for all the parameters used by the controller.
An example parameter file can be found in the `test folder of the controller <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/admittance_controller/test/test_params.yaml>`_
The admittance controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters. The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/admittance_controller/src/admittance_controller_parameters.yaml>`_ contains descriptions for all the parameters used by the controller.

.. generate_parameter_library_details:: ../src/admittance_controller_parameters.yaml

An example parameter file for this controller can be found in `the test folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/admittance_controller/test/test_params.yaml>`_:

.. literalinclude:: ../test/test_params.yaml
:language: yaml

Topics
^^^^^^^
Expand Down
9 changes: 9 additions & 0 deletions diff_drive_controller/doc/parameters_context.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
linear.x: |
Joint limits structure for the linear ``x``-axis.
The limiter ignores position limits.
For details see ``joint_limits`` package from ros2_control repository.
angular.z: |
Joint limits structure for the rotation about ``z``-axis.
The limiter ignores position limits.
For details see ``joint_limits`` package from ros2_control repository.
17 changes: 6 additions & 11 deletions diff_drive_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -67,17 +67,12 @@ Publishers
Parameters
,,,,,,,,,,,,

Check `parameter definition file for details <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/diff_drive_controller/src/diff_drive_controller_parameter.yaml>`_.
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters. The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/diff_drive_controller/src/diff_drive_controller_parameter.yaml>`_ contains descriptions for all the parameters used by the controller.

Note that the documentation on parameters for joint limits can be found in `their header file <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/joint_limits/include/joint_limits/joint_limits_rosparam.hpp#L56-L75>`_.
Those parameters are:
.. generate_parameter_library_details:: ../src/diff_drive_controller_parameter.yaml
parameters_context.yaml

linear.x [JointLimits structure]
Joint limits structure for the linear X-axis.
The limiter ignores position limits.
For details see ``joint_limits`` package from ros2_control repository.
An example parameter file for this controller can be found in `the test directory <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/diff_drive_controller/test/config/test_diff_drive_controller.yaml>`_:

angular.z [JointLimits structure]
Joint limits structure for the rotation about Z-axis.
The limiter ignores position limits.
For details see ``joint_limits`` package from ros2_control repository.
.. literalinclude:: ../test/config/test_diff_drive_controller.yaml
:language: yaml
12 changes: 12 additions & 0 deletions force_torque_sensor_broadcaster/doc/parameters_context.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
interface_names: |
(optional) Defines custom, per axis interface names.
This is used if different prefixes, i.e., sensor name, or non-standard interface names are used.
It is sufficient that only one ``interface_name`` is defined.
This enables the broadcaster to use force sensing cells with less than six measuring axes.
An example definition is:
.. code-block:: yaml
interface_names:
force:
x: example_name/example_interface
26 changes: 9 additions & 17 deletions force_torque_sensor_broadcaster/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -12,25 +12,17 @@ The controller is a wrapper around ``ForceTorqueSensor`` semantic component (see

Parameters
^^^^^^^^^^^
The interfaces can be defined in two ways, using ``sensor_name`` or ``interface_names`` parameter.
Those two parameters can not be defined at the same time
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters. The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/force_torque_sensor_broadcaster/src/force_torque_sensor_broadcaster_parameters.yaml>`_ contains descriptions for all the parameters used by the controller.

frame_id (mandatory)
Frame in which the output message will be published.
The interfaces can be defined in two ways, using the ``sensor_name`` or the ``interface_names`` parameter:
Those two parameters cannot be defined at the same time.

sensor_name (optional)
Defines sensor name used as prefix for its interfaces.
If used standard interface names for a 6D FTS will be used: <sensor_name>/force.x, ..., <sensor_name>/torque.z.
Full list of parameters:

interface_names.[force|torque].[x|y|z] (optional)
Defines custom, per axis interface names.
This is used if different prefixes, i.e., sensor name, or non-standard interface names are used.
It is sufficient that only one ``interface_name`` is defined.
This enables broadcaster use for force sensing cells with less then six measuring axes.
Example definition is:
.. generate_parameter_library_details:: ../src/force_torque_sensor_broadcaster_parameters.yaml
parameters_context.yaml

.. code-block:: yaml
An example parameter file for this controller can be found in `the test directory <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/force_torque_sensor_broadcaster/test/force_torque_sensor_broadcaster_params.yaml>`_:

interface_names:
force:
x: example_name/example_interface
.. literalinclude:: ../test/force_torque_sensor_broadcaster_params.yaml
:language: yaml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,8 @@ force_torque_sensor_broadcaster:
sensor_name: {
type: string,
default_value: "",
description: "Name of the sensor used as prefix for interfaces if there are no individual interface names defined.",
description: "Name of the sensor used as prefix for interfaces if there are no individual interface names defined.
If used, standard interface names for a 6D FTS will be used: ``<sensor_name>/force.x, ..., <sensor_name>/torque.z``",
}
interface_names:
force:
Expand Down
17 changes: 15 additions & 2 deletions gripper_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,23 @@
Gripper Action Controller
--------------------------------

Controller for executing a gripper command action for simple single-dof grippers.
Controllers for executing a gripper command action for simple single-dof grippers:

- ``position_controllers/GripperActionController``
- ``effort_controllers/GripperActionController``

Parameters
^^^^^^^^^^^
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.
These controllers use the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters. The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/gripper_controllers/src/gripper_action_controller_parameters.yaml>`_ contains descriptions for all the parameters used by the controller.

List of parameters
=========================

.. generate_parameter_library_details:: ../src/gripper_action_controller_parameters.yaml


An example parameter file
=========================

.. generate_parameter_library_default::
../src/gripper_action_controller_parameters.yaml
13 changes: 12 additions & 1 deletion imu_sensor_broadcaster/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,17 @@ The controller is a wrapper around ``IMUSensor`` semantic component (see ``contr

Parameters
^^^^^^^^^^^
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters. The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/imu_sensor_broadcaster/src/imu_sensor_broadcaster_parameters.yaml>`_ contains descriptions for all the parameters used by the controller.

List of parameters
=========================
.. generate_parameter_library_details:: ../src/imu_sensor_broadcaster_parameters.yaml


An example parameter file
=========================

An example parameter file for this controller can be found in `the test directory <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/imu_sensor_broadcaster/test/imu_sensor_broadcaster_params.yaml>`_:

.. literalinclude:: ../test/imu_sensor_broadcaster_params.yaml
:language: yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
map_interface_to_joint_state: |
Optional parameter (map) providing mapping between custom interface names to standard fields in ``joint_states`` message.
Usecases:
#. Hydraulics robots where feedback and commanded values often have an offset and reliance on open-loop control is common.
Typically one would map both values in separate interfaces in the framework.
To visualize those data multiple joint_state_broadcaster instances and robot_state_publishers would be used to visualize both values in RViz.
#. A robot provides multiple measuring techniques for its joint values which results in slightly different values.
Typically one would use separate interface for providing those values in the framework.
Using multiple joint_state_broadcaster instances we could publish and show both in RViz.
Format (each line is optional):
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\tposition: <custom_interface>
\t\tvelocity: <custom_interface>
\t\teffort: <custom_interface>
Examples:
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\tposition: kf_estimated_position
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\tvelocity: derived_velocity
\t\teffort: derived_effort
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\teffort: torque_sensor
.. code-block:: yaml
\tmap_interface_to_joint_state:
\t\teffort: current_sensor
71 changes: 10 additions & 61 deletions joint_state_broadcaster/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -22,70 +22,19 @@ If none of the requested interface are not defined, the controller returns error

Parameters
----------
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters. The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/joint_state_broadcaster/src/joint_state_broadcaster_parameters.yaml>`_ contains descriptions for all the parameters used by the controller.

use_local_topics
Optional parameter (boolean; default: ``False``) defining if ``joint_states`` and ``dynamic_joint_states`` messages should be published into local namespace, e.g., ``/my_state_broadcaster/joint_states``.

List of parameters
,,,,,,,,,,,,,,,,,,

joints
Optional parameter (string array) to support broadcasting of only specific joints and interfaces.
It has to be used in combination with the ``interfaces`` parameter.
Joint state broadcaster asks for access to all defined interfaces on all defined joints.
.. generate_parameter_library_details::
../src/joint_state_broadcaster_parameters.yaml
joint_state_broadcaster_parameter_context.yml


interfaces
Optional parameter (string array) to support broadcasting of only specific joints and interfaces.
It has to be used in combination with the ``joints`` parameter.
An example parameter file
,,,,,,,,,,,,,,,,,,,,,,,,,


extra_joints
Optional parameter (string array) with names of extra joints to be added to ``joint_states`` and ``dynamic_joint_states`` with state set to 0.


map_interface_to_joint_state
Optional parameter (map) providing mapping between custom interface names to standard fields in ``joint_states`` message.
Usecases:

1. Hydraulics robots where feedback and commanded values often have an offset and reliance on open-loop control is common.
Typically one would map both values in separate interfaces in the framework.
To visualize those data multiple joint_state_broadcaster instances and robot_state_publishers would be used to visualize both values in RViz.

1. A robot provides multiple measuring techniques for its joint values which results in slightly different values.
Typically one would use separate interface for providing those values in the framework.
Using multiple joint_state_broadcaster instances we could publish and show both in RViz.

Format (each line is optional):

.. code-block:: yaml
map_interface_to_joint_state:
position: <custom_interface>
velocity: <custom_interface>
effort: <custom_interface>
Examples:

.. code-block:: yaml
map_interface_to_joint_state:
position: kf_estimated_position
.. code-block:: yaml
map_interface_to_joint_state:
velocity: derived_velocity
effort: derived_effort
.. code-block:: yaml
map_interface_to_joint_state:
effort: torque_sensor
.. code-block:: yaml
map_interface_to_joint_state:
effort: current_sensor
.. generate_parameter_library_default::
../src/joint_state_broadcaster_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,18 +2,29 @@ joint_state_broadcaster:
use_local_topics: {
type: bool,
default_value: false,
description: "Defining if ``joint_states`` and ``dynamic_joint_states`` messages should be published into local namespace, e.g., ``/my_state_broadcaster/joint_states``."
}
joints: {
type: string_array,
default_value: [],
description: "Parameter to support broadcasting of only specific joints and interfaces.
It has to be used in combination with the ``interfaces`` parameter.
If either ``joints`` or ``interfaces`` is left empty, all available state interfaces will be
published.
Joint state broadcaster asks for access to all defined interfaces on all defined joints."
}
extra_joints: {
type: string_array,
default_value: [],
description: "Names of extra joints to be added to ``joint_states`` and ``dynamic_joint_states`` with state set to 0."
}
interfaces: {
type: string_array,
default_value: [],
description: "Parameter to support broadcasting of only specific joints and interfaces.
It has to be used in combination with the ``joints`` parameter.
If either ``joints`` or ``interfaces`` is left empty, all available state interfaces will be
published."
}
map_interface_to_joint_state:
position: {
Expand Down
Loading

0 comments on commit 0cfe23e

Please sign in to comment.