Skip to content

Commit aebe6b1

Browse files
authored
Add new members for PID controller parameters (#1585)
1 parent 6920a2a commit aebe6b1

File tree

3 files changed

+48
-3
lines changed

3 files changed

+48
-3
lines changed

doc/migration.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,3 +15,5 @@ diff_drive_controller
1515
pid_controller
1616
*****************************
1717
* Parameters ``enable_feedforward`` and service ``set_feedforward_control`` are removed. Instead, set the feedforward_gain to zero or a non-zero value. (`#1553 <https://github.com/ros-controls/ros2_controllers/pull/1553>`_).
18+
* The legacy ``antiwindup`` boolean and integral clamp parameters ``i_clamp_max``/``i_clamp_min`` have
19+
been deprecated in favor of the new ``antiwindup_strategy`` parameter (`#1585 <https://github.com/ros-controls/ros2_controllers/pull/1585>`__). Choose a suitable anti-windup strategy and set the parameters accordingly.

doc/release_notes.rst

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,3 +11,10 @@ force_torque_sensor_broadcaster
1111
joint_trajectory_controller
1212
*******************************
1313
* 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>`__).
14+
15+
pid_controller
16+
*******************************
17+
* The controller now supports the new anti-windup strategy of the PID class, which allows for more flexible control of the anti-windup behavior (`#1585 <https://github.com/ros-controls/ros2_controllers/pull/1585>`__).
18+
* Output clamping via ``u_clamp_max`` and ``u_clamp_min`` was added, allowing users to bound the controller output.
19+
* The legacy ``antiwindup`` boolean and integral clamp parameters ``i_clamp_max``/``i_clamp_min`` have been deprecated in favor of the new ``antiwindup_strategy`` parameter. A ``tracking_time_constant`` parameter has also been introduced to configure the back-calculation strategy.
20+
* A new ``error_deadband`` parameter stops integration when the error is within a specified range.

pid_controller/src/pid_controller.yaml

Lines changed: 39 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -60,23 +60,59 @@ pid_controller:
6060
default_value: 0.0,
6161
description: "Derivative gain for PID"
6262
}
63+
u_clamp_max: {
64+
type: double,
65+
default_value: .inf,
66+
description: "Upper output clamp."
67+
}
68+
u_clamp_min: {
69+
type: double,
70+
default_value: -.inf,
71+
description: "Lower output clamp."
72+
}
6373
antiwindup: {
6474
type: bool,
6575
default_value: false,
66-
description: "Antiwindup functionality. When set to true, limits
76+
description: "[Deprecated, see antiwindup_strategy] Anti-windup functionality. When set to true, limits
6777
the integral error to prevent windup; otherwise, constrains the
6878
integral contribution to the control output. i_clamp_max and
6979
i_clamp_min are applied in both scenarios."
7080
}
7181
i_clamp_max: {
7282
type: double,
7383
default_value: 0.0,
74-
description: "Upper integral clamp."
84+
description: "[Deprecated, see antiwindup_strategy] Upper integral clamp."
7585
}
7686
i_clamp_min: {
7787
type: double,
7888
default_value: 0.0,
79-
description: "Lower integral clamp."
89+
description: "[Deprecated, see antiwindup_strategy] Lower integral clamp."
90+
}
91+
antiwindup_strategy: {
92+
type: string,
93+
default_value: "legacy",
94+
description: "Specifies the anti-windup strategy. Options: 'back_calculation',
95+
'conditional_integration', 'legacy' or 'none'. Note that the 'back_calculation' strategy use the
96+
tracking_time_constant parameter to tune the anti-windup behavior.",
97+
validation: {
98+
one_of<>: [[
99+
"back_calculation",
100+
"conditional_integration",
101+
"legacy",
102+
"none"
103+
]]
104+
}
105+
}
106+
tracking_time_constant: {
107+
type: double,
108+
default_value: 0.0,
109+
description: "Specifies the tracking time constant for the 'back_calculation' strategy. If
110+
set to 0.0 when this strategy is selected, a recommended default value will be applied."
111+
}
112+
error_deadband: {
113+
type: double,
114+
default_value: 1.e-16,
115+
description: "Is used to stop integration when the error is within the given range."
80116
}
81117
feedforward_gain: {
82118
type: double,

0 commit comments

Comments
 (0)