Skip to content

Commit cad7894

Browse files
[JTC] Rename parameter: normalize_error to angle_wraparound (#772)
1 parent 66c5ac3 commit cad7894

File tree

3 files changed

+24
-7
lines changed

3 files changed

+24
-7
lines changed

joint_trajectory_controller/doc/parameters.rst

+6-4
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ gains (structure)
102102
103103
u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v)
104104
105-
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see below),
105+
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see ``angle_wraparound`` below),
106106
the controller period :math:`dt`, and the ``velocity`` or ``effort`` manipulated variable (control variable) :math:`u`, respectively.
107107

108108
gains.<joint_name>.p (double)
@@ -130,10 +130,12 @@ gains.<joint_name>.ff_velocity_scale (double)
130130

131131
Default: 0.0
132132

133-
gains.<joint_name>.normalize_error (bool)
133+
gains.<joint_name>.angle_wraparound (bool)
134+
For joints that wrap around (without end stop, ie. are continuous),
135+
where the shortest rotation to the target position is the desired motion.
134136
If true, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`.
135137
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
136-
position :math:`s` from the state interface. Use this for revolute joints without end stop,
137-
where the shortest rotation to the target position is the desired motion.
138+
position :math:`s` from the state interface.
139+
138140

139141
Default: false

joint_trajectory_controller/src/joint_trajectory_controller.cpp

+11-2
Original file line numberDiff line numberDiff line change
@@ -726,12 +726,21 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
726726
}
727727
}
728728

729-
// Configure joint position error normalization from ROS parameters
729+
// Configure joint position error normalization from ROS parameters (angle_wraparound)
730730
normalize_joint_error_.resize(dof_);
731731
for (size_t i = 0; i < dof_; ++i)
732732
{
733733
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
734-
normalize_joint_error_[i] = gains.normalize_error;
734+
if (gains.normalize_error)
735+
{
736+
// TODO(anyone): Remove deprecation warning in the end of 2023
737+
RCLCPP_INFO(logger, "`normalize_error` is deprecated, use `angle_wraparound` instead!");
738+
normalize_joint_error_[i] = gains.normalize_error;
739+
}
740+
else
741+
{
742+
normalize_joint_error_[i] = gains.angle_wraparound;
743+
}
735744
}
736745

737746
if (params_.state_interfaces.empty())

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

+7-1
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,13 @@ joint_trajectory_controller:
113113
normalize_error: {
114114
type: bool,
115115
default_value: false,
116-
description: "Use position error normalization to -pi to pi."
116+
description: "(Deprecated) Use position error normalization to -pi to pi."
117+
}
118+
angle_wraparound: {
119+
type: bool,
120+
default_value: false,
121+
description: "For joints that wrap around (ie. are continuous).
122+
Normalizes position-error to -pi to pi."
117123
}
118124
constraints:
119125
stopped_velocity_tolerance: {

0 commit comments

Comments
 (0)