Skip to content

Commit

Permalink
Merge branch 'humble' into mergify/bp/humble/pr-725
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored Sep 16, 2023
2 parents aae656c + c8fc1a3 commit 3e32fd4
Show file tree
Hide file tree
Showing 44 changed files with 113 additions and 30 deletions.
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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

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

2.25.0 (2023-09-15)
-------------------
* Update docs for diff drive controller (`#751 <https://github.com/ros-controls/ros2_controllers/issues/751>`_) (`#753 <https://github.com/ros-controls/ros2_controllers/issues/753>`_)
* Contributors: Christoph Fröhlich

2.24.0 (2023-08-07)
-------------------
* Activate AdmittanceControllerTestParameterizedInvalidParameters (`#711 <https://github.com/ros-controls/ros2_controllers/issues/711>`_) (`#733 <https://github.com/ros-controls/ros2_controllers/issues/733>`_)
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.24.0</version>
<version>2.25.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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

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.24.0</version>
<version>2.25.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
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.25.0 (2023-09-15)
-------------------
* removed duplicated previous_publish_timestamp\_ increment by publish_period\_ in diff_drive_controller.cpp (`#644 <https://github.com/ros-controls/ros2_controllers/issues/644>`_) (`#777 <https://github.com/ros-controls/ros2_controllers/issues/777>`_)
* Update docs for diff drive controller (`#751 <https://github.com/ros-controls/ros2_controllers/issues/751>`_) (`#753 <https://github.com/ros-controls/ros2_controllers/issues/753>`_)
* Contributors: Christoph Fröhlich, Jules CARPENTIER

2.24.0 (2023-08-07)
-------------------

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.24.0</version>
<version>2.25.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
2 changes: 0 additions & 2 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,8 +203,6 @@ controller_interface::return_type DiffDriveController::update(

if (should_publish)
{
previous_publish_timestamp_ += publish_period_;

if (realtime_odometry_publisher_->trylock())
{
auto & odometry_message = realtime_odometry_publisher_->msg_;
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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

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.24.0</version>
<version>2.25.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.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

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.24.0</version>
<version>2.25.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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------
* Use tabs (`#743 <https://github.com/ros-controls/ros2_controllers/issues/743>`_) (`#746 <https://github.com/ros-controls/ros2_controllers/issues/746>`_)
* Contributors: Christoph Fröhlich

2.24.0 (2023-08-07)
-------------------

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.24.0</version>
<version>2.25.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.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

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.24.0</version>
<version>2.25.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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

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>2.24.0</version>
<version>2.25.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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

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>2.24.0</version>
<version>2.25.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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------
* [JTC] Rename parameter: normalize_error to angle_wraparound (`#772 <https://github.com/ros-controls/ros2_controllers/issues/772>`_) (`#776 <https://github.com/ros-controls/ros2_controllers/issues/776>`_)
* Remove wrong description (`#742 <https://github.com/ros-controls/ros2_controllers/issues/742>`_) (`#747 <https://github.com/ros-controls/ros2_controllers/issues/747>`_)
* [JTC] Update trajectory documentation (`#714 <https://github.com/ros-controls/ros2_controllers/issues/714>`_) (`#741 <https://github.com/ros-controls/ros2_controllers/issues/741>`_)
* Contributors: Christoph Fröhlich

2.24.0 (2023-08-07)
-------------------
* [JTC] Disable use of closed-loop PID adapter if controller is used in open-loop mode. (`#551 <https://github.com/ros-controls/ros2_controllers/issues/551>`_) (`#740 <https://github.com/ros-controls/ros2_controllers/issues/740>`_)
Expand Down
10 changes: 6 additions & 4 deletions joint_trajectory_controller/doc/parameters.rst
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,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 @@ -128,10 +128,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
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>2.24.0</version>
<version>2.25.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
13 changes: 11 additions & 2 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -722,12 +722,21 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
}
}

// Configure joint position error normalization from ROS parameters
// Configure joint position error normalization from ROS parameters (angle_wraparound)
normalize_joint_error_.resize(dof_);
for (size_t i = 0; i < dof_; ++i)
{
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
normalize_joint_error_[i] = gains.normalize_error;
if (gains.normalize_error)
{
// TODO(anyone): Remove deprecation warning in the end of 2023
RCLCPP_INFO(logger, "`normalize_error` is deprecated, use `angle_wraparound` instead!");
normalize_joint_error_[i] = gains.normalize_error;
}
else
{
normalize_joint_error_[i] = gains.angle_wraparound;
}
}

if (params_.state_interfaces.empty())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,13 @@ joint_trajectory_controller:
normalize_error: {
type: bool,
default_value: false,
description: "Use position error normalization to -pi to pi."
description: "(Deprecated) Use position error normalization to -pi to pi."
}
angle_wraparound: {
type: bool,
default_value: false,
description: "For joints that wrap around (ie. are continuous).
Normalizes position-error to -pi to pi."
}
constraints:
stopped_velocity_tolerance: {
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
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

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>2.24.0</version>
<version>2.25.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 ros2_controllers/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ros2_controllers
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion ros2_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>ros2_controllers</name>
<version>2.24.0</version>
<version>2.25.0</version>
<description>Metapackage for ROS2 controllers related packages</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Jordan Palacios</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions ros2_controllers_test_nodes/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ros2_controllers_test_nodes
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion ros2_controllers_test_nodes/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>ros2_controllers_test_nodes</name>
<version>2.24.0</version>
<version>2.25.0</version>
<description>Demo nodes for showing and testing functionalities of the ros2_control framework.</description>

<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion ros2_controllers_test_nodes/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

setup(
name=package_name,
version="2.24.0",
version="2.25.0",
packages=[package_name],
data_files=[
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
Expand Down
3 changes: 3 additions & 0 deletions rqt_joint_trajectory_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package rqt_joint_trajectory_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion rqt_joint_trajectory_controller/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>rqt_joint_trajectory_controller</name>
<version>2.24.0</version>
<version>2.25.0</version>
<description>Graphical frontend for interacting with joint_trajectory_controller instances.</description>

<maintainer email="[email protected]">Bence Magyar</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion rqt_joint_trajectory_controller/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

setup(
name=package_name,
version="2.24.0",
version="2.25.0",
packages=[package_name],
data_files=[
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
Expand Down
3 changes: 3 additions & 0 deletions steering_controllers_library/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package steering_controllers_library
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.25.0 (2023-09-15)
-------------------

2.24.0 (2023-08-07)
-------------------

Expand Down
Loading

0 comments on commit 3e32fd4

Please sign in to comment.