Skip to content

Commit f652c3d

Browse files
authored
Update anti-windup techniques (#298)
1 parent d5ad588 commit f652c3d

File tree

8 files changed

+1565
-119
lines changed

8 files changed

+1565
-119
lines changed

control_toolbox/include/control_toolbox/pid.hpp

Lines changed: 414 additions & 26 deletions
Large diffs are not rendered by default.

control_toolbox/include/control_toolbox/pid_ros.hpp

Lines changed: 128 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -92,13 +92,14 @@ class PidROS
9292
* \param d The derivative gain.
9393
* \param i_max Upper integral clamp.
9494
* \param i_min Lower integral clamp.
95-
* \param antiwindup Antiwindup functionality. When set to true, limits
95+
* \param antiwindup Anti-windup functionality. When set to true, limits
9696
the integral error to prevent windup; otherwise, constrains the
9797
integral contribution to the control output. i_max and
9898
i_min are applied in both scenarios.
9999
*
100100
* \note New gains are not applied if i_min_ > i_max_
101101
*/
102+
[[deprecated("Use initialize_from_args with AntiwindupStrategy instead.")]]
102103
void initialize_from_args(
103104
double p, double i, double d, double i_max, double i_min, bool antiwindup);
104105

@@ -109,17 +110,80 @@ class PidROS
109110
* \param d The derivative gain.
110111
* \param i_max The max integral windup.
111112
* \param i_min The min integral windup.
112-
* \param antiwindup antiwindup.
113+
* \param antiwindup Anti-windup functionality. When set to true, limits
114+
the integral error to prevent windup; otherwise, constrains the
115+
integral contribution to the control output. i_max and
116+
i_min are applied in both scenarios.
113117
* \param save_i_term save integrator output between resets.
114118
*
115119
* \note New gains are not applied if i_min_ > i_max_
116120
*/
121+
[[deprecated("Use initialize_from_args with AntiwindupStrategy instead.")]]
117122
void initialize_from_args(
118123
double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term);
119124

125+
/*!
126+
* \brief Initialize the PID controller and set the parameters
127+
* \param p The proportional gain.
128+
* \param i The integral gain.
129+
* \param d The derivative gain.
130+
* \param i_max The max integral windup.
131+
* \param i_min The min integral windup.
132+
* \param u_max Upper output clamp.
133+
* \param u_min Lower output clamp.
134+
* \param trk_tc Specifies the tracking time constant for the 'back_calculation' strategy. If set
135+
* to 0.0 when this strategy is selected, a recommended default value will be applied.
136+
* \param saturation Enables output saturation. When true, the controller output is
137+
clamped between u_max and u_min.
138+
* \param antiwindup Anti-windup functionality. When set to true, limits
139+
the integral error to prevent windup; otherwise, constrains the
140+
integral contribution to the control output. i_max and
141+
i_min are applied in both scenarios.
142+
* \param antiwindup_strat Specifies the anti-windup strategy. Options: 'back_calculation',
143+
'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the
144+
tracking_time_constant parameter to tune the anti-windup behavior. When a strategy other
145+
than 'none' is selected, it will override the controller's default anti-windup behavior.
146+
* \deprecated{only when `antiwindup_strat == AntiwindupStrategy::NONE`:}
147+
* Old anti-windup technique is deprecated and will be removed by
148+
* the ROS 2 Kilted Kaiju release.
149+
* \warning{If you pass `AntiwindupStrategy::NONE`, at runtime a warning will be printed:}
150+
* `"Old anti-windup technique is deprecated. This option will be removed by the ROS 2 Kilted Kaiju release."`
151+
* \param save_i_term save integrator output between resets.
152+
*
153+
* \note New gains are not applied if i_min_ > i_max_ or if u_min_ > u_max_.
154+
*/
155+
[[deprecated("Use initialize_from_args with AntiwindupStrategy only.")]]
156+
void initialize_from_args(
157+
double p, double i, double d, double i_max, double i_min, double u_max, double u_min,
158+
double trk_tc, bool saturation, bool antiwindup, AntiwindupStrategy antiwindup_strat,
159+
bool save_i_term);
160+
161+
/*!
162+
* \brief Initialize the PID controller and set the parameters.
163+
*
164+
* \param p The proportional gain.
165+
* \param i The integral gain.
166+
* \param d The derivative gain.
167+
* \param u_max Upper output clamp.
168+
* \param u_min Lower output clamp.
169+
* \param trk_tc Specifies the tracking time constant for the 'back_calculation' strategy. If set
170+
* to 0.0 when this strategy is selected, a recommended default value will be applied.
171+
* \param saturation Enables output saturation. When true, the controller output is
172+
clamped between u_max and u_min.
173+
* \param antiwindup_strat Specifies the anti-windup strategy. Options: 'back_calculation',
174+
'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the
175+
tracking_time_constant parameter to tune the anti-windup behavior.
176+
* \param save_i_term save integrator output between resets.
177+
*
178+
* \note New gains are not applied if u_min_ > u_max_.
179+
*/
180+
void initialize_from_args(
181+
double p, double i, double d, double u_max, double u_min, double trk_tc, bool saturation,
182+
AntiwindupStrategy antiwindup_strat, bool save_i_term);
183+
120184
/*!
121185
* \brief Initialize the PID controller based on already set parameters
122-
* \return True if all parameters are set (p, i, d, i_min and i_max), False otherwise
186+
* \return True if all parameters are set (p, i, d, i_max, i_min, u_max, u_min and trk_tc), False otherwise
123187
*/
124188
bool initialize_from_ros_parameters();
125189

@@ -182,8 +246,67 @@ class PidROS
182246
*
183247
* \note New gains are not applied if i_min > i_max
184248
*/
249+
[[deprecated("Use set_gains with AntiwindupStrategy instead.")]]
185250
void set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
186251

252+
/*!
253+
* \brief Initialize the PID controller and set the parameters
254+
* \param p The proportional gain.
255+
* \param i The integral gain.
256+
* \param d The derivative gain.
257+
* \param i_max The max integral windup.
258+
* \param i_min The min integral windup.
259+
* \param u_max Upper output clamp.
260+
* \param u_min Lower output clamp.
261+
* \param trk_tc Specifies the tracking time constant for the 'back_calculation' strategy. If set
262+
* to 0.0 when this strategy is selected, a recommended default value will be applied.
263+
* \param saturation Enables output saturation. When true, the controller output is
264+
clamped between u_max and u_min.
265+
* \param antiwindup Anti-windup functionality. When set to true, limits
266+
the integral error to prevent windup; otherwise, constrains the
267+
integral contribution to the control output. i_max and
268+
i_min are applied in both scenarios.
269+
* \param antiwindup_strat Specifies the anti-windup strategy. Options: 'back_calculation',
270+
'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the
271+
tracking_time_constant parameter to tune the anti-windup behavior. When a strategy other
272+
than 'none' is selected, it will override the controller's default anti-windup behavior.
273+
* \deprecated{only when `antiwindup_strat == AntiwindupStrategy::NONE`:}
274+
* Old anti-windup technique is deprecated and will be removed by
275+
* the ROS 2 Kilted Kaiju release.
276+
* \warning{If you pass `AntiwindupStrategy::NONE`, at runtime a warning will be printed:}
277+
* `"Old anti-windup technique is deprecated. This option will be removed by
278+
* the ROS 2 Kilted Kaiju release."`
279+
*
280+
* \note New gains are not applied if i_min > i_max or if u_min_ > u_max_.
281+
*/
282+
[[deprecated("Use set_gains with AntiwindupStrategy only.")]]
283+
void set_gains(
284+
double p, double i, double d, double i_max, double i_min, double u_max, double u_min,
285+
double trk_tc = 0.0, bool saturation = false, bool antiwindup = false,
286+
AntiwindupStrategy antiwindup_strat = AntiwindupStrategy::NONE);
287+
288+
/*!
289+
* \brief Set PID gains for the controller (preferred).
290+
*
291+
* \param p The proportional gain.
292+
* \param i The integral gain.
293+
* \param d The derivative gain.
294+
* \param u_max Upper output clamp.
295+
* \param u_min Lower output clamp.
296+
* \param trk_tc Specifies the tracking time constant for the 'back_calculation' strategy. If set
297+
* to 0.0 when this strategy is selected, a recommended default value will be applied.
298+
* \param saturation Enables output saturation. When true, the controller output is
299+
clamped between u_max and u_min.
300+
* \param antiwindup_strat Specifies the anti-windup strategy. Options: 'back_calculation',
301+
'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the
302+
tracking_time_constant parameter to tune the anti-windup behavior.
303+
*
304+
* \note New gains are not applied if u_min_ > u_max_.
305+
*/
306+
void set_gains(
307+
double p, double i, double d, double u_max, double u_min, double trk_tc, bool saturation,
308+
AntiwindupStrategy antiwindup_strat);
309+
187310
/*!
188311
* \brief Set PID gains for the controller.
189312
* \param gains A struct of the PID gain values
@@ -248,6 +371,8 @@ class PidROS
248371

249372
bool get_boolean_param(const std::string & param_name, bool & value);
250373

374+
bool get_string_param(const std::string & param_name, std::string & value);
375+
251376
/*!
252377
* \brief Set prefix for topic and parameter names
253378
* \param[in] topic_prefix prefix to add to the pid parameters.

0 commit comments

Comments
 (0)