@@ -57,12 +57,8 @@ namespace control_toolbox
5757 * \param u_min Lower output clamp.
5858 * \param tracking_time_constant Specifies the tracking time constant for the 'back_calculation' strategy. If set
5959 * to 0.0 when this strategy is selected, a recommended default value will be applied.
60- * \param legacy_antiwindup Anti-windup functionality. When set to true, limits
61- the integral error to prevent windup; otherwise, constrains the
62- integral contribution to the control output. i_max and
63- i_min are applied in both scenarios.
64- * \param error_deadband Error deadband is used to stop integration when the error is within the given range.
65- * \param type Specifies the antiwindup strategy type. Valid values are:
60+ * \param error_deadband Error deadband is used to stop integration when the error is within the given range.
61+ * \param type Specifies the antiwindup strategy type. Valid values are:
6662 * - `NONE`: No antiwindup strategy applied.
6763 * - `LEGACY`: Legacy antiwindup strategy, which limits the integral term to prevent windup (deprecated: This option will be removed in a future release).
6864 * - `BACK_CALCULATION`: Back calculation antiwindup strategy, which uses a tracking time constant.
@@ -75,7 +71,6 @@ struct AntiWindupStrategy
7571 {
7672 UNDEFINED = -1 ,
7773 NONE,
78- LEGACY,
7974 BACK_CALCULATION,
8075 CONDITIONAL_INTEGRATION
8176 };
@@ -84,7 +79,6 @@ struct AntiWindupStrategy
8479 : type(UNDEFINED),
8580 i_min (std::numeric_limits<double >::quiet_NaN()),
8681 i_max(std::numeric_limits<double >::quiet_NaN()),
87- legacy_antiwindup(false ),
8882 tracking_time_constant(0.0 ),
8983 error_deadband(std::numeric_limits<double >::epsilon())
9084 {
@@ -100,13 +94,6 @@ struct AntiWindupStrategy
10094 {
10195 type = CONDITIONAL_INTEGRATION;
10296 }
103- else if (s == " legacy" )
104- {
105- type = LEGACY;
106- std::cout << " Using the legacy anti-windup technique is deprecated. This option will be "
107- " removed by the ROS 2 Kilted Kaiju release."
108- << std::endl;
109- }
11097 else if (s == " none" )
11198 {
11299 type = NONE;
@@ -116,7 +103,7 @@ struct AntiWindupStrategy
116103 type = UNDEFINED;
117104 throw std::invalid_argument (
118105 " AntiWindupStrategy: Unknown antiwindup strategy : '" + s +
119- " '. Valid strategies are: 'back_calculation', 'conditional_integration', 'legacy', "
106+ " '. Valid strategies are: 'back_calculation', 'conditional_integration', "
120107 " 'none'." );
121108 }
122109 }
@@ -135,23 +122,15 @@ struct AntiWindupStrategy
135122 " AntiWindupStrategy 'back_calculation' requires a valid positive tracking time constant "
136123 " (tracking_time_constant)" );
137124 }
138- if (type == LEGACY && ((i_min > i_max) || !std::isfinite (i_min) || !std::isfinite (i_max)))
125+ if (type != NONE && ((i_min > i_max) || !std::isfinite (i_min) || !std::isfinite (i_max)))
139126 {
140127 throw std::invalid_argument (
141128 fmt::format (
142- " AntiWindupStrategy 'legacy' requires i_min < i_max and to be finite (i_min: {}, i_max: "
143- " {})" ,
129+ " AntiWindupStrategy requires i_min < i_max and to be finite (i_min: {}, i_max: {})" ,
144130 i_min, i_max));
145131 }
146- if (type != LEGACY && (std::isfinite (i_min) || std::isfinite (i_max)))
147- {
148- std::cout << " Warning: The i_min and i_max are only valid for the deprecated LEGACY "
149- " antiwindup strategy. Please use the AntiWindupStrategy::set_type() method to "
150- " set the type of antiwindup strategy you want to use."
151- << std::endl;
152- }
153132 if (
154- type != NONE && type != UNDEFINED && type != LEGACY && type != BACK_CALCULATION &&
133+ type != NONE && type != UNDEFINED && type != BACK_CALCULATION &&
155134 type != CONDITIONAL_INTEGRATION)
156135 {
157136 throw std::invalid_argument (" AntiWindupStrategy has an invalid type" );
@@ -171,8 +150,6 @@ struct AntiWindupStrategy
171150 return " back_calculation" ;
172151 case CONDITIONAL_INTEGRATION:
173152 return " conditional_integration" ;
174- case LEGACY:
175- return " legacy" ;
176153 case NONE:
177154 return " none" ;
178155 case UNDEFINED:
@@ -185,8 +162,6 @@ struct AntiWindupStrategy
185162 double i_min = std::numeric_limits<double >::quiet_NaN(); /* *< Minimum allowable integral term. */
186163 double i_max = std::numeric_limits<double >::quiet_NaN(); /* *< Maximum allowable integral term. */
187164
188- bool legacy_antiwindup = false ; /* *< Use legacy anti-windup strategy. */
189-
190165 // tracking_time_constant Specifies the tracking time constant for the 'back_calculation'
191166 // strategy. If set to 0.0 a recommended default value will be applied.
192167 double tracking_time_constant = 0.0 ; /* *< Tracking time constant for back_calculation strategy. */
@@ -286,64 +261,6 @@ class Pid
286261 */
287262 struct Gains
288263 {
289- /* !
290- * \brief Optional constructor for passing in values without antiwindup and saturation
291- *
292- * \param p The proportional gain.
293- * \param i The integral gain.
294- * \param d The derivative gain.
295- * \param i_max Upper integral clamp.
296- * \param i_min Lower integral clamp.
297- *
298- */
299- [[deprecated(" Use constructor with AntiWindupStrategy instead." )]]
300- Gains (double p, double i, double d, double i_max, double i_min)
301- : p_gain_(p),
302- i_gain_ (i),
303- d_gain_(d),
304- i_max_(i_max),
305- i_min_(i_min),
306- u_max_(std::numeric_limits<double >::infinity()),
307- u_min_(-std::numeric_limits<double >::infinity()),
308- antiwindup_(false )
309- {
310- antiwindup_strat_.type = AntiWindupStrategy::LEGACY;
311- antiwindup_strat_.i_max = i_max;
312- antiwindup_strat_.i_min = i_min;
313- antiwindup_strat_.legacy_antiwindup = true ;
314- }
315-
316- /* !
317- * \brief Optional constructor for passing in values without saturation
318- *
319- * \param p The proportional gain.
320- * \param i The integral gain.
321- * \param d The derivative gain.
322- * \param i_max Upper integral clamp.
323- * \param i_min Lower integral clamp.
324- * \param antiwindup Anti-windup functionality. When set to true, limits
325- the integral error to prevent windup; otherwise, constrains the
326- integral contribution to the control output. i_max and
327- i_min are applied in both scenarios.
328- *
329- */
330- [[deprecated(" Use constructor with AntiWindupStrategy instead." )]]
331- Gains (double p, double i, double d, double i_max, double i_min, bool antiwindup)
332- : p_gain_(p),
333- i_gain_(i),
334- d_gain_(d),
335- i_max_(i_max),
336- i_min_(i_min),
337- u_max_(std::numeric_limits<double >::infinity()),
338- u_min_(-std::numeric_limits<double >::infinity()),
339- antiwindup_(antiwindup)
340- {
341- antiwindup_strat_.type = AntiWindupStrategy::LEGACY;
342- antiwindup_strat_.i_max = i_max;
343- antiwindup_strat_.i_min = i_min;
344- antiwindup_strat_.legacy_antiwindup = antiwindup;
345- }
346-
347264 /* !
348265 * \brief Constructor for passing in values.
349266 *
@@ -367,7 +284,6 @@ class Pid
367284 i_min_(antiwindup_strat.i_min),
368285 u_max_(u_max),
369286 u_min_(u_min),
370- antiwindup_(antiwindup_strat.legacy_antiwindup),
371287 antiwindup_strat_(antiwindup_strat)
372288 {
373289 if (std::isnan (u_min) || std::isnan (u_max))
@@ -412,53 +328,26 @@ class Pid
412328 return true ;
413329 }
414330
415- // Default constructor
416- [[deprecated(
417- " Use constructor with AntiWindupStrategy only. The default constructor might be deleted in "
418- " future" )]] Gains()
419- {
420- }
421-
422331 void print () const
423332 {
424333 std::cout << " Gains: p: " << p_gain_ << " , i: " << i_gain_ << " , d: " << d_gain_
425334 << " , i_max: " << i_max_ << " , i_min: " << i_min_ << " , u_max: " << u_max_
426- << " , u_min: " << u_min_ << " , antiwindup : " << antiwindup_
427- << " , antiwindup_strat: " << antiwindup_strat_. to_string () << std::endl;
335+ << " , u_min: " << u_min_ << " , antiwindup_strat : " << antiwindup_strat_. to_string ()
336+ << std::endl;
428337 }
429338
430339 double p_gain_ = 0.0 ; /* *< Proportional gain. */
431340 double i_gain_ = 0.0 ; /* *< Integral gain. */
432341 double d_gain_ = 0.0 ; /* *< Derivative gain. */
433- double i_max_ = 0.0 ; /* *< Maximum allowable integral term. */
434- double i_min_ = 0.0 ; /* *< Minimum allowable integral term. */
342+ double i_max_ =
343+ std::numeric_limits<double >::infinity(); /* *< Maximum allowable integral term. */
344+ double i_min_ =
345+ -std::numeric_limits<double >::infinity(); /* *< Minimum allowable integral term. */
435346 double u_max_ = std::numeric_limits<double >::infinity(); /* *< Maximum allowable output. */
436347 double u_min_ = -std::numeric_limits<double >::infinity(); /* *< Minimum allowable output. */
437- bool antiwindup_ = false ; /* *< Anti-windup. */
438348 AntiWindupStrategy antiwindup_strat_; /* *< Anti-windup strategy. */
439349 };
440350
441- /* !
442- * \brief Constructor, zeros out Pid values when created and
443- * initialize Pid-gains and integral term limits.
444- *
445- * \param p The proportional gain.
446- * \param i The integral gain.
447- * \param d The derivative gain.
448- * \param i_max Upper integral clamp.
449- * \param i_min Lower integral clamp.
450- * \param antiwindup Anti-windup functionality. When set to true, limits
451- the integral error to prevent windup; otherwise, constrains the
452- integral contribution to the control output. i_max and
453- i_min are applied in both scenarios.
454- *
455- * \throws An std::invalid_argument exception is thrown if i_min > i_max
456- */
457- [[deprecated(" Use constructor with AntiWindupStrategy only." )]]
458- Pid (
459- double p = 0.0 , double i = 0.0 , double d = 0.0 , double i_max = 0.0 , double i_min = -0.0 ,
460- bool antiwindup = false );
461-
462351 /* !
463352 * \brief Constructor, initialize Pid-gains and term limits.
464353 *
@@ -471,11 +360,13 @@ class Pid
471360 'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the
472361 tracking_time_constant parameter to tune the anti-windup behavior.
473362 *
474- * \throws An std::invalid_argument exception is thrown if u_min > u_max
363+ * \throws An std::invalid_argument exception is thrown if u_min > u_max.
475364 */
476365 Pid (
477- double p, double i, double d, double u_max, double u_min,
478- const AntiWindupStrategy & antiwindup_strat);
366+ double p = 0.0 , double i = 0.0 , double d = 0.0 ,
367+ double u_max = std::numeric_limits<double >::infinity(),
368+ double u_min = -std::numeric_limits<double>::infinity(),
369+ const AntiWindupStrategy & antiwindup_strat = AntiWindupStrategy());
479370
480371 /* !
481372 * \brief Copy constructor required for preventing mutexes from being copied
@@ -488,25 +379,6 @@ class Pid
488379 */
489380 ~Pid ();
490381
491- /* !
492- * \brief Zeros out Pid values and initialize Pid-gains and term limits
493- *
494- * \param p The proportional gain.
495- * \param i The integral gain.
496- * \param d The derivative gain.
497- * \param i_max Upper integral clamp.
498- * \param i_min Lower integral clamp.
499- * \param antiwindup Anti-windup functionality. When set to true, limits
500- the integral error to prevent windup; otherwise, constrains the
501- integral contribution to the control output. i_max and
502- i_min are applied in both scenarios.
503- * \return True if all parameters are successfully set, False otherwise.
504- * \note New gains are not applied if i_min_ > i_max_
505- */
506- [[deprecated(" Use initialize with AntiWindupStrategy instead." )]]
507- bool initialize (
508- double p, double i, double d, double i_max, double i_min, bool antiwindup = false );
509-
510382 /* !
511383 * \brief Initialize Pid-gains and term limits.
512384 *
@@ -520,7 +392,7 @@ class Pid
520392 tracking_time_constant parameter to tune the anti-windup behavior.
521393 * \return True if all parameters are successfully set, False otherwise.
522394 *
523- * \note New gains are not applied if i_min_ > i_max_ or u_min > u_max
395+ * \note New gains are not applied if u_min > u_max.
524396 */
525397 bool initialize (
526398 double p, double i, double d, double u_max, double u_min,
@@ -544,36 +416,6 @@ class Pid
544416 */
545417 void clear_saved_iterm ();
546418
547- /* !
548- * \brief Get PID gains for the controller.
549- * \param p The proportional gain.
550- * \param i The integral gain.
551- * \param d The derivative gain.
552- * \param i_max Upper integral clamp.
553- * \param i_min Lower integral clamp.
554- *
555- * \note This method is not RT safe
556- */
557- void get_gains (double & p, double & i, double & d, double & i_max, double & i_min);
558-
559- /* !
560- * \brief Get PID gains for the controller.
561- * \param p The proportional gain.
562- * \param i The integral gain.
563- * \param d The derivative gain.
564- * \param i_max Upper integral clamp.
565- * \param i_min Lower integral clamp.
566- * \param antiwindup Anti-windup functionality. When set to true, limits
567- the integral error to prevent windup; otherwise, constrains the
568- integral contribution to the control output. i_max and
569- i_min are applied in both scenarios.
570- *
571- * \note This method is not RT safe
572- */
573- [[deprecated(" Use get_gains overload with AntiWindupStrategy argument." )]]
574- void get_gains (
575- double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
576-
577419 /* !
578420 * \brief Get PID gains for the controller (preferred).
579421 * \param p The proportional gain.
@@ -607,25 +449,6 @@ class Pid
607449 */
608450 Gains get_gains_rt () { return gains_; }
609451
610- /* !
611- * \brief Set PID gains for the controller.
612- * \param p The proportional gain.
613- * \param i The integral gain.
614- * \param d The derivative gain.
615- * \param i_max Upper integral clamp.
616- * \param i_min Lower integral clamp.
617- * \param antiwindup Anti-windup functionality. When set to true, limits
618- the integral error to prevent windup; otherwise, constrains the
619- integral contribution to the control output. i_max and
620- i_min are applied in both scenarios.
621- * \return True if all parameters are successfully set, False otherwise.
622- *
623- * \note New gains are not applied if i_min > i_max
624- * \note This method is not RT safe
625- */
626- [[deprecated(" Use set_gains with AntiWindupStrategy instead." )]]
627- bool set_gains (double p, double i, double d, double i_max, double i_min, bool antiwindup = false );
628-
629452 /* !
630453 * \brief Set PID gains for the controller.
631454 *
@@ -639,7 +462,7 @@ class Pid
639462 tracking_time_constant parameter to tune the anti-windup behavior.
640463 * \return True if all parameters are successfully set, False otherwise.
641464 *
642- * \note New gains are not applied if i_min_ > i_max_ or u_min > u_max
465+ * \note New gains are not applied if u_min > u_max
643466 * \note This method is not RT safe
644467 */
645468 bool set_gains (
0 commit comments