Skip to content

Commit

Permalink
Merge branch 'humble' into mergify/bp/humble/pr-434
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Jul 15, 2024
2 parents 5eb6df8 + 143bfc9 commit 9d78d2c
Show file tree
Hide file tree
Showing 68 changed files with 1,303 additions and 124 deletions.
8 changes: 4 additions & 4 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ repos:

# Python hooks
- repo: https://github.com/asottile/pyupgrade
rev: v3.15.2
rev: v3.16.0
hooks:
- id: pyupgrade
args: [--py36-plus]
Expand All @@ -56,14 +56,14 @@ repos:
args: ["--line-length=99"]

- repo: https://github.com/pycqa/flake8
rev: 7.0.0
rev: 7.1.0
hooks:
- id: flake8
args: ["--extend-ignore=E501"]

# CPP hooks
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v18.1.5
rev: v18.1.8
hooks:
- id: clang-format
args: ['-fallback-style=none', '-i']
Expand Down Expand Up @@ -133,7 +133,7 @@ repos:
exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$

- repo: https://github.com/python-jsonschema/check-jsonschema
rev: 0.28.4
rev: 0.28.6
hooks:
- id: check-github-workflows
args: ["--verbose"]
Expand Down
6 changes: 6 additions & 0 deletions ackermann_steering_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package ackermann_steering_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.0 (2024-07-09)
-------------------
* [Steering controllers library] Reference interfaces are body twist (`#1168 <https://github.com/ros-controls/ros2_controllers/issues/1168>`_) (`#1173 <https://github.com/ros-controls/ros2_controllers/issues/1173>`_)
* Fix steering controllers library code documentation and naming (`#1149 <https://github.com/ros-controls/ros2_controllers/issues/1149>`_) (`#1164 <https://github.com/ros-controls/ros2_controllers/issues/1164>`_)
* Contributors: mergify[bot]

2.35.0 (2024-05-22)
-------------------
* Add parameter check for geometric values (backport `#1120 <https://github.com/ros-controls/ros2_controllers/issues/1120>`_) (`#1125 <https://github.com/ros-controls/ros2_controllers/issues/1125>`_)
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>2.35.0</version>
<version>2.36.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
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfsTIME
// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size());
for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i)
Expand Down Expand Up @@ -173,6 +173,7 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic)
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
Expand Down Expand Up @@ -211,8 +212,9 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic_chained)
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
EXPECT_NEAR(

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
controller_->command_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
EXPECT_NEAR(
Expand Down Expand Up @@ -261,6 +263,7 @@ TEST_F(AckermannSteeringControllerTest, receive_message_and_publish_updated_stat
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
Expand All @@ -276,6 +279,7 @@ TEST_F(AckermannSteeringControllerTest, receive_message_and_publish_updated_stat

subscribe_and_get_messages(msg);

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
msg.linear_velocity_command[CMD_TRACTION_RIGHT_WHEEL], 0.22222222222222224, COMMON_THRESHOLD);
EXPECT_NEAR(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@ class AckermannSteeringControllerFixture : public ::testing::Test

std::array<double, 4> joint_state_values_ = {0.5, 0.5, 0.0, 0.0};
std::array<double, 4> joint_command_values_ = {1.1, 3.3, 2.2, 4.4};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.0 (2024-07-09)
-------------------

2.35.0 (2024-05-22)
-------------------

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

2.36.0 (2024-07-09)
-------------------
* [Steering controllers library] Reference interfaces are body twist (`#1168 <https://github.com/ros-controls/ros2_controllers/issues/1168>`_) (`#1173 <https://github.com/ros-controls/ros2_controllers/issues/1173>`_)
* Fix steering controllers library code documentation and naming (`#1149 <https://github.com/ros-controls/ros2_controllers/issues/1149>`_) (`#1164 <https://github.com/ros-controls/ros2_controllers/issues/1164>`_)
* Contributors: mergify[bot]

2.35.0 (2024-05-22)
-------------------
* Add parameter check for geometric values (backport `#1120 <https://github.com/ros-controls/ros2_controllers/issues/1120>`_) (`#1125 <https://github.com/ros-controls/ros2_controllers/issues/1125>`_)
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>2.35.0</version>
<version>2.36.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
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfsTIME
// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size());
for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i)
Expand Down Expand Up @@ -158,7 +158,7 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic)
controller_interface::return_type::OK);

EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.253221, COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.1 / 0.45, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
COMMON_THRESHOLD);
Expand Down Expand Up @@ -190,7 +190,7 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic_chained)
controller_interface::return_type::OK);

EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.253221, COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.1 / 0.45, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
COMMON_THRESHOLD);
Expand Down Expand Up @@ -237,22 +237,22 @@ TEST_F(BicycleSteeringControllerTest, receive_message_and_publish_updated_status
EXPECT_EQ(msg.linear_velocity_command[0], 1.1);
EXPECT_EQ(msg.steering_angle_command[0], 2.2);

publish_commands();
publish_commands(0.1, 0.2);
ASSERT_TRUE(controller_->wait_for_commands(executor));

ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);

EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.253221, COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.1 / 0.45, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
COMMON_THRESHOLD);

subscribe_and_get_messages(msg);

EXPECT_NEAR(msg.linear_velocity_command[0], 0.253221, COMMON_THRESHOLD);
EXPECT_NEAR(msg.linear_velocity_command[0], 0.1 / 0.45, COMMON_THRESHOLD);
EXPECT_NEAR(msg.steering_angle_command[0], 1.4179821977774734, COMMON_THRESHOLD);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ class BicycleSteeringControllerFixture : public ::testing::Test

