Skip to content

Commit

Permalink
Merge branch 'master' into jtc/dynamic_parameters
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored Sep 25, 2023
2 parents 1e94b12 + 79c6d1c commit aea166f
Show file tree
Hide file tree
Showing 56 changed files with 469 additions and 67 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci-coverage-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ jobs:
file: ros_ws/lcov/total_coverage.info
flags: unittests
name: codecov-umbrella
- uses: actions/[email protected].2
- uses: actions/[email protected].3
with:
name: colcon-logs-coverage-rolling
path: ros_ws/log
2 changes: 1 addition & 1 deletion .github/workflows/reusable-ros-tooling-source-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ jobs:
https://raw.githubusercontent.com/ros2/ros2/${{ inputs.ros2_repo_branch }}/ros2.repos
https://raw.githubusercontent.com/${{ github.repository }}/${{ github.sha }}/ros2_controllers.${{ inputs.ros_distro }}.repos?token=${{ secrets.GITHUB_TOKEN }}
colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml
- uses: actions/[email protected].2
- uses: actions/[email protected].3
with:
name: colcon-logs-ubuntu-22.04
path: ros_ws/log
3 changes: 3 additions & 0 deletions ackermann_steering_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ackermann_steering_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------

3.15.0 (2023-09-11)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion ackermann_steering_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ackermann_steering_controller</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>Steering controller for Ackermann kinematics. Rear fixed wheels are powering the vehicle and front wheels are steering it.</description>
<license>Apache License 2.0</license>
<maintainer email="[email protected]">Bence Magyar</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions admittance_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package admittance_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------

3.15.0 (2023-09-11)
-------------------
* Update docs for diff drive controller (`#751 <https://github.com/ros-controls/ros2_controllers/issues/751>`_)
Expand Down
2 changes: 1 addition & 1 deletion admittance_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>admittance_controller</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>Implementation of admittance controllers for different input and output interface.</description>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Bence Magyar</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions bicycle_steering_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package bicycle_steering_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------

3.15.0 (2023-09-11)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion bicycle_steering_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>bicycle_steering_controller</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>Steering controller with bicycle kinematics. Rear fixed wheel is powering the vehicle and front wheel is steering.</description>
<license>Apache License 2.0</license>
<maintainer email="[email protected]">Bence Magyar</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions diff_drive_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package diff_drive_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------

3.15.0 (2023-09-11)
-------------------
* Update docs for diff drive controller (`#751 <https://github.com/ros-controls/ros2_controllers/issues/751>`_)
Expand Down
2 changes: 1 addition & 1 deletion diff_drive_controller/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>diff_drive_controller</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>Controller for a differential drive mobile base.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Jordan Palacios</maintainer>
Expand Down
5 changes: 5 additions & 0 deletions effort_controllers/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package effort_controllers
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------
* [Doc] Add specific documentation on the available fw cmd controllers (`#765 <https://github.com/ros-controls/ros2_controllers/issues/765>`_)
* Contributors: Christoph Fröhlich

3.15.0 (2023-09-11)
-------------------

Expand Down
40 changes: 37 additions & 3 deletions effort_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,41 @@ effort_controllers

This is a collection of controllers that work using the "effort" joint command interface but may accept different joint-level commands at the controller level, e.g. controlling the effort on a certain joint to achieve a set position.

Hardware interface type
-----------------------
The package contains the following controllers:

These controllers work with joints using the "effort" command interface.
effort_controllers/JointGroupEffortController
-------------------------------------------------

This is specialization of the :ref:`forward_command_controller <forward_command_controller_userdoc>` that works using the "effort" joint interface.


ROS 2 interface of the controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Topics
,,,,,,,,,,,,,,,,,,

~/commands (input topic) [std_msgs::msg::Float64MultiArray]
Joints' effort commands


Parameters
,,,,,,,,,,,,,,,,,,
This controller overrides the interface parameter from :ref:`forward_command_controller <forward_command_controller_userdoc>`, and the
``joints`` parameter is the only one that is required.

An example parameter file is given here

.. code-block:: yaml
controller_manager:
ros__parameters:
update_rate: 100 # Hz
effort_controller:
type: effort_controllers/JointGroupEffortController
effort_controller:
ros__parameters:
joints:
- slider_to_cart
2 changes: 1 addition & 1 deletion effort_controllers/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>effort_controllers</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>Generic controller for forwarding commands.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Jordan Palacios</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions force_torque_sensor_broadcaster/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package force_torque_sensor_broadcaster
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------

3.15.0 (2023-09-11)
-------------------
* [ForceTorqueSensorBroadcaster] Create ParamListener and get parameters on configure (`#698 <https://github.com/ros-controls/ros2_controllers/issues/698>`_)
Expand Down
2 changes: 1 addition & 1 deletion force_torque_sensor_broadcaster/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>force_torque_sensor_broadcaster</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>Controller to publish state of force-torque sensors.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
5 changes: 5 additions & 0 deletions forward_command_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package forward_command_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------
* [Doc] Add specific documentation on the available fw cmd controllers (`#765 <https://github.com/ros-controls/ros2_controllers/issues/765>`_)
* Contributors: Christoph Fröhlich

3.15.0 (2023-09-11)
-------------------

Expand Down
12 changes: 11 additions & 1 deletion forward_command_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,18 @@ Hardware interface type

This controller can be used for every type of command interface.


ROS 2 interface of the controller
---------------------------------

Topics
^^^^^^^

~/commands (input topic) [std_msgs::msg::Float64MultiArray]
Target joint commands

Parameters
------------
^^^^^^^^^^^^^^

This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.

Expand Down
2 changes: 1 addition & 1 deletion forward_command_controller/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>forward_command_controller</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>Generic controller for forwarding commands.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Jordan Palacios</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions gripper_controllers/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package gripper_controllers
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------

3.15.0 (2023-09-11)
-------------------
* Add test for effort gripper controller (`#769 <https://github.com/ros-controls/ros2_controllers/issues/769>`_)
Expand Down
2 changes: 1 addition & 1 deletion gripper_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>gripper_controllers</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>The gripper_controllers package</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>

Expand Down
3 changes: 3 additions & 0 deletions imu_sensor_broadcaster/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package imu_sensor_broadcaster
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------

3.15.0 (2023-09-11)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion imu_sensor_broadcaster/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>imu_sensor_broadcaster</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>Controller to publish readings of IMU sensors.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions joint_state_broadcaster/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package joint_state_broadcaster
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------

3.15.0 (2023-09-11)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion joint_state_broadcaster/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>joint_state_broadcaster</name>
<version>3.15.0</version>
<version>3.16.0</version>
<description>Broadcaster to publish joint state</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Stogl</maintainer>
Expand Down
9 changes: 9 additions & 0 deletions joint_trajectory_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,15 @@
Changelog for package joint_trajectory_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.16.0 (2023-09-20)
-------------------
* [Docs] Improve interface description of JTC (`#770 <https://github.com/ros-controls/ros2_controllers/issues/770>`_)
* [JTC] Add time-out for trajectory interfaces (`#609 <https://github.com/ros-controls/ros2_controllers/issues/609>`_)
* [JTC] Rename parameter: normalize_error to angle_wraparound (`#772 <https://github.com/ros-controls/ros2_controllers/issues/772>`_)
* [JTC] Fix hold position mode with goal_time>0 (`#758 <https://github.com/ros-controls/ros2_controllers/issues/758>`_)
* [JTC] Add note on goal_time=0 in docs (`#773 <https://github.com/ros-controls/ros2_controllers/issues/773>`_)
* Contributors: Christoph Fröhlich

3.15.0 (2023-09-11)
-------------------
* [JTC] Make most parameters read-only (`#771 <https://github.com/ros-controls/ros2_controllers/issues/771>`_)
Expand Down
20 changes: 16 additions & 4 deletions joint_trajectory_controller/doc/parameters.rst
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,16 @@ allow_nonzero_velocity_at_trajectory_end (boolean)

Default: true

cmd_timeout (double)
Timeout after which the input command is considered stale.
Timeout is counted from the end of the trajectory (the last point).
``cmd_timeout`` must be greater than ``constraints.goal_time``,
otherwise ignored.

If zero, timeout is deactivated"

Default: 0.0

constraints (structure)
Default values for tolerances if no explicit values are states in JointTrajectory message.

Expand Down Expand Up @@ -102,7 +112,7 @@ gains (structure)
u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v)
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see below),
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see ``angle_wraparound`` below),
the controller period :math:`dt`, and the ``velocity`` or ``effort`` manipulated variable (control variable) :math:`u`, respectively.

gains.<joint_name>.p (double)
Expand Down Expand Up @@ -130,10 +140,12 @@ gains.<joint_name>.ff_velocity_scale (double)

Default: 0.0

gains.<joint_name>.normalize_error (bool)
gains.<joint_name>.angle_wraparound (bool)
For joints that wrap around (without end stop, ie. are continuous),
where the shortest rotation to the target position is the desired motion.
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.
position :math:`s` from the state interface.


Default: false
27 changes: 13 additions & 14 deletions joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -14,16 +14,24 @@ Waypoints consist of positions, and optionally velocities and accelerations.

*Parts of this documentation were originally published in the ROS 1 wiki under the* `CC BY 3.0 license <https://creativecommons.org/licenses/by/3.0/>`_. *Citations are given in the respective section, but were adapted for the ROS 2 implementation.* [#f1]_

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

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:

* ``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:

* 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`).
* 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`).

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

* With command interface ``position``, there are no restrictions for state interfaces.
* With command interface ``velocity``:
Expand All @@ -32,12 +40,9 @@ This leads to the the following allowed combinations of command and state interf
* 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).

Other features
--------------

Expand Down Expand Up @@ -118,14 +123,8 @@ 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``
Legal combinations of state interfaces are given in section `Hardware Interface Types`_.

Commands
,,,,,,,,,
Expand Down
Loading

0 comments on commit aea166f

Please sign in to comment.