Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[JTC] Import docs from wiki.ros.org (backport #566) #634

Merged
merged 2 commits into from
May 31, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
183 changes: 126 additions & 57 deletions joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,23 +5,50 @@
joint_trajectory_controller
===========================

Controller for executing joint-space trajectories on a group of joints. Trajectories are specified as a set of waypoints to be reached at specific time instants, which the controller attempts to execute as well as the mechanism allows. Waypoints consist of positions, and optionally velocities and accelerations.
Controller for executing joint-space trajectories on a group of joints.
The controller interpolates in time between the points so that their distance can be arbitrary.
Even trajectories with only one point are accepted.
Trajectories are specified as a set of waypoints to be reached at specific time instants,
which the controller attempts to execute as well as the mechanism allows.
Waypoints consist of positions, and optionally velocities and accelerations.

Trajectory representation
-------------------------

The controller is templated to work with multiple trajectory representations. By default, a spline interpolator is provided, but it's possible to support other representations. The spline interpolator uses the following interpolation strategies depending on the waypoint specification:
*Parts of this documentation were originally published in the ROS 1 wiki under the* `CC BY 3.0 license <http://creativecommons.org/licenses/by/3.0/>`_. *Citations are given in the respective section, but were adapted for the ROS 2 implementation.* [#f1]_ [#f2]_

Trajectory representation [#f1]_
---------------------------------

Trajectories are represented internally with ``trajectory_msgs/msg/JointTrajectory`` data structure.
By default, a spline interpolator is provided, but it's possible to support other representations.
The spline interpolator uses the following interpolation strategies depending on the waypoint specification:

* Linear: Only position is specified. Guarantees continuity at the position level. Discouraged because it yields trajectories with discontinuous velocities at the waypoints.

* Cubic: Position and velocity are specified. Guarantees continuity at the velocity level.

* Quintic: Position, velocity and acceleration are specified: Guarantees continuity at the acceleration level.

Hardware interface type
-----------------------
Hardware interface type [#f1]_
-------------------------------

Currently joints with position, velocity, acceleration, and effort interfaces are supported. The joints can have one or more command interfaces, where the following control laws are applied at the same time:

* For command interfaces ``position``, the desired positions are simply forwarded to the joints,
* For command interfaces ``acceleration``, desired accelerations are simply forwarded to the joints.
* For ``velocity`` (``effort``) command interfaces, the position+velocity trajectory following error is mapped to ``velocity`` (``effort``) commands through a PID loop (:ref:`parameters`).

This leads to the the following allowed combinations of command and state interfaces:

The controller is templated to work with multiple hardware interface types. Currently joints with position, velocity and effort interfaces are supported. For position-controlled joints, desired positions are simply forwarded to the joints; while for velocity (effort) joints, the position+velocity trajectory following error is mapped to velocity (effort) commands through a PID loop. Example controller configurations can be found here.
* With command interface ``position``, there are no restrictions for state interfaces.
* With command interface ``velocity``:

* if command interface ``velocity`` is the only one, state interfaces must include ``position, velocity`` .
* no restrictions otherwise.

* With command interface ``effort``, state interfaces must include ``position, velocity``.
* With command interface ``acceleration``, there are no restrictions for state interfaces.

Example controller configurations can be found :ref:`below <ROS 2 interface>`.

Similarly to the trajectory representation case above, it's possible to support new hardware interfaces, or alternative mappings to an already supported interface (eg. a proxy controller for generating effort commands).

Expand All @@ -34,27 +61,6 @@ Other features

* Robust to system clock changes: Discontinuous system clock changes do not cause discontinuities in the execution of already queued trajectory segments.

ros2_control 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/master/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
^^^^^^^^^


Using Joint Trajectory Controller(s)
------------------------------------
Expand Down Expand Up @@ -104,6 +110,17 @@ A yaml file for using it could be:
goal: 0.03


Preemption policy [#f1]_
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Only one action goal can be active at any moment, or none if the topic interface is used. Path and goal tolerances are checked only for the trajectory segments of the active goal.

When an active action goal is preempted by another command coming from the action interface, the goal is canceled and the client is notified.

Sending an empty trajectory message from the topic interface (not the action interface) will override the current action goal and not abort the action.

.. _parameters:

Details about parameters
^^^^^^^^^^^^^^^^^^^^^^^^

Expand Down Expand Up @@ -201,17 +218,87 @@ gains.<joint_name>.ff_velocity_scale (double)

Default: 0.0

ROS2 interface of the controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
gains.<joint_name>.normalize_error (bool)
If true, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`.
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
position :math:`s` from the state interface. Use this for revolute joints without end stop,
where the shortest rotation to the target position is the desired motion.

Default: false


.. _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/master/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:

~/joint_trajectory (input topic) [trajectory_msgs::msg::JointTrajectory]
Topic for commanding the controller.
* via action, see :ref:`actions <Actions>`
* via topic, see :ref:`subscriber <Subscriber>`

~/controller_state (output topic) [control_msgs::msg::JointTrajectoryControllerState]
Topic publishing internal states.
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``.

~/follow_joint_trajectory (action server) [control_msgs::action::FollowJointTrajectory]
Action server for commanding the controller.
.. _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


Specialized versions of JointTrajectoryController (TBD in ...)
Expand All @@ -223,26 +310,8 @@ The following version of the Joint Trajectory Controller are available mapping t

* position_controllers::JointTrajectoryController

* Input: position, [velocity, [acceleration]]
* Output: position

* position_velocity_controllers::JointTrajectoryController

* Input: position, [velocity, [acceleration]]
* Output: position and velocity

* position_velocity_acceleration_controllers::JointTrajectoryController

* Input: position, [velocity, [acceleration]]
* Output: position, velocity and acceleration

.. * velocity_controllers::JointTrajectoryController
.. * Input: position, [velocity, [acceleration]]
.. * Output: velocity
.. TODO(anyone): would it be possible to output velocty and acceleration?
.. (to have an vel_acc_controllers)
.. * effort_controllers::JointTrajectoryController
.. * Input: position, [velocity, [acceleration]]
.. * Output: effort
.. rubric:: Footnote

(*Not implemented yet*) When using pure ``velocity`` or ``effort`` controllers a command is generated using the desired state and state error using a velocity feedforward term plus a corrective PID term. (#171)
.. [#f1] Adolfo Rodriguez: `joint_trajectory_controller <http://wiki.ros.org/joint_trajectory_controller>`_
.. [#f2] Adolfo Rodriguez: `Understanding trajectory replacement <http://wiki.ros.org/joint_trajectory_controller/UnderstandingTrajectoryReplacement>`_
Loading