ros2_control - rolling
Loading...
Searching...
No Matches
pid.hpp
1// Copyright (c) 2008, Willow Garage, Inc.
2//
3// Redistribution and use in source and binary forms, with or without
4// modification, are permitted provided that the following conditions are met:
5//
6// * Redistributions of source code must retain the above copyright
7// notice, this list of conditions and the following disclaimer.
8//
9// * Redistributions in binary form must reproduce the above copyright
10// notice, this list of conditions and the following disclaimer in the
11// documentation and/or other materials provided with the distribution.
12//
13// * Neither the name of the Willow Garage nor the names of its
14// contributors may be used to endorse or promote products derived from
15// this software without specific prior written permission.
16//
17// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27// POSSIBILITY OF SUCH DAMAGE.
28
29#ifndef CONTROL_TOOLBOX__PID_HPP_
30#define CONTROL_TOOLBOX__PID_HPP_
31
32#include <chrono>
33#include <cmath>
34#include <iostream>
35#include <limits>
36#include <string>
37
38#include "fmt/format.h"
39#include "rclcpp/duration.hpp"
40#include "realtime_tools/realtime_thread_safe_box.hpp"
41
42namespace control_toolbox
43{
63{
64public:
65 enum Value : int8_t
66 {
67 UNDEFINED = -1,
68 NONE,
69 BACK_CALCULATION,
70 CONDITIONAL_INTEGRATION
71 };
72
74 : type(NONE),
75 i_max(std::numeric_limits<double>::infinity()),
76 i_min(-std::numeric_limits<double>::infinity()),
78 error_deadband(std::numeric_limits<double>::epsilon())
79 {
80 }
81
82 void set_type(const std::string & s)
83 {
84 if (s == "back_calculation")
85 {
86 type = BACK_CALCULATION;
87 }
88 else if (s == "conditional_integration")
89 {
90 type = CONDITIONAL_INTEGRATION;
91 }
92 else if (s == "none")
93 {
94 type = NONE;
95 }
96 else
97 {
98 type = UNDEFINED;
99 throw std::invalid_argument(
100 "AntiWindupStrategy: Unknown antiwindup strategy : '" + s +
101 "'. Valid strategies are: 'back_calculation', 'conditional_integration', "
102 "'none'.");
103 }
104 }
105
106 void validate() const
107 {
108 if (type == UNDEFINED)
109 {
110 throw std::invalid_argument("AntiWindupStrategy is UNDEFINED. Please set a valid type");
111 }
112 if (
113 type == BACK_CALCULATION &&
114 (tracking_time_constant < 0.0 || !std::isfinite(tracking_time_constant)))
115 {
116 throw std::invalid_argument(
117 "AntiWindupStrategy 'back_calculation' requires a valid positive tracking time constant "
118 "(tracking_time_constant)");
119 }
120 if (i_min > 0)
121 {
122 throw std::invalid_argument(
123 fmt::format("PID requires i_min to be smaller or equal to 0 (i_min: {})", i_min));
124 }
125 if (i_max < 0)
126 {
127 throw std::invalid_argument(
128 fmt::format("PID requires i_max to be greater or equal to 0 (i_max: {})", i_max));
129 }
130 if (
131 type != NONE && type != UNDEFINED && type != BACK_CALCULATION &&
132 type != CONDITIONAL_INTEGRATION)
133 {
134 throw std::invalid_argument("AntiWindupStrategy has an invalid type");
135 }
136 }
137
138 void print() const
139 {
140 std::cout << "antiwindup_strat: " << to_string() << "\ti_max: " << i_max << ", i_min: " << i_min
141 << "\ttracking_time_constant: " << tracking_time_constant
142 << "\terror_deadband: " << error_deadband << std::endl;
143 }
144
145 operator std::string() const { return to_string(); }
146
147 constexpr bool operator==(Value other) const { return type == other; }
148 constexpr bool operator!=(Value other) const { return type != other; }
149
150 std::string to_string() const
151 {
152 switch (type)
153 {
154 case BACK_CALCULATION:
155 return "back_calculation";
156 case CONDITIONAL_INTEGRATION:
157 return "conditional_integration";
158 case NONE:
159 return "none";
160 case UNDEFINED:
161 default:
162 return "UNDEFINED";
163 }
164 }
165
166 Value type = UNDEFINED;
167 double i_max = std::numeric_limits<double>::infinity();
168 double i_min = -std::numeric_limits<double>::infinity();
170 // tracking_time_constant Specifies the tracking time constant for the 'back_calculation'
171 // strategy. If set to 0.0 a recommended default value will be applied.
175 std::numeric_limits<double>::epsilon();
176};
177
178template <typename T>
179inline bool is_zero(T value, T tolerance = std::numeric_limits<T>::epsilon())
180{
181 return std::abs(value) <= tolerance;
182}
183
184/***************************************************/
259/***************************************************/
260
261class Pid
262{
263public:
267 struct Gains
268 {
283 double p, double i, double d, double u_max, double u_min,
284 const AntiWindupStrategy & antiwindup_strat)
285 : p_gain_(p),
286 i_gain_(i),
287 d_gain_(d),
288 u_max_(u_max),
289 u_min_(u_min),
290 antiwindup_strat_(antiwindup_strat)
291 {
292 }
293
294 bool validate(std::string & error_msg) const
295 {
296 if (u_min_ >= u_max_) // is false if any value is nan
297 {
298 error_msg = fmt::format("Gains: u_min ({}) must be less than u_max ({})", u_min_, u_max_);
299 return false;
300 }
301 else if (std::isnan(u_min_) || std::isnan(u_max_))
302 {
303 error_msg = "Gains: u_min and u_max must not be NaN";
304 return false;
305 }
306 try
307 {
308 antiwindup_strat_.validate();
309 }
310 catch (const std::exception & e)
311 {
312 error_msg = e.what();
313 return false;
314 }
315 return true;
316 }
317
318 void print() const
319 {
320 std::cout << "Gains: p: " << p_gain_ << ", i: " << i_gain_ << ", d: " << d_gain_
321 << ", u_max: " << u_max_ << ", u_min: " << u_min_ << std::endl;
322 antiwindup_strat_.print();
323 }
324
325 double p_gain_ = 0.0;
326 double i_gain_ = 0.0;
327 double d_gain_ = 0.0;
328 double u_max_ = std::numeric_limits<double>::infinity();
329 double u_min_ = -std::numeric_limits<double>::infinity();
331 };
332
347 Pid(
348 double p = 0.0, double i = 0.0, double d = 0.0,
349 double u_max = std::numeric_limits<double>::infinity(),
350 double u_min = -std::numeric_limits<double>::infinity(),
351 const AntiWindupStrategy & antiwindup_strat = AntiWindupStrategy());
352
357 Pid(const Pid & source);
358
362 ~Pid();
363
379 bool initialize(
380 double p, double i, double d, double u_max, double u_min,
381 const AntiWindupStrategy & antiwindup_strat);
382
387 void reset();
388
394 void reset(bool save_i_term);
395
399 void clear_saved_iterm();
400
414 void get_gains(
415 double & p, double & i, double & d, double & u_max, double & u_min,
416 AntiWindupStrategy & antiwindup_strat);
417
425
432 Gains get_gains_rt() { return gains_; }
433
450 bool set_gains(
451 double p, double i, double d, double u_max, double u_min,
452 const AntiWindupStrategy & antiwindup_strat);
453
462 bool set_gains(const Gains & gains);
463
474 [[nodiscard]] double compute_command(double error, const double & dt_s);
475
486 [[nodiscard]] double compute_command(double error, const rcl_duration_value_t & dt_ns);
487
498 [[nodiscard]] double compute_command(double error, const rclcpp::Duration & dt);
499
510 [[nodiscard]] double compute_command(double error, const std::chrono::nanoseconds & dt_ns);
511
523 [[nodiscard]] double compute_command(double error, double error_dot, const double & dt_s);
524
536 [[nodiscard]] double compute_command(
537 double error, double error_dot, const rcl_duration_value_t & dt_ns);
538
550 [[nodiscard]] double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
551
563 [[nodiscard]] double compute_command(
564 double error, double error_dot, const std::chrono::nanoseconds & dt_ns);
565
569 void set_current_cmd(double cmd);
570
574 double get_current_cmd();
575
582 void get_current_pid_errors(double & pe, double & ie, double & de);
583
588 Pid & operator=(const Pid & source)
589 {
590 if (this == &source)
591 {
592 return *this;
593 }
594
595 // Copy the realtime box to then new PID class
596 gains_box_ = source.gains_box_;
597
598 // Reset the state of this PID controller
599 reset();
600
601 return *this;
602 }
603
604protected:
605 // local copy of the gains for the RT loop
606 Gains gains_{
607 0.0,
608 0.0,
609 0.0,
610 std::numeric_limits<double>::infinity(),
611 -std::numeric_limits<double>::infinity(),
613 // Store the PID gains in a realtime box to allow dynamic reconfigure to update it without
614 // blocking the realtime update loop
616
617 double p_error_last_ = 0;
618 double p_error_ = 0;
619 double d_error_ = 0;
620 double i_term_ = 0;
621 double cmd_ = 0;
622 double cmd_unsat_ = 0;
623};
624
625} // namespace control_toolbox
626
627#endif // CONTROL_TOOLBOX__PID_HPP_
Generic Proportional–Integral–Derivative (PID) controller.
Definition pid.hpp:262
void clear_saved_iterm()
Clear the saved integrator output of this controller.
Definition pid.cpp:106
Pid & operator=(const Pid &source)
Custom assignment operator Does not initialize dynamic reconfigure for PID gains.
Definition pid.hpp:588
double cmd_unsat_
Definition pid.hpp:622
Gains get_gains()
Get PID gains for the controller.
Definition pid.cpp:121
bool initialize(double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
Initialize Pid-gains and term limits.
Definition pid.cpp:75
~Pid()
Destructor of Pid class.
Definition pid.cpp:73
void set_current_cmd(double cmd)
Set current command for this PID controller.
Definition pid.cpp:329
double p_error_
Definition pid.hpp:618
void reset()
Reset the state of this PID controller.
Definition pid.cpp:87
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid.cpp:333
double d_error_
Definition pid.hpp:619
Gains get_gains_rt()
Get PID gains for the controller.
Definition pid.hpp:432
double get_current_cmd()
Return current command for this PID controller.
Definition pid.cpp:331
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:182
double cmd_
Definition pid.hpp:621
double i_term_
Definition pid.hpp:620
bool set_gains(double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
Set PID gains for the controller.
Definition pid.cpp:127
Definition realtime_thread_safe_box.hpp:68
Definition dither.hpp:42
Antiwindup strategy for PID controllers.
Definition pid.hpp:63
double error_deadband
Definition pid.hpp:174
double tracking_time_constant
Definition pid.hpp:172
double i_max
Definition pid.hpp:167
double i_min
Definition pid.hpp:168
Store gains in a struct to allow easier realtime box usage.
Definition pid.hpp:268
double d_gain_
Definition pid.hpp:327
double i_gain_
Definition pid.hpp:326
AntiWindupStrategy antiwindup_strat_
Definition pid.hpp:330
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:282
double u_min_
Definition pid.hpp:329
double u_max_
Definition pid.hpp:328
double p_gain_
Definition pid.hpp:325