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>::quiet_NaN()),
86 i_max(std::numeric_limits<double>::quiet_NaN()),
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 (type == LEGACY && ((i_min > i_max) || !std::isfinite(i_min) || !std::isfinite(i_max)))
139 {
140 throw std::invalid_argument(
141 fmt::format(
142 "AntiWindupStrategy 'legacy' requires i_min < i_max and to be finite (i_min: {}, i_max: "
143 "{})",
144 i_min, i_max));
145 }
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 }
153 if (
154 type != NONE && type != UNDEFINED && type != LEGACY && type != BACK_CALCULATION &&
155 type != CONDITIONAL_INTEGRATION)
156 {
157 throw std::invalid_argument("AntiWindupStrategy has an invalid type");
158 }
159 }
160
161 operator std::string() const { return to_string(); }
162
163 constexpr bool operator==(Value other) const { return type == other; }
164 constexpr bool operator!=(Value other) const { return type != other; }
165
166 std::string to_string() const
167 {
168 switch (type)
169 {
170 case BACK_CALCULATION:
171 return "back_calculation";
172 case CONDITIONAL_INTEGRATION:
173 return "conditional_integration";
174 case LEGACY:
175 return "legacy";
176 case NONE:
177 return "none";
178 case UNDEFINED:
179 default:
180 return "UNDEFINED";
181 }
182 }
183
184 Value type = UNDEFINED;
185 double i_min = std::numeric_limits<double>::quiet_NaN();
186 double i_max = std::numeric_limits<double>::quiet_NaN();
188 bool legacy_antiwindup = false;
190 // tracking_time_constant Specifies the tracking time constant for the 'back_calculation'
191 // strategy. If set to 0.0 a recommended default value will be applied.
195 std::numeric_limits<double>::epsilon();
196};
197
198template <typename T>
199inline bool is_zero(T value, T tolerance = std::numeric_limits<T>::epsilon())
200{
201 return std::abs(value) <= tolerance;
202}
203
204/***************************************************/
279/***************************************************/
280
281class Pid
282{
283public:
287 struct Gains
288 {
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),
309 {
310 antiwindup_strat_.type = AntiWindupStrategy::LEGACY;
311 antiwindup_strat_.i_max = i_max;
312 antiwindup_strat_.i_min = i_min;
314 }
315
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),
340 {
341 antiwindup_strat_.type = AntiWindupStrategy::LEGACY;
342 antiwindup_strat_.i_max = i_max;
343 antiwindup_strat_.i_min = i_min;
345 }
346
361 double p, double i, double d, double u_max, double u_min,
363 : p_gain_(p),
364 i_gain_(i),
365 d_gain_(d),
368 u_max_(u_max),
369 u_min_(u_min),
370 antiwindup_(antiwindup_strat.legacy_antiwindup),
372 {
373 if (std::isnan(u_min) || std::isnan(u_max))
374 {
375 throw std::invalid_argument("Gains: u_min and u_max must not be NaN");
376 }
377 if (u_min > u_max)
378 {
379 std::cout << "Received invalid u_min and u_max values: " << "u_min: " << u_min
380 << ", u_max: " << u_max << ". Setting saturation to false." << std::endl;
381 u_max_ = std::numeric_limits<double>::infinity();
382 u_min_ = -std::numeric_limits<double>::infinity();
383 }
384 }
385
386 bool validate(std::string & error_msg) const
387 {
388 if (i_min_ > i_max_)
389 {
390 error_msg = fmt::format("Gains: i_min ({}) must be less than i_max ({})", i_min_, i_max_);
391 return false;
392 }
393 else if (u_min_ >= u_max_)
394 {
395 error_msg = fmt::format("Gains: u_min ({}) must be less than u_max ({})", u_min_, u_max_);
396 return false;
397 }
398 else if (std::isnan(u_min_) || std::isnan(u_max_))
399 {
400 error_msg = "Gains: u_min and u_max must not be NaN";
401 return false;
402 }
403 try
404 {
405 antiwindup_strat_.validate();
406 }
407 catch (const std::exception & e)
408 {
409 error_msg = e.what();
410 return false;
411 }
412 return true;
413 }
414
415 // Default constructor
416 [[deprecated(
417 "Use constructor with AntiWindupStrategy only. The default constructor might be deleted in "
418 "future")]] Gains()
419 {
420 }
421
422 void print() const
423 {
424 std::cout << "Gains: p: " << p_gain_ << ", i: " << i_gain_ << ", d: " << d_gain_
425 << ", 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;
428 }
429
430 double p_gain_ = 0.0;
431 double i_gain_ = 0.0;
432 double d_gain_ = 0.0;
433 double i_max_ = 0.0;
434 double i_min_ = 0.0;
435 double u_max_ = std::numeric_limits<double>::infinity();
436 double u_min_ = -std::numeric_limits<double>::infinity();
437 bool antiwindup_ = false;
439 };
440
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
476 Pid(
477 double p, double i, double d, double u_max, double u_min,
479
484 Pid(const Pid & source);
485
489 ~Pid();
490
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
525 [[deprecated("Use initialize() instead")]] void initPid(
526 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
527
543 bool initialize(
544 double p, double i, double d, double u_max, double u_min,
546
551 void reset();
552
558 void reset(bool save_i_term);
559
563 void clear_saved_iterm();
564
575 void get_gains(double & p, double & i, double & d, double & i_max, double & i_min);
576
585 [[deprecated("Use get_gains() instead")]] void getGains(
586 double & p, double & i, double & d, double & i_max, double & i_min);
587
602 [[deprecated("Use get_gains overload with AntiWindupStrategy argument.")]]
603 void get_gains(
604 double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
605
618 [[deprecated("Use get_gains() instead")]] void getGains(
619 double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
620
634 void get_gains(
635 double & p, double & i, double & d, double & u_max, double & u_min,
637
645
652 [[deprecated("Use get_gains() instead")]] Gains getGains();
653
660 Gains get_gains_rt() { return gains_; }
661
678 [[deprecated("Use set_gains with AntiWindupStrategy instead.")]]
679 bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
680
695 [[deprecated("Use set_gains() instead")]] void setGains(
696 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
697
714 bool set_gains(
715 double p, double i, double d, double u_max, double u_min,
717
726 bool set_gains(const Gains & gains);
727
734 [[deprecated("Use set_gains() instead")]] void setGains(const Gains & gains);
735
746 [[nodiscard]] double compute_command(double error, const double & dt_s);
747
758 [[deprecated("Use compute_command() instead")]] [[nodiscard]] double computeCommand(
759 double error, uint64_t dt);
760
771 [[nodiscard]] double compute_command(double error, const rcl_duration_value_t & dt_ns);
772
783 [[nodiscard]] double compute_command(double error, const rclcpp::Duration & dt);
784
795 [[nodiscard]] double compute_command(double error, const std::chrono::nanoseconds & dt_ns);
796
808 [[nodiscard]] double compute_command(double error, double error_dot, const double & dt_s);
809
821 [[deprecated("Use compute_command() instead")]] [[nodiscard]] double computeCommand(
822 double error, double error_dot, uint64_t dt);
823
835 [[nodiscard]] double compute_command(
836 double error, double error_dot, const rcl_duration_value_t & dt_ns);
837
849 [[nodiscard]] double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
850
862 [[nodiscard]] double compute_command(
863 double error, double error_dot, const std::chrono::nanoseconds & dt_ns);
864
868 void set_current_cmd(double cmd);
869
873 [[deprecated("Use set_current_cmd() instead")]] void setCurrentCmd(double cmd);
874
878 double get_current_cmd();
879
883 [[deprecated("Use get_current_cmd() instead")]] double getCurrentCmd();
884
888 [[deprecated("Use get_current_pid_errors() instead")]] double getDerivativeError();
889
896 void get_current_pid_errors(double & pe, double & ie, double & de);
897
904 [[deprecated("Use get_current_pid_errors() instead")]] void getCurrentPIDErrors(
905 double & pe, double & ie, double & de);
906
912 {
913 if (this == &source)
914 {
915 return *this;
916 }
917
918 // Copy the realtime box to then new PID class
919 gains_box_ = source.gains_box_;
920
921 // Reset the state of this PID controller
922 reset();
923
924 return *this;
925 }
926
927protected:
928 // local copy of the gains for the RT loop
929 Gains gains_{
930 0.0,
931 0.0,
932 0.0,
933 std::numeric_limits<double>::infinity(),
934 -std::numeric_limits<double>::infinity(),
936 // Store the PID gains in a realtime box to allow dynamic reconfigure to update it without
937 // blocking the realtime update loop
939
940 double p_error_last_ = 0;
941 double p_error_ = 0;
942 double d_error_ = 0;
943 double i_term_ = 0;
944 double cmd_ = 0;
945 double cmd_unsat_ = 0;
946};
947
948} // namespace control_toolbox
949
950#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:282
void clear_saved_iterm()
Clear the saved integrator output of this controller.
Definition pid.cpp:153
double getDerivativeError()
Return derivative error.
Definition pid.cpp:466
Pid & operator=(const Pid &source)
Custom assignment operator Does not initialize dynamic reconfigure for PID gains.
Definition pid.hpp:911
Gains getGains()
Get PID gains for the controller.
Definition pid.cpp:494
double cmd_unsat_
Definition pid.hpp:945
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:437
double p_error_
Definition pid.hpp:941
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:464
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid.cpp:441
void setCurrentCmd(double cmd)
Set current command for this PID controller.
Definition pid.cpp:462
double d_error_
Definition pid.hpp:942
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:452
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:478
Gains get_gains_rt()
Get PID gains for the controller.
Definition pid.hpp:660
double get_current_cmd()
Return current command for this PID controller.
Definition pid.cpp:439
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:267
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid.cpp:473
double cmd_
Definition pid.hpp:944
double i_term_
Definition pid.hpp:943
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:496
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:194
bool legacy_antiwindup
Definition pid.hpp:188
double tracking_time_constant
Definition pid.hpp:192
double i_max
Definition pid.hpp:186
double i_min
Definition pid.hpp:185
Store gains in a struct to allow easier realtime box usage.
Definition pid.hpp:288
double d_gain_
Definition pid.hpp:432
double i_min_
Definition pid.hpp:434
double i_gain_
Definition pid.hpp:431
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:331
AntiWindupStrategy antiwindup_strat_
Definition pid.hpp:438
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:360
double u_min_
Definition pid.hpp:436
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:300
bool antiwindup_
Definition pid.hpp:437
double u_max_
Definition pid.hpp:435
double i_max_
Definition pid.hpp:433
double p_gain_
Definition pid.hpp:430