ros2_control - iron
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 { std::cout << string() << std::endl; }
157
158 std::string string() const
159 {
160 return fmt::format(
161 "antiwindup_strat: {}\ti_max: {}\ti_min: {}\ttracking_time_constant: {}\terror_deadband: {}",
163 }
164
165 operator std::string() const { return to_string(); }
166
167 constexpr bool operator==(Value other) const { return type == other; }
168 constexpr bool operator!=(Value other) const { return type != other; }
169
170 std::string to_string() const
171 {
172 switch (type)
173 {
174 case BACK_CALCULATION:
175 return "back_calculation";
176 case CONDITIONAL_INTEGRATION:
177 return "conditional_integration";
178 case LEGACY:
179 return "legacy";
180 case NONE:
181 return "none";
182 case UNDEFINED:
183 default:
184 return "UNDEFINED";
185 }
186 }
187
188 Value type = UNDEFINED;
189 double i_min = -std::numeric_limits<double>::infinity();
190 double i_max = std::numeric_limits<double>::infinity();
192 bool legacy_antiwindup = false;
194 // tracking_time_constant Specifies the tracking time constant for the 'back_calculation'
195 // strategy. If set to 0.0 a recommended default value will be applied.
199 std::numeric_limits<double>::epsilon();
200};
201
202template <typename T>
203inline bool is_zero(T value, T tolerance = std::numeric_limits<T>::epsilon())
204{
205 return std::abs(value) <= tolerance;
206}
207
208/***************************************************/
283/***************************************************/
284
285class Pid
286{
287public:
291 struct Gains
292 {
303 [[deprecated("Use constructor with AntiWindupStrategy instead.")]]
304 Gains(double p, double i, double d, double i_max, double i_min)
305 : p_gain_(p),
306 i_gain_(i),
307 d_gain_(d),
308 i_max_(i_max),
309 i_min_(i_min),
313 {
314 antiwindup_strat_.type = AntiWindupStrategy::LEGACY;
315 antiwindup_strat_.i_max = i_max;
316 antiwindup_strat_.i_min = i_min;
318 }
319
334 [[deprecated("Use constructor with AntiWindupStrategy instead.")]]
335 Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
336 : p_gain_(p),
337 i_gain_(i),
338 d_gain_(d),
339 i_max_(i_max),
340 i_min_(i_min),
344 {
345 antiwindup_strat_.type = AntiWindupStrategy::LEGACY;
346 antiwindup_strat_.i_max = i_max;
347 antiwindup_strat_.i_min = i_min;
349 }
350
365 double p, double i, double d, double u_max, double u_min,
367 : p_gain_(p),
368 i_gain_(i),
369 d_gain_(d),
372 u_max_(u_max),
373 u_min_(u_min),
374 antiwindup_(antiwindup_strat.legacy_antiwindup),
376 {
377 }
378
379 bool validate(std::string & error_msg) const
380 {
381 if (u_min_ >= u_max_) // is false if any value is nan
382 {
383 error_msg = fmt::format("Gains: u_min ({}) must be less than u_max ({})", u_min_, u_max_);
384 return false;
385 }
386 else if (std::isnan(u_min_) || std::isnan(u_max_))
387 {
388 error_msg = "Gains: u_min and u_max must not be NaN";
389 return false;
390 }
391 try
392 {
393 antiwindup_strat_.validate();
394 }
395 catch (const std::exception & e)
396 {
397 error_msg = e.what();
398 return false;
399 }
400 return true;
401 }
402
403 // Default constructor
404 [[deprecated(
405 "Use constructor with AntiWindupStrategy only. The default constructor might be deleted in "
406 "future")]] Gains()
407 {
408 }
409
410 void print() const { std::cout << string() << std::endl; }
411
412 std::string string() const
413 {
414 return fmt::format(
415 "Gains(p: {}, i: {}, d: {}, u_max: {}, u_min: {}, antiwindup_strat: '{}')", p_gain_,
417 }
418
419 double p_gain_ = 0.0;
420 double i_gain_ = 0.0;
421 double d_gain_ = 0.0;
422 double i_max_ =
423 std::numeric_limits<double>::infinity();
424 double i_min_ =
425 -std::numeric_limits<double>::infinity();
426 double u_max_ = std::numeric_limits<double>::infinity();
427 double u_min_ = -std::numeric_limits<double>::infinity();
428 bool antiwindup_ = false;
430 };
431
448 [[deprecated("Use constructor with AntiWindupStrategy only.")]]
449 Pid(
450 double p = 0.0, double i = 0.0, double d = 0.0,
451 double i_max = std::numeric_limits<double>::infinity(),
452 double i_min = -std::numeric_limits<double>::infinity(), bool antiwindup = false);
453
468 Pid(
469 double p, double i, double d, double u_max, double u_min,
471
476 Pid(const Pid & source);
477
481 ~Pid();
482
498 [[deprecated("Use initialize with AntiWindupStrategy instead.")]]
499 bool initialize(
500 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
501
517 [[deprecated("Use initialize() instead")]] void initPid(
518 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
519
535 bool initialize(
536 double p, double i, double d, double u_max, double u_min,
538
543 void reset();
544
550 void reset(bool save_i_term);
551
555 void clear_saved_iterm();
556
567 void get_gains(double & p, double & i, double & d, double & i_max, double & i_min);
568
577 [[deprecated("Use get_gains() instead")]] void getGains(
578 double & p, double & i, double & d, double & i_max, double & i_min);
579
594 [[deprecated("Use get_gains overload with AntiWindupStrategy argument.")]]
595 void get_gains(
596 double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
597
610 [[deprecated("Use get_gains() instead")]] void getGains(
611 double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
612
626 void get_gains(
627 double & p, double & i, double & d, double & u_max, double & u_min,
629
637
644 [[deprecated("Use get_gains() instead")]] Gains getGains();
645
652 Gains get_gains_rt() { return gains_; }
653
670 [[deprecated("Use set_gains with AntiWindupStrategy instead.")]]
671 bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
672
687 [[deprecated("Use set_gains() instead")]] void setGains(
688 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
689
706 bool set_gains(
707 double p, double i, double d, double u_max, double u_min,
709
718 bool set_gains(const Gains & gains);
719
726 [[deprecated("Use set_gains() instead")]] void setGains(const Gains & gains);
727
738 [[nodiscard]] double compute_command(double error, const double & dt_s);
739
750 [[deprecated("Use compute_command() instead")]] [[nodiscard]] double computeCommand(
751 double error, uint64_t dt);
752
763 [[nodiscard]] double compute_command(double error, const rcl_duration_value_t & dt_ns);
764
775 [[nodiscard]] double compute_command(double error, const rclcpp::Duration & dt);
776
787 [[nodiscard]] double compute_command(double error, const std::chrono::nanoseconds & dt_ns);
788
800 [[nodiscard]] double compute_command(double error, double error_dot, const double & dt_s);
801
813 [[deprecated("Use compute_command() instead")]] [[nodiscard]] double computeCommand(
814 double error, double error_dot, uint64_t dt);
815
827 [[nodiscard]] double compute_command(
828 double error, double error_dot, const rcl_duration_value_t & dt_ns);
829
841 [[nodiscard]] double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
842
854 [[nodiscard]] double compute_command(
855 double error, double error_dot, const std::chrono::nanoseconds & dt_ns);
856
860 void set_current_cmd(double cmd);
861
865 [[deprecated("Use set_current_cmd() instead")]] void setCurrentCmd(double cmd);
866
870 double get_current_cmd();
871
875 [[deprecated("Use get_current_cmd() instead")]] double getCurrentCmd();
876
880 [[deprecated("Use get_current_pid_errors() instead")]] double getDerivativeError();
881
888 void get_current_pid_errors(double & pe, double & ie, double & de);
889
896 [[deprecated("Use get_current_pid_errors() instead")]] void getCurrentPIDErrors(
897 double & pe, double & ie, double & de);
898
904 {
905 if (this == &source)
906 {
907 return *this;
908 }
909
910 // Copy the realtime box to then new PID class
911 gains_box_ = source.gains_box_;
912
913 // Reset the state of this PID controller
914 reset();
915
916 return *this;
917 }
918
919protected:
920 // local copy of the gains for the RT loop
921 Gains gains_{
922 0.0,
923 0.0,
924 0.0,
925 std::numeric_limits<double>::infinity(),
926 -std::numeric_limits<double>::infinity(),
928 // Store the PID gains in a realtime box to allow dynamic reconfigure to update it without
929 // blocking the realtime update loop
931
932 double p_error_last_ = 0;
933 double p_error_ = 0;
934 double d_error_ = 0;
935 double i_term_ = 0;
936 double cmd_ = 0;
937 double cmd_unsat_ = 0;
938};
939
940} // namespace control_toolbox
941
942#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:286
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:903
Gains getGains()
Get PID gains for the controller.
Definition pid.cpp:500
double cmd_unsat_
Definition pid.hpp:937
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:933
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:934
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:652
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:936
double i_term_
Definition pid.hpp:935
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:198
bool legacy_antiwindup
Definition pid.hpp:192
double tracking_time_constant
Definition pid.hpp:196
double i_max
Definition pid.hpp:190
double i_min
Definition pid.hpp:189
Store gains in a struct to allow easier realtime box usage.
Definition pid.hpp:292
double d_gain_
Definition pid.hpp:421
double i_min_
Definition pid.hpp:424
double i_gain_
Definition pid.hpp:420
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:335
AntiWindupStrategy antiwindup_strat_
Definition pid.hpp:429
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:364
double u_min_
Definition pid.hpp:427
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:304
bool antiwindup_
Definition pid.hpp:428
double u_max_
Definition pid.hpp:426
double i_max_
Definition pid.hpp:422
double p_gain_
Definition pid.hpp:419