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] Update requirements of state interfaces (backport #798) #799

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
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
20 changes: 19 additions & 1 deletion joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,19 @@ Waypoints consist of positions, and optionally velocities and accelerations.
Hardware interface type [#f1]_
-------------------------------

<<<<<<< HEAD
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:
=======
Currently, joints with hardware interface types ``position``, ``velocity``, ``acceleration``, and ``effort`` (defined `here <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp>`_) are supported in the following combinations as command interfaces:

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

This means that the joints can have one or more command interfaces, where the following control laws are applied at the same time:
>>>>>>> c831b6c (Update requirements of state interfaces (#798))

* 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.
Expand All @@ -29,11 +41,17 @@ This leads to the the following allowed combinations of command and state interf
* 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.

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

Further restrictions of state interfaces exist:

* ``velocity`` state interface cannot be used if ``position`` interface is missing.
* ``acceleration`` state interface cannot be used if ``position`` and ``velocity`` interfaces are not present."

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 Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ tl::expected<void, std::string> command_interface_type_combinations(
{
return tl::make_unexpected(
"'velocity' command interface can be used either alone or 'position' "
"interface has to be present");
"command interface has to be present");
}

if (
Expand All @@ -52,7 +52,7 @@ tl::expected<void, std::string> command_interface_type_combinations(
{
return tl::make_unexpected(
"'acceleration' command interface can only be used if 'velocity' and "
"'position' interfaces are present");
"'position' command interfaces are present");
}

if (
Expand Down