std::array<double, 2> joint_state_values_ = {3.3, 0.5};
std::array<double, 2> joint_command_values_ = {1.1, 2.2};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
std::string steering_interface_name_ = "position";

// defined in setup
Expand Down
6 changes: 6 additions & 0 deletions diff_drive_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package diff_drive_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.0 (2024-07-09)
-------------------
* Add mobile robot kinematics 101 and improve steering library docs (`#954 <https://github.com/ros-controls/ros2_controllers/issues/954>`_) (`#1160 <https://github.com/ros-controls/ros2_controllers/issues/1160>`_)
* Bump version of pre-commit hooks (`#1157 <https://github.com/ros-controls/ros2_controllers/issues/1157>`_) (`#1158 <https://github.com/ros-controls/ros2_controllers/issues/1158>`_)
* Contributors: mergify[bot]

2.35.0 (2024-05-22)
-------------------
* Add parameter check for geometric values (backport `#1120 <https://github.com/ros-controls/ros2_controllers/issues/1120>`_) (`#1125 <https://github.com/ros-controls/ros2_controllers/issues/1125>`_)
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>2.35.0</version>
<version>2.36.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
4 changes: 2 additions & 2 deletions doc/controllers_index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,9 @@ Guidelines and Best Practices

.. toctree::
:titlesonly:
:glob:

*
mobile_robot_kinematics.rst
writing_new_controller.rst


Controllers for Wheeled Mobile Robots
Expand Down
13 changes: 13 additions & 0 deletions doc/migration.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/doc/migration.rst

Migration Guides: Galactic to Humble
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This list summarizes important changes between Galactic (previous) and Humble (current) releases, where changes to user code might be necessary.

.. note::

This list was created in July 2024, earlier changes are not included.

joint_trajectory_controller
*****************************
* Tolerances sent with the action goal were not used before, but are now processed and used for the upcoming action. (`#716 <https://github.com/ros-controls/ros2_controllers/pull/716>`_). Adaptions to the action goal might be necessary.
53 changes: 53 additions & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/doc/release_notes.rst

Release Notes: Galactic to Humble
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This list summarizes the changes between Galactic (previous) and Humble (current) releases. Bugfixes are not included in this list.

.. note::

This list was created in July 2024, earlier changes may not be included.

diff_drive_controller
*****************************
* Remove unused parameter ``wheels_per_side`` (`#958 <https://github.com/ros-controls/ros2_controllers/pull/958>`_).

joint_trajectory_controller
*****************************

* Activate update of dynamic parameters (`#761 <https://github.com/ros-controls/ros2_controllers/pull/761>`_ and `#849 <https://github.com/ros-controls/ros2_controllers/pull/849>`_).
* Continue with last trajectory-point on success, instead of hold-position from current state (`#842 <https://github.com/ros-controls/ros2_controllers/pull/842>`_).
* Add console output for tolerance checks (`#932 <https://github.com/ros-controls/ros2_controllers/pull/932>`_):

.. code::
[tolerances]: State tolerances failed for joint 2:
[tolerances]: Position Error: 0.020046, Position Tolerance: 0.010000
[trajectory_controllers]: Aborted due goal_time_tolerance exceeding by 1.010000 seconds
* Goals are now cancelled in ``on_deactivate`` transition (`#962 <https://github.com/ros-controls/ros2_controllers/pull/962>`_).
* Empty trajectory messages are discarded (`#902 <https://github.com/ros-controls/ros2_controllers/pull/902>`_).
* Action field ``error_string`` is now filled with meaningful strings (`#887 <https://github.com/ros-controls/ros2_controllers/pull/887>`_).
* Angle wraparound behavior (continuous joints) was added from the current state to the first segment of the incoming trajectory (`#796 <https://github.com/ros-controls/ros2_controllers/pull/796>`_).
* Tolerances sent with the action goal are now processed and used for the action. (`#716 <https://github.com/ros-controls/ros2_controllers/pull/716>`_). For details, see the `JointTolerance message <https://github.com/ros-controls/control_msgs/blob/master/control_msgs/msg/JointTolerance.msg>`_:

.. code-block:: markdown
The tolerances specify the amount the position, velocity, and
accelerations can vary from the setpoints. For example, in the case
of trajectory control, when the actual position varies beyond
(desired position + position tolerance), the trajectory goal may
abort.
There are two special values for tolerances:
* 0 - The tolerance is unspecified and will remain at whatever the default is
* -1 - The tolerance is "erased". If there was a default, the joint will be
allowed to move without restriction.
pid_controller
************************
* 🚀 The PID controller was added 🎉 (`#434 <https://github.com/ros-controls/ros2_controllers/pull/434>`_).

steering_controllers_library
********************************
* Changing default int values to double in steering controller's yaml file. The controllers should now initialize successfully without specifying these parameters (`#927 <https://github.com/ros-controls/ros2_controllers/pull/927>`_).
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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.0 (2024-07-09)
-------------------

2.35.0 (2024-05-22)
-------------------

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>2.35.0</version>
<version>2.36.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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.0 (2024-07-09)
-------------------

2.35.0 (2024-05-22)
-------------------

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>2.35.0</version>
<version>2.36.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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.0 (2024-07-09)
-------------------

2.35.0 (2024-05-22)
-------------------

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>2.35.0</version>
<version>2.36.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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.36.0 (2024-07-09)
-------------------

2.35.0 (2024-05-22)
-------------------

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>2.35.0</version>
<version>2.36.0</version>
<description>The gripper_controllers package</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>

Expand Down
Loading

0 comments on commit 9d78d2c

Please sign in to comment.