Skip to content

Commit a4cc58d

Browse files
Add new AntiWindup parameters to JTC (#1759)
Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com>
1 parent 1dce1cc commit a4cc58d

File tree

3 files changed

+61
-3
lines changed

3 files changed

+61
-3
lines changed

doc/release_notes.rst

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,4 +6,8 @@ This list summarizes the changes between Jazzy (previous) and Kilted (current) r
66

77
force_torque_sensor_broadcaster
88
*******************************
9-
* Multiplier support was added. Users can now specify per–axis scaling factors for both force and torque readings, applied after the existing offset logic. (`#1647 <https://github.com/ros-controls/ros2_controllers/pull/1647/files>`__.
9+
* Multiplier support was added. Users can now specify per–axis scaling factors for both force and torque readings, applied after the existing offset logic. (`#1647 <https://github.com/ros-controls/ros2_controllers/pull/1647/files>`__).
10+
11+
joint_trajectory_controller
12+
*******************************
13+
* The controller now supports the new anti-windup strategy of the PID class, which allows for more flexible control of the anti-windup behavior. (`#1759 <https://github.com/ros-controls/ros2_controllers/pull/1759>`__).

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1663,16 +1663,23 @@ void JointTrajectoryController::update_pids()
16631663
for (size_t i = 0; i < num_cmd_joints_; ++i)
16641664
{
16651665
const auto & gains = params_.gains.joints_map.at(params_.joints.at(map_cmd_to_joints_[i]));
1666+
control_toolbox::AntiWindupStrategy antiwindup_strat;
1667+
antiwindup_strat.set_type(gains.antiwindup_strategy);
1668+
antiwindup_strat.i_max = gains.i_clamp;
1669+
antiwindup_strat.i_min = -gains.i_clamp;
1670+
antiwindup_strat.error_deadband = gains.error_deadband;
1671+
antiwindup_strat.tracking_time_constant = gains.tracking_time_constant;
16661672
if (pids_[i])
16671673
{
16681674
// update PIDs with gains from ROS parameters
1669-
pids_[i]->set_gains(gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);
1675+
pids_[i]->set_gains(
1676+
gains.p, gains.i, gains.d, gains.u_clamp_max, gains.u_clamp_min, antiwindup_strat);
16701677
}
16711678
else
16721679
{
16731680
// Init PIDs with gains from ROS parameters
16741681
pids_[i] = std::make_shared<control_toolbox::Pid>(
1675-
gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);
1682+
gains.p, gains.i, gains.d, gains.u_clamp_max, gains.u_clamp_min, antiwindup_strat);
16761683
}
16771684
ff_velocity_scale_[i] = gains.ff_velocity_scale;
16781685
}

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -134,6 +134,53 @@ joint_trajectory_controller:
134134
default_value: 0.0,
135135
description: "Feed-forward scaling :math:`k_{ff}` of velocity"
136136
}
137+
u_clamp_max: {
138+
type: double,
139+
default_value: .inf,
140+
description: "Upper output clamp."
141+
}
142+
u_clamp_min: {
143+
type: double,
144+
default_value: -.inf,
145+
description: "Lower output clamp."
146+
}
147+
i_clamp_max: {
148+
type: double,
149+
default_value: 0.0,
150+
description: "[Deprecated, see antiwindup_strategy] Upper integral clamp."
151+
}
152+
i_clamp_min: {
153+
type: double,
154+
default_value: 0.0,
155+
description: "[Deprecated, see antiwindup_strategy] Lower integral clamp."
156+
}
157+
antiwindup_strategy: {
158+
type: string,
159+
default_value: "legacy",
160+
read_only: true,
161+
description: "Specifies the anti-windup strategy. Options: 'back_calculation',
162+
'conditional_integration', 'legacy' or 'none'. Note that the 'back_calculation' strategy use the
163+
tracking_time_constant parameter to tune the anti-windup behavior.",
164+
validation: {
165+
one_of<>: [[
166+
"back_calculation",
167+
"conditional_integration",
168+
"legacy",
169+
"none"
170+
]]
171+
}
172+
}
173+
tracking_time_constant: {
174+
type: double,
175+
default_value: 0.0,
176+
description: "Specifies the tracking time constant for the 'back_calculation' strategy. If
177+
set to 0.0 when this strategy is selected, a recommended default value will be applied."
178+
}
179+
error_deadband: {
180+
type: double,
181+
default_value: 0.0,
182+
description: "Is used to stop integration when the error is within the given range."
183+
}
137184
constraints:
138185
stopped_velocity_tolerance: {
139186
type: double,

0 commit comments

Comments
 (0)