Skip to content

Commit

Permalink
[JTC] Rename parameter: normalize_error to angle_wraparound (#772)
Browse files Browse the repository at this point in the history
(cherry picked from commit cad7894)
  • Loading branch information
christophfroehlich authored and mergify[bot] committed Sep 13, 2023
1 parent a58243b commit dee3dce
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 7 deletions.
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
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

0 comments on commit dee3dce

Please sign in to comment.