From c0eb3d7a03a3da9c0f7471debfef8ec45025dbcf Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 16 Oct 2023 12:58:44 +0200 Subject: [PATCH] Update requirements of state interfaces (#798) (cherry picked from commit c831b6cee52886bf3e93300b63f7b8d9e3566bb4) # Conflicts: # joint_trajectory_controller/doc/userdoc.rst --- joint_trajectory_controller/doc/userdoc.rst | 20 ++++++++++++++++++- .../validate_jtc_parameters.hpp | 4 ++-- 2 files changed, 21 insertions(+), 3 deletions(-) diff --git a/joint_trajectory_controller/doc/userdoc.rst b/joint_trajectory_controller/doc/userdoc.rst index 92f0f9629d..4bbe0446d7 100644 --- a/joint_trajectory_controller/doc/userdoc.rst +++ b/joint_trajectory_controller/doc/userdoc.rst @@ -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 `_) 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. @@ -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 `. 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). diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp index 6c909e3278..0b22c7cdd9 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp @@ -42,7 +42,7 @@ tl::expected 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 ( @@ -52,7 +52,7 @@ tl::expected 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 (