Skip to content

Commit

Permalink
Updated docs
Browse files Browse the repository at this point in the history
  • Loading branch information
vlad-touchlab committed Jul 11, 2024
1 parent e630961 commit bcbac7a
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 1 deletion.
2 changes: 2 additions & 0 deletions joint_trajectory_controller/doc/trajectory.rst
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@ The spline interpolator uses the following interpolation strategies depending on

Trajectories with velocity fields only, velocity and acceleration only, or acceleration fields only can be processed and are accepted, if ``allow_integration_in_goal_trajectories`` is true. Position (and velocity) is then integrated from velocity (or acceleration, respectively) by Heun's method.

Effort trajectories are allowed for controllers that claim the ``effort`` command interface and they are treated as feed-forward effort that is added to the position feedback. Effort is handled separately from position, velocity and acceleration. We use linear interpolation for effort when the ``spline`` interpolation method is selected.

Visualized Examples
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
To visualize the difference of the different interpolation methods and their inputs, different trajectories defined at a 0.5s grid and are sampled at a rate of 10ms.
Expand Down
5 changes: 4 additions & 1 deletion joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,15 @@ Currently, joints with hardware interface types ``position``, ``velocity``, ``ac
* ``position``, ``velocity``, ``acceleration``
* ``velocity``
* ``effort``
* ``position``, ``effort``

This means that 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 if it is configured (:ref:`parameters`).
* For ``effort`` command interface (without ``position`` command interface), if the trajectory contains effort, this will be added to the PID commands as a feed forward effort.
* For ``position, effort`` command interface, if the trajectory contains effort, this will be passed directly to the ``effort`` interface (PID won't be used) while the positions will be passed to the ``position`` interface.

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

Expand All @@ -38,7 +41,7 @@ This leads to the following allowed combinations of command and state interfaces

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

* With command interface ``effort``, state interfaces must include ``position, velocity``.
* With command interface ``effort`` or ``position, effort``, state interfaces must include ``position, velocity``.

* With command interface ``acceleration``, state interfaces must include ``position, velocity``.

Expand Down

0 comments on commit bcbac7a

Please sign in to comment.