Skip to content

Commit

Permalink
Use branch name substitution for all links (#618)
Browse files Browse the repository at this point in the history
(cherry picked from commit aece974)

# Conflicts:
#	joint_trajectory_controller/doc/userdoc.rst
  • Loading branch information
christophfroehlich authored and mergify[bot] committed May 30, 2023
1 parent a3d07e7 commit 3a2f34e
Show file tree
Hide file tree
Showing 13 changed files with 96 additions and 21 deletions.
12 changes: 6 additions & 6 deletions admittance_controller/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/admittance_controller/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/admittance_controller/doc/userdoc.rst

.. _admittance_controller_userdoc:

Expand All @@ -18,8 +18,8 @@ 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/master/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/master/admittance_controller/test/test_params.yaml>`_
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>`_


Topics
Expand All @@ -44,14 +44,14 @@ The controller has ``position`` and ``velocity`` reference interfaces exported i
States
^^^^^^^
The state interfaces are defined with ``joints`` and ``state_interfaces`` parameters as follows: ``<joint>/<state_interface>``.
Supported state interfaces are ``position``, ``velocity``, and ``acceleration`` as defined in the `hardware_interface/hardware_interface_type_values.hpp <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp>`_.
Supported state interfaces are ``position``, ``velocity``, and ``acceleration`` as defined in the `hardware_interface/hardware_interface_type_values.hpp <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp>`_.
If some interface is not provided, the last commanded interface will be used for calculation.

For handling TCP wrenches `*Force Torque Sensor* semantic component (from package *controller_interface*) <https://github.com/ros-controls/ros2_control/blob/master/controller_interface/include/semantic_components/force_torque_sensor.hpp>`_ is used.
For handling TCP wrenches `*Force Torque Sensor* semantic component (from package *controller_interface*) <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/controller_interface/include/semantic_components/force_torque_sensor.hpp>`_ is used.
The interfaces have prefix ``ft_sensor.name``, building the interfaces: ``<sensor_name>/[force.x|force.y|force.z|torque.x|torque.y|torque.z]``.


Commands
^^^^^^^^^
The command interfaces are defined with ``joints`` and ``command_interfaces`` parameters as follows: ``<joint>/<command_interface>``.
Supported state interfaces are ``position``, ``velocity``, and ``acceleration`` as defined in the `hardware_interface/hardware_interface_type_values.hpp <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp>`_.
Supported state interfaces are ``position``, ``velocity``, and ``acceleration`` as defined in the `hardware_interface/hardware_interface_type_values.hpp <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp>`_.
6 changes: 3 additions & 3 deletions diff_drive_controller/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/diff_drive_controller/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/diff_drive_controller/doc/userdoc.rst

.. _diff_drive_controller_userdoc:

Expand Down Expand Up @@ -72,9 +72,9 @@ Services
Parameters
------------

Check `parameter definition file for details <https://github.com/ros-controls/ros2_controllers/blob/master/diff_drive_controller/src/diff_drive_controller_parameter.yaml>`_.
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>`_.

Note that the documentation on parameters for joint limits can be found in `their header file <https://github.com/ros-controls/ros2_control/blob/master/joint_limits/include/joint_limits/joint_limits_rosparam.hpp#L56-L75>`_.
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:

linear.x [JointLimits structure]
Expand Down
4 changes: 2 additions & 2 deletions doc/controllers_index.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/doc/controllers_index.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/doc/controllers_index.rst

.. _controllers:

Expand All @@ -22,7 +22,7 @@ The controllers' namespaces are commanding the following command interface types
- ``effort_controllers``: ``hardware_interface::HW_IF_EFFORT``
- ...

.. _common hardware interface definitions: https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp
.. _common hardware interface definitions: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp



Expand Down
2 changes: 1 addition & 1 deletion doc/writing_new_controller.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/doc/writing_new_controller.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/doc/writing_new_controller.rst

.. _writing_new_controllers:

Expand Down
2 changes: 1 addition & 1 deletion effort_controllers/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/effort_controllers/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/effort_controllers/doc/userdoc.rst

.. _effort_controllers_userdoc:

Expand Down
2 changes: 1 addition & 1 deletion force_torque_sensor_broadcaster/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/force_torque_sensor_broadcaster/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/force_torque_sensor_broadcaster/doc/userdoc.rst

.. _force_torque_sensor_broadcaster_userdoc:

Expand Down
2 changes: 1 addition & 1 deletion forward_command_controller/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/forward_command_controller/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/forward_command_controller/doc/userdoc.rst

.. _forward_command_controller_userdoc:

Expand Down
2 changes: 1 addition & 1 deletion imu_sensor_broadcaster/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/imu_sensor_broadcaster/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/imu_sensor_broadcaster/doc/userdoc.rst

.. _imu_sensor_broadcaster_userdoc:

Expand Down
2 changes: 1 addition & 1 deletion joint_state_broadcaster/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/joint_state_broadcaster/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/joint_state_broadcaster/doc/userdoc.rst

.. _joint_state_broadcaster_userdoc:

Expand Down
77 changes: 76 additions & 1 deletion joint_trajectory_controller/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/joint_trajectory_controller/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/joint_trajectory_controller/doc/userdoc.rst

.. _joint_trajectory_controller_userdoc:

Expand Down Expand Up @@ -210,8 +210,83 @@ ROS2 interface of the controller
~/controller_state (output topic) [control_msgs::msg::JointTrajectoryControllerState]
Topic publishing internal states.

<<<<<<< HEAD
~/follow_joint_trajectory (action server) [control_msgs::action::FollowJointTrajectory]
Action server for commanding the controller.
=======
.. _ROS 2 interface:

Description of controller's interfaces
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

References
,,,,,,,,,,,,,,,,,,

(the controller is not yet implemented as chainable controller)

States
,,,,,,,,,,,,,,,,,,

The state interfaces are defined with ``joints`` and ``state_interfaces`` parameters as follows: ``<joint>/<state_interface>``.
Supported state interfaces are ``position``, ``velocity``, ``acceleration`` and ``effort`` as defined in the `hardware_interface/hardware_interface_type_values.hpp <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp>`_.

Legal combinations of state interfaces are:

* ``position``
* ``position`` and ``velocity``
* ``position``, ``velocity`` and ``acceleration``
* ``effort``

Commands
,,,,,,,,,

There are two mechanisms for sending trajectories to the controller:

* via action, see :ref:`actions <Actions>`
* via topic, see :ref:`subscriber <Subscriber>`

Both use the ``trajectory_msgs/JointTrajectory`` message to specify trajectories, and require specifying values for all the controller joints (as opposed to only a subset) if ``allow_partial_joints_goal`` is not set to ``True``.

.. _Actions:

Actions [#f1]_
,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,

<controller_name>/follow_joint_trajectory [control_msgs::action::FollowJointTrajectory]
Action server for commanding the controller


The primary way to send trajectories is through the action interface, and should be favored when execution monitoring is desired.
Action goals allow to specify not only the trajectory to execute, but also (optionally) path and goal tolerances.
When no tolerances are specified, the defaults given in the parameter interface are used (see :ref:`parameters`).
If tolerances are violated during trajectory execution, the action goal is aborted, the client is notified, and the current position is held.

.. _Subscriber:

Subscriber [#f1]_
,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,

<controller_name>/joint_trajectory [trajectory_msgs::msg::JointTrajectory]
Topic for commanding the controller

The topic interface is a fire-and-forget alternative. Use this interface if you don't care about execution monitoring.
The controller's path and goal tolerance specification is not used in this case, as there is no mechanism to notify the sender about tolerance violations.
Note that although some degree of monitoring is available through the ``~/query_state`` service and ``~/state`` topic it is much more cumbersome to realize than with the action interface.


Publishers
,,,,,,,,,,,

<controller_name>/controller_state [control_msgs::msg::JointTrajectoryControllerState]
Topic publishing internal states with the update-rate of the controller manager


Services
,,,,,,,,,,,

<controller_name>/query_state [control_msgs::srv::QueryTrajectoryState]
Query controller state at any future time
>>>>>>> aece974 (Use branch name substitution for all links (#618))


Specialized versions of JointTrajectoryController (TBD in ...)
Expand Down
2 changes: 1 addition & 1 deletion position_controllers/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/position_controllers/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/position_controllers/doc/userdoc.rst

.. _position_controllers_userdoc:

Expand Down
2 changes: 1 addition & 1 deletion tricycle_controller/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/tricycle_controller/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/tricycle_controller/doc/userdoc.rst

.. _tricycle_controller_userdoc:

Expand Down
2 changes: 1 addition & 1 deletion velocity_controllers/doc/userdoc.rst
@@ -1,4 +1,4 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/|github_branch|/velocity_controllers/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/velocity_controllers/doc/userdoc.rst

.. _velocity_controllers_userdoc:

Expand Down

0 comments on commit 3a2f34e

Please sign in to comment.