From 6fcb015e79da2e0929b69d76066993c8df2a66e2 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Sun, 26 May 2024 18:01:34 +0000 Subject: [PATCH] Remove manual angle-wraparound parameter --- doc/release_notes/Jazzy.rst | 2 +- .../src/joint_trajectory_controller.cpp | 11 ----------- .../src/joint_trajectory_controller_parameters.yaml | 6 ------ 3 files changed, 1 insertion(+), 18 deletions(-) diff --git a/doc/release_notes/Jazzy.rst b/doc/release_notes/Jazzy.rst index 8ecac3508f..4c5db18f3e 100644 --- a/doc/release_notes/Jazzy.rst +++ b/doc/release_notes/Jazzy.rst @@ -32,7 +32,7 @@ joint_trajectory_controller * Empty trajectory messages are discarded (`#902 `_). * Action field ``error_string`` is now filled with meaningful strings (`#887 `_). * Angle wraparound behavior (continuous joints) was added from the current state to the first segment of the incoming trajectory (`#796 `_). -* The URDF is now parsed for continuous joints and angle wraparound is automatically activated now (`#949 `_). +* The URDF is now parsed for continuous joints and angle wraparound is automatically activated now (`#949 `_). ``angle_wraparound`` parameter was completely removed. pid_controller ************************ diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index b250b25236..b80d1b7908 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -703,17 +703,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( joints_angle_wraparound_.resize(dof_); for (size_t i = 0; i < dof_; ++i) { - const auto & gains = params_.gains.joints_map.at(params_.joints[i]); - if (gains.angle_wraparound) - { - // TODO(christophfroehlich): remove this warning in a future release (ROS-J) - RCLCPP_WARN( - logger, - "[Deprecated] Parameter 'gains..angle_wraparound' is deprecated. The " - "angle_wraparound is now used if a continuous joint is configured in the URDF."); - joints_angle_wraparound_[i] = true; - } - if (!urdf_.empty()) { auto urdf_joint = model_.getJoint(params_.joints[i]); diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index b17229cab8..8bd64b6314 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -122,12 +122,6 @@ joint_trajectory_controller: default_value: 0.0, description: "Feed-forward scaling :math:`k_{ff}` of velocity" } - angle_wraparound: { - type: bool, - default_value: false, - description: "[deprecated] For joints that wrap around (ie. are continuous). - Normalizes position-error to -pi to pi." - } constraints: stopped_velocity_tolerance: { type: double,