Skip to content

Commit

Permalink
Merge branch 'master' into jtc/fix_state_offset_tests
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Nov 1, 2023
2 parents 85b23a7 + 6e46053 commit ae5bdbd
Show file tree
Hide file tree
Showing 54 changed files with 145 additions and 59 deletions.
20 changes: 18 additions & 2 deletions .github/workflows/ci-coverage-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,29 @@ jobs:
with:
required-ros-distributions: ${{ env.ROS_DISTRO }}
- uses: actions/checkout@v4
- uses: ros-tooling/[email protected].3
- uses: ros-tooling/[email protected].4
with:
target-ros2-distro: ${{ env.ROS_DISTRO }}
import-token: ${{ secrets.GITHUB_TOKEN }}
# build all packages listed in the meta package
# build all packages listed here
package-name:
ackermann_steering_controller
admittance_controller
bicycle_steering_controller
diff_drive_controller
effort_controllers
force_torque_sensor_broadcaster
forward_command_controller
gripper_controllers
imu_sensor_broadcaster
joint_state_broadcaster
joint_trajectory_controller
position_controllers
range_sensor_broadcaster
steering_controllers_library
tricycle_controller
tricycle_steering_controller
velocity_controllers

vcs-repo-file-url: |
https://raw.githubusercontent.com/${{ github.repository }}/${{ github.sha }}/ros2_controllers-not-released.${{ env.ROS_DISTRO }}.repos?token=${{ secrets.GITHUB_TOKEN }}
Expand Down
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 @@ -32,7 +32,7 @@ jobs:
- uses: actions/checkout@v4
with:
ref: ${{ inputs.ref }}
- uses: ros-tooling/[email protected].3
- uses: ros-tooling/[email protected].4
with:
target-ros2-distro: ${{ inputs.ros_distro }}
ref: ${{ inputs.ref }}
Expand Down
5 changes: 5 additions & 0 deletions ackermann_steering_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package ackermann_steering_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.17.0 (2023-10-31)
-------------------
* Improve docs (`#785 <https://github.com/ros-controls/ros2_controllers/issues/785>`_)
* Contributors: Christoph Fröhlich

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

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.16.0</version>
<version>3.17.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.17.0 (2023-10-31)
-------------------

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

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.16.0</version>
<version>3.17.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
5 changes: 5 additions & 0 deletions bicycle_steering_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package bicycle_steering_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.17.0 (2023-10-31)
-------------------
* Improve docs (`#785 <https://github.com/ros-controls/ros2_controllers/issues/785>`_)
* Contributors: Christoph Fröhlich

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

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.16.0</version>
<version>3.17.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
2 changes: 2 additions & 0 deletions codecov.yml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@ coverage:
patch: off
fixes:
- "ros_ws/src/ros2_controllers/::"
ignore:
- "**/test"
comment:
layout: "diff, flags, files"
behavior: default
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.17.0 (2023-10-31)
-------------------

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

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.16.0</version>
<version>3.17.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
3 changes: 3 additions & 0 deletions effort_controllers/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package effort_controllers
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.17.0 (2023-10-31)
-------------------

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>`_)
Expand Down
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.16.0</version>
<version>3.17.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.17.0 (2023-10-31)
-------------------

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

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.16.0</version>
<version>3.17.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
3 changes: 3 additions & 0 deletions forward_command_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package forward_command_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.17.0 (2023-10-31)
-------------------

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>`_)
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.16.0</version>
<version>3.17.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.17.0 (2023-10-31)
-------------------

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

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.16.0</version>
<version>3.17.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.17.0 (2023-10-31)
-------------------

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

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.16.0</version>
<version>3.17.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.17.0 (2023-10-31)
-------------------

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

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.16.0</version>
<version>3.17.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
7 changes: 7 additions & 0 deletions joint_trajectory_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,13 @@
Changelog for package joint_trajectory_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.17.0 (2023-10-31)
-------------------
* Cleanup comments and unnecessary checks (`#803 <https://github.com/ros-controls/ros2_controllers/issues/803>`_)
* Update requirements of state interfaces (`#798 <https://github.com/ros-controls/ros2_controllers/issues/798>`_)
* [JTC] Add tests for acceleration command interface (`#752 <https://github.com/ros-controls/ros2_controllers/issues/752>`_)
* Contributors: Christoph Fröhlich

3.16.0 (2023-09-20)
-------------------
* [Docs] Improve interface description of JTC (`#770 <https://github.com/ros-controls/ros2_controllers/issues/770>`_)
Expand Down
10 changes: 8 additions & 2 deletions joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ Waypoints consist of positions, and optionally velocities and accelerations.
Hardware interface types
-------------------------------

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:
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``
Expand All @@ -37,10 +37,16 @@ This leads to the following allowed combinations of command and 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``, 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>`.

Other features
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,15 +71,13 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
JointTrajectoryController();

/**
* @brief command_interface_configuration This controller requires the position command
* interfaces for the controlled joints
* @brief command_interface_configuration
*/
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
controller_interface::InterfaceConfiguration command_interface_configuration() const override;

/**
* @brief command_interface_configuration This controller requires the position and velocity
* state interfaces for the controlled joints
* @brief command_interface_configuration
*/
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,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 @@ -51,7 +51,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
2 changes: 1 addition & 1 deletion joint_trajectory_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>joint_trajectory_controller</name>
<version>3.16.0</version>
<version>3.17.0</version>
<description>Controller for executing joint-space trajectories on a group of joints</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Jordan Palacios</maintainer>
Expand Down
18 changes: 1 addition & 17 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -652,17 +652,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
// get parameters from the listener in case they were updated
params_ = param_listener_->get_params();

// Check if the DoF has changed
if ((dof_ > 0) && (params_.joints.size() != dof_))
{
RCLCPP_ERROR(
logger,
"The JointTrajectoryController does not support restarting with a different number of DOF");
// TODO(andyz): update vector lengths if num. joints did change and re-initialize them so we
// can continue
return CallbackReturn::FAILURE;
}

// get degrees of freedom
dof_ = params_.joints.size();

// TODO(destogl): why is this here? Add comment or move
Expand Down Expand Up @@ -692,12 +682,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
return CallbackReturn::FAILURE;
}

// // Specialized, child controllers set interfaces before calling configure function.
// if (command_interface_types_.empty())
// {
// command_interface_types_ = get_node()->get_parameter("command_interfaces").as_string_array();
// }

if (params_.command_interfaces.empty())
{
RCLCPP_ERROR(logger, "'command_interfaces' parameter is empty.");
Expand Down
3 changes: 3 additions & 0 deletions position_controllers/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package position_controllers
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.17.0 (2023-10-31)
-------------------

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>`_)
Expand Down
2 changes: 1 addition & 1 deletion position_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>position_controllers</name>
<version>3.16.0</version>
<version>3.17.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 range_sensor_broadcaster/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package range_sensor_broadcaster
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.17.0 (2023-10-31)
-------------------

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

Expand Down
2 changes: 1 addition & 1 deletion range_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>range_sensor_broadcaster</name>
<version>3.16.0</version>
<version>3.17.0</version>
<description>Controller to publish readings of Range sensors.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<author email="[email protected]">Florent Chretien</author>
Expand Down
Loading

0 comments on commit ae5bdbd

Please sign in to comment.