ros2_control - jazzy
Loading...
Searching...
No Matches
pid.hpp
1// Copyright (c) 2008, Willow Garage, Inc.
2// All rights reserved.
3//
4// Software License Agreement (BSD License 2.0)
5//
6// Redistribution and use in source and binary forms, with or without
7// modification, are permitted provided that the following conditions
8// are met:
9//
10// * Redistributions of source code must retain the above copyright
11// notice, this list of conditions and the following disclaimer.
12// * Redistributions in binary form must reproduce the above
13// copyright notice, this list of conditions and the following
14// disclaimer in the documentation and/or other materials provided
15// with the distribution.
16// * Neither the name of the Willow Garage nor the names of its
17// contributors may be used to endorse or promote products derived
18// from this software without specific prior written permission.
19//
20// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31// POSSIBILITY OF SUCH DAMAGE.
32
33#ifndef CONTROL_TOOLBOX__PID_HPP_
34#define CONTROL_TOOLBOX__PID_HPP_
35
36#include <chrono>
37#include <cmath>
38#include <iostream>
39#include <limits>
40#include <string>
41
42#include "fmt/format.h"
43#include "rclcpp/duration.hpp"
44#include "realtime_tools/realtime_thread_safe_box.hpp"
45
46namespace control_toolbox
47{
72{
73public:
74 enum Value : int8_t
75 {
76 UNDEFINED = -1,
77 NONE,
78 LEGACY,
79 BACK_CALCULATION,
80 CONDITIONAL_INTEGRATION
81 };
82
84 : type(UNDEFINED),
85 i_min(-std::numeric_limits<double>::infinity()),
86 i_max(std::numeric_limits<double>::infinity()),
87 legacy_antiwindup(false),
89 error_deadband(std::numeric_limits<double>::epsilon())
90 {
91 }
92
93 void set_type(const std::string & s)
94 {
95 if (s == "back_calculation")
96 {
97 type = BACK_CALCULATION;
98 }
99 else if (s == "conditional_integration")
100 {
101 type = CONDITIONAL_INTEGRATION;
102 }
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 }
110 else if (s == "none")
111 {
112 type = NONE;
113 }
114 else
115 {
116 type = UNDEFINED;
117 throw std::invalid_argument(
118 "AntiWindupStrategy: Unknown antiwindup strategy : '" + s +
119 "'. Valid strategies are: 'back_calculation', 'conditional_integration', 'legacy', "
120 "'none'.");
121 }
122 }
123
124 void validate() const
125 {
126 if (type == UNDEFINED)
127 {
128 throw std::invalid_argument("AntiWindupStrategy is UNDEFINED. Please set a valid type");
129 }
130 if (
131 type == BACK_CALCULATION &&
132 (tracking_time_constant < 0.0 || !std::isfinite(tracking_time_constant)))
133 {
134 throw std::invalid_argument(
135 "AntiWindupStrategy 'back_calculation' requires a valid positive tracking time constant "
136 "(tracking_time_constant)");
137 }
138 if (i_min > 0)
139 {
140 throw std::invalid_argument(
141 fmt::format("PID requires i_min to be smaller or equal to 0 (i_min: {})", i_min));
142 }
143 if (i_max < 0)
144 {
145 throw std::invalid_argument(
146 fmt::format("PID requires i_max to be greater or equal to 0 (i_max: {})", i_max));
147 }
148 if (
149 type != NONE && type != UNDEFINED && type != LEGACY && type != BACK_CALCULATION &&
150 type != CONDITIONAL_INTEGRATION)
151 {
152 throw std::invalid_argument("AntiWindupStrategy has an invalid type");
153 }
154 }
155
156 void print() const
157 {
158 std::cout << "antiwindup_strat: " << to_string() << "\ti_max: " << i_max << ", i_min: " << i_min
159 << "\ttracking_time_constant: " << tracking_time_constant
160 << "\terror_deadband: " << error_deadband << std::endl;
161 }
162
163 operator std::string() const { return to_string(); }
164
165 constexpr bool operator==(Value other) const { return type == other; }
166 constexpr bool operator!=(Value other) const { return type != other; }
167
168 std::string to_string() const
169 {
170 switch (type)
171 {
172 case BACK_CALCULATION:
173 return "back_calculation";
174 case CONDITIONAL_INTEGRATION:
175 return "conditional_integration";
176 case LEGACY:
177 return "legacy";
178 case NONE:
179 return "none";
180 case UNDEFINED:
181 default:
182 return "UNDEFINED";
183 }
184 }
185
186 Value type = UNDEFINED;
187 double i_min = -std::numeric_limits<double>::infinity();
188 double i_max = std::numeric_limits<double>::infinity();
190 bool legacy_antiwindup = false;
192 // tracking_time_constant Specifies the tracking time constant for the 'back_calculation'
193 // strategy. If set to 0.0 a recommended default value will be applied.
197 std::numeric_limits<double>::epsilon();
198};
199
200template <typename T>
201inline bool is_zero(T value, T tolerance = std::numeric_limits<T>::epsilon())
202{
203 return std::abs(value) <= tolerance;
204}
205
206/***************************************************/
281/***************************************************/
282
283class Pid
284{
285public:
289 struct Gains
290 {
301 [[deprecated("Use constructor with AntiWindupStrategy instead.")]]
302 Gains(double p, double i, double d, double i_max, double i_min)
303 : p_gain_(p),
304 i_gain_(i),
305 d_gain_(d),
306 i_max_(i_max),
307 i_min_(i_min),
311 {
312 antiwindup_strat_.type = AntiWindupStrategy::LEGACY;
313 antiwindup_strat_.i_max = i_max;
314 antiwindup_strat_.i_min = i_min;
316 }
317
332 [[deprecated("Use constructor with AntiWindupStrategy instead.")]]
333 Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
334 : p_gain_(p),
335 i_gain_(i),
336 d_gain_(d),
337 i_max_(i_max),
338 i_min_(i_min),
342 {
343 antiwindup_strat_.type = AntiWindupStrategy::LEGACY;
344 antiwindup_strat_.i_max = i_max;
345 antiwindup_strat_.i_min = i_min;
347 }
348
363 double p, double i, double d, double u_max, double u_min,
365 : p_gain_(p),
366 i_gain_(i),
367 d_gain_(d),
370 u_max_(u_max),
371 u_min_(u_min),
372 antiwindup_(antiwindup_strat.legacy_antiwindup),
374 {
375 }
376
377 bool validate(std::string & error_msg) const
378 {
379 if (u_min_ >= u_max_) // is false if any value is nan
380 {
381 error_msg = fmt::format("Gains: u_min ({}) must be less than u_max ({})", u_min_, u_max_);
382 return false;
383 }
384 else if (std::isnan(u_min_) || std::isnan(u_max_))
385 {
386 error_msg = "Gains: u_min and u_max must not be NaN";
387 return false;
388 }
389 try
390 {
391 antiwindup_strat_.validate();
392 }
393 catch (const std::exception & e)
394 {
395 error_msg = e.what();
396 return false;
397 }
398 return true;
399 }
400
401 // Default constructor
402 [[deprecated(
403 "Use constructor with AntiWindupStrategy only. The default constructor might be deleted in "
404 "future")]] Gains()
405 {
406 }
407
408 void print() const
409 {
410 std::cout << "Gains: p: " << p_gain_ << ", i: " << i_gain_ << ", d: " << d_gain_
411 << ", u_max: " << u_max_ << ", u_min: " << u_min_ << std::endl;
412 antiwindup_strat_.print();
413 }
414
415 double p_gain_ = 0.0;
416 double i_gain_ = 0.0;
417 double d_gain_ = 0.0;
418 double i_max_ =
419 std::numeric_limits<double>::infinity();
420 double i_min_ =
421 -std::numeric_limits<double>::infinity();
422 double u_max_ = std::numeric_limits<double>::infinity();
423 double u_min_ = -std::numeric_limits<double>::infinity();
424 bool antiwindup_ = false;
426 };
427
444 [[deprecated("Use constructor with AntiWindupStrategy only.")]]
445 Pid(
446 double p = 0.0, double i = 0.0, double d = 0.0,
447 double i_max = std::numeric_limits<double>::infinity(),
448 double i_min = -std::numeric_limits<double>::infinity(), bool antiwindup = false);
449
464 Pid(
465 double p, double i, double d, double u_max, double u_min,
467
472 Pid(const Pid & source);
473
477 ~Pid();
478
494 [[deprecated("Use initialize with AntiWindupStrategy instead.")]]
495 bool initialize(
496 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
497
513 [[deprecated("Use initialize() instead")]] void initPid(
514 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
515
531 bool initialize(
532 double p, double i, double d, double u_max, double u_min,
534
539 void reset();
540
546 void reset(bool save_i_term);
547
551 void clear_saved_iterm();
552
563 void get_gains(double & p, double & i, double & d, double & i_max, double & i_min);
564
573 [[deprecated("Use get_gains() instead")]] void getGains(
574 double & p, double & i, double & d, double & i_max, double & i_min);
575
590 [[deprecated("Use get_gains overload with AntiWindupStrategy argument.")]]
591 void get_gains(
592 double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
593
606 [[deprecated("Use get_gains() instead")]] void getGains(
607 double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
608
622 void get_gains(
623 double & p, double & i, double & d, double & u_max, double & u_min,
625
633
640 [[deprecated("Use get_gains() instead")]] Gains getGains();
641
648 Gains get_gains_rt() { return gains_; }
649
666 [[deprecated("Use set_gains with AntiWindupStrategy instead.")]]
667 bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
668
683 [[deprecated("Use set_gains() instead")]] void setGains(
684 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
685
702 bool set_gains(
703 double p, double i, double d, double u_max, double u_min,
705
714 bool set_gains(const Gains & gains);
715
722 [[deprecated("Use set_gains() instead")]] void setGains(const Gains & gains);
723
734 [[nodiscard]] double compute_command(double error, const double & dt_s);
735
746 [[deprecated("Use compute_command() instead")]] [[nodiscard]] double computeCommand(
747 double error, uint64_t dt);
748
759 [[nodiscard]] double compute_command(double error, const rcl_duration_value_t & dt_ns);
760
771 [[nodiscard]] double compute_command(double error, const rclcpp::Duration & dt);
772
783 [[nodiscard]] double compute_command(double error, const std::chrono::nanoseconds & dt_ns);
784
796 [[nodiscard]] double compute_command(double error, double error_dot, const double & dt_s);
797
809 [[deprecated("Use compute_command() instead")]] [[nodiscard]] double computeCommand(
810 double error, double error_dot, uint64_t dt);
811
823 [[nodiscard]] double compute_command(
824 double error, double error_dot, const rcl_duration_value_t & dt_ns);
825
837 [[nodiscard]] double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
838
850 [[nodiscard]] double compute_command(
851 double error, double error_dot, const std::chrono::nanoseconds & dt_ns);
852
856 void set_current_cmd(double cmd);
857
861 [[deprecated("Use set_current_cmd() instead")]] void setCurrentCmd(double cmd);
862
866 double get_current_cmd();
867
871 [[deprecated("Use get_current_cmd() instead")]] double getCurrentCmd();
872
876 [[deprecated("Use get_current_pid_errors() instead")]] double getDerivativeError();
877
884 void get_current_pid_errors(double & pe, double & ie, double & de);
885
892 [[deprecated("Use get_current_pid_errors() instead")]] void getCurrentPIDErrors(
893 double & pe, double & ie, double & de);
894
900 {
901 if (this == &source)
902 {
903 return *this;
904 }
905
906 // Copy the realtime box to then new PID class
907 gains_box_ = source.gains_box_;
908
909 // Reset the state of this PID controller
910 reset();
911
912 return *this;
913 }
914
915protected:
916 // local copy of the gains for the RT loop
917 Gains gains_{
918 0.0,
919 0.0,
920 0.0,
921 std::numeric_limits<double>::infinity(),
922 -std::numeric_limits<double>::infinity(),
924 // Store the PID gains in a realtime box to allow dynamic reconfigure to update it without
925 // blocking the realtime update loop
927
928 double p_error_last_ = 0;
929 double p_error_ = 0;
930 double d_error_ = 0;
931 double i_term_ = 0;
932 double cmd_ = 0;
933 double cmd_unsat_ = 0;
934};
935
936} // namespace control_toolbox
937
938#endif // CONTROL_TOOLBOX__PID_HPP_
A Low-pass filter class.
Definition low_pass_filter.hpp:78
Generic Proportional–Integral–Derivative (PID) controller.
Definition pid.hpp:284
void clear_saved_iterm()
Clear the saved integrator output of this controller.
Definition pid.cpp:153
double getDerivativeError()
Return derivative error.
Definition pid.cpp:472
Pid & operator=(const Pid &source)
Custom assignment operator Does not initialize dynamic reconfigure for PID gains.
Definition pid.hpp:899
Gains getGains()
Get PID gains for the controller.
Definition pid.cpp:500
double cmd_unsat_
Definition pid.hpp:933
Gains get_gains()
Get PID gains for the controller.
Definition pid.cpp:190
bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Set PID gains for the controller.
Definition pid.cpp:198
~Pid()
Destructor of Pid class.
Definition pid.cpp:107
bool initialize(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Zeros out Pid values and initialize Pid-gains and term limits.
Definition pid.cpp:111
void set_current_cmd(double cmd)
Set current command for this PID controller.
Definition pid.cpp:443
double p_error_
Definition pid.hpp:929
void reset()
Reset the state of this PID controller.
Definition pid.cpp:134
double getCurrentCmd()
Return current command for this PID controller.
Definition pid.cpp:470
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid.cpp:447
void setCurrentCmd(double cmd)
Set current command for this PID controller.
Definition pid.cpp:468
double d_error_
Definition pid.hpp:930
double computeCommand(double error, uint64_t dt)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is...
Definition pid.cpp:458
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Initialize Pid-gains and term limits.
Definition pid.cpp:484
Gains get_gains_rt()
Get PID gains for the controller.
Definition pid.hpp:648
double get_current_cmd()
Return current command for this PID controller.
Definition pid.cpp:445
double compute_command(double error, const double &dt_s)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is...
Definition pid.cpp:271
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid.cpp:479
double cmd_
Definition pid.hpp:932
double i_term_
Definition pid.hpp:931
void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Set PID gains for the controller.
Definition pid.cpp:502
Definition realtime_thread_safe_box.hpp:68
Definition dither.hpp:46
Antiwindup strategy for PID controllers.
Definition pid.hpp:72
double error_deadband
Definition pid.hpp:196
bool legacy_antiwindup
Definition pid.hpp:190
double tracking_time_constant
Definition pid.hpp:194
double i_max
Definition pid.hpp:188
double i_min
Definition pid.hpp:187
Store gains in a struct to allow easier realtime box usage.
Definition pid.hpp:290
double d_gain_
Definition pid.hpp:417
double i_min_
Definition pid.hpp:420
double i_gain_
Definition pid.hpp:416
Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Optional constructor for passing in values without saturation.
Definition pid.hpp:333
AntiWindupStrategy antiwindup_strat_
Definition pid.hpp:425
Gains(double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
Constructor for passing in values.
Definition pid.hpp:362
double u_min_
Definition pid.hpp:423
Gains(double p, double i, double d, double i_max, double i_min)
Optional constructor for passing in values without antiwindup and saturation.
Definition pid.hpp:302
bool antiwindup_
Definition pid.hpp:424
double u_max_
Definition pid.hpp:422
double i_max_
Definition pid.hpp:418
double p_gain_
Definition pid.hpp:415