ros2_control - kilted
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{
67{
68public:
69 enum Value : int8_t
70 {
71 UNDEFINED = -1,
72 NONE,
73 BACK_CALCULATION,
74 CONDITIONAL_INTEGRATION
75 };
76
78 : type(NONE),
79 i_max(std::numeric_limits<double>::infinity()),
80 i_min(-std::numeric_limits<double>::infinity()),
82 error_deadband(std::numeric_limits<double>::epsilon())
83 {
84 }
85
86 void set_type(const std::string & s)
87 {
88 if (s == "back_calculation")
89 {
90 type = BACK_CALCULATION;
91 }
92 else if (s == "conditional_integration")
93 {
94 type = CONDITIONAL_INTEGRATION;
95 }
96 else if (s == "none")
97 {
98 type = NONE;
99 }
100 else
101 {
102 type = UNDEFINED;
103 throw std::invalid_argument(
104 "AntiWindupStrategy: Unknown antiwindup strategy : '" + s +
105 "'. Valid strategies are: 'back_calculation', 'conditional_integration', "
106 "'none'.");
107 }
108 }
109
110 void validate() const
111 {
112 if (type == UNDEFINED)
113 {
114 throw std::invalid_argument("AntiWindupStrategy is UNDEFINED. Please set a valid type");
115 }
116 if (
117 type == BACK_CALCULATION &&
118 (tracking_time_constant < 0.0 || !std::isfinite(tracking_time_constant)))
119 {
120 throw std::invalid_argument(
121 "AntiWindupStrategy 'back_calculation' requires a valid positive tracking time constant "
122 "(tracking_time_constant)");
123 }
124 if (i_min > 0)
125 {
126 throw std::invalid_argument(
127 fmt::format("PID requires i_min to be smaller or equal to 0 (i_min: {})", i_min));
128 }
129 if (i_max < 0)
130 {
131 throw std::invalid_argument(
132 fmt::format("PID requires i_max to be greater or equal to 0 (i_max: {})", i_max));
133 }
134 if (
135 type != NONE && type != UNDEFINED && type != BACK_CALCULATION &&
136 type != CONDITIONAL_INTEGRATION)
137 {
138 throw std::invalid_argument("AntiWindupStrategy has an invalid type");
139 }
140 }
141
142 void print() const
143 {
144 std::cout << "antiwindup_strat: " << to_string() << "\ti_max: " << i_max << ", i_min: " << i_min
145 << "\ttracking_time_constant: " << tracking_time_constant
146 << "\terror_deadband: " << error_deadband << std::endl;
147 }
148
149 operator std::string() const { return to_string(); }
150
151 constexpr bool operator==(Value other) const { return type == other; }
152 constexpr bool operator!=(Value other) const { return type != other; }
153
154 std::string to_string() const
155 {
156 switch (type)
157 {
158 case BACK_CALCULATION:
159 return "back_calculation";
160 case CONDITIONAL_INTEGRATION:
161 return "conditional_integration";
162 case NONE:
163 return "none";
164 case UNDEFINED:
165 default:
166 return "UNDEFINED";
167 }
168 }
169
170 Value type = UNDEFINED;
171 double i_max = std::numeric_limits<double>::infinity();
172 double i_min = -std::numeric_limits<double>::infinity();
174 // tracking_time_constant Specifies the tracking time constant for the 'back_calculation'
175 // strategy. If set to 0.0 a recommended default value will be applied.
179 std::numeric_limits<double>::epsilon();
180};
181
182template <typename T>
183inline bool is_zero(T value, T tolerance = std::numeric_limits<T>::epsilon())
184{
185 return std::abs(value) <= tolerance;
186}
187
188/***************************************************/
263/***************************************************/
264
265class Pid
266{
267public:
271 struct Gains
272 {
287 double p, double i, double d, double u_max, double u_min,
289 : p_gain_(p),
290 i_gain_(i),
291 d_gain_(d),
292 u_max_(u_max),
293 u_min_(u_min),
297 {
298 }
299
300 bool validate(std::string & error_msg) const
301 {
302 if (u_min_ >= u_max_) // is false if any value is nan
303 {
304 error_msg = fmt::format("Gains: u_min ({}) must be less than u_max ({})", u_min_, u_max_);
305 return false;
306 }
307 else if (std::isnan(u_min_) || std::isnan(u_max_))
308 {
309 error_msg = "Gains: u_min and u_max must not be NaN";
310 return false;
311 }
312 try
313 {
314 antiwindup_strat_.validate();
315 }
316 catch (const std::exception & e)
317 {
318 error_msg = e.what();
319 return false;
320 }
321 return true;
322 }
323
324 void print() const
325 {
326 std::cout << "Gains: p: " << p_gain_ << ", i: " << i_gain_ << ", d: " << d_gain_
327 << ", u_max: " << u_max_ << ", u_min: " << u_min_ << std::endl;
328 antiwindup_strat_.print();
329 }
330
331 double p_gain_ = 0.0;
332 double i_gain_ = 0.0;
333 double d_gain_ = 0.0;
334 double i_max_ =
335 std::numeric_limits<double>::infinity();
336 double i_min_ =
337 -std::numeric_limits<double>::infinity();
338 double u_max_ = std::numeric_limits<double>::infinity();
339 double u_min_ = -std::numeric_limits<double>::infinity();
341 };
342
357 Pid(
358 double p = 0.0, double i = 0.0, double d = 0.0,
359 double u_max = std::numeric_limits<double>::infinity(),
360 double u_min = -std::numeric_limits<double>::infinity(),
362
367 Pid(const Pid & source);
368
372 ~Pid();
373
389 bool initialize(
390 double p, double i, double d, double u_max, double u_min,
392
397 void reset();
398
404 void reset(bool save_i_term);
405
409 void clear_saved_iterm();
410
424 void get_gains(
425 double & p, double & i, double & d, double & u_max, double & u_min,
427
435
442 Gains get_gains_rt() { return gains_; }
443
460 bool set_gains(
461 double p, double i, double d, double u_max, double u_min,
463
472 bool set_gains(const Gains & gains);
473
484 [[nodiscard]] double compute_command(double error, const double & dt_s);
485
496 [[nodiscard]] double compute_command(double error, const rcl_duration_value_t & dt_ns);
497
508 [[nodiscard]] double compute_command(double error, const rclcpp::Duration & dt);
509
520 [[nodiscard]] double compute_command(double error, const std::chrono::nanoseconds & dt_ns);
521
533 [[nodiscard]] double compute_command(double error, double error_dot, const double & dt_s);
534
546 [[nodiscard]] double compute_command(
547 double error, double error_dot, const rcl_duration_value_t & dt_ns);
548
560 [[nodiscard]] double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
561
573 [[nodiscard]] double compute_command(
574 double error, double error_dot, const std::chrono::nanoseconds & dt_ns);
575
579 void set_current_cmd(double cmd);
580
584 double get_current_cmd();
585
592 void get_current_pid_errors(double & pe, double & ie, double & de);
593
599 {
600 if (this == &source)
601 {
602 return *this;
603 }
604
605 // Copy the realtime box to then new PID class
606 gains_box_ = source.gains_box_;
607
608 // Reset the state of this PID controller
609 reset();
610
611 return *this;
612 }
613
614protected:
615 // local copy of the gains for the RT loop
616 Gains gains_{
617 0.0,
618 0.0,
619 0.0,
620 std::numeric_limits<double>::infinity(),
621 -std::numeric_limits<double>::infinity(),
623 // Store the PID gains in a realtime box to allow dynamic reconfigure to update it without
624 // blocking the realtime update loop
626
627 double p_error_last_ = 0;
628 double p_error_ = 0;
629 double d_error_ = 0;
630 double i_term_ = 0;
631 double cmd_ = 0;
632 double cmd_unsat_ = 0;
633};
634
635} // namespace control_toolbox
636
637#endif // CONTROL_TOOLBOX__PID_HPP_
A Low-pass filter class.
Definition low_pass_filter.hpp:79
Generic Proportional–Integral–Derivative (PID) controller.
Definition pid.hpp:266
void clear_saved_iterm()
Clear the saved integrator output of this controller.
Definition pid.cpp:110
Pid & operator=(const Pid &source)
Custom assignment operator Does not initialize dynamic reconfigure for PID gains.
Definition pid.hpp:598
double cmd_unsat_
Definition pid.hpp:632
Gains get_gains()
Get PID gains for the controller.
Definition pid.cpp:125
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:79
~Pid()
Destructor of Pid class.
Definition pid.cpp:77
void set_current_cmd(double cmd)
Set current command for this PID controller.
Definition pid.cpp:333
double p_error_
Definition pid.hpp:628
void reset()
Reset the state of this PID controller.
Definition pid.cpp:91
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid.cpp:337
double d_error_
Definition pid.hpp:629
Gains get_gains_rt()
Get PID gains for the controller.
Definition pid.hpp:442
double get_current_cmd()
Return current command for this PID controller.
Definition pid.cpp:335
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:186
double cmd_
Definition pid.hpp:631
double i_term_
Definition pid.hpp:630
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:131
Definition realtime_thread_safe_box.hpp:68
Definition dither.hpp:46
Antiwindup strategy for PID controllers.
Definition pid.hpp:67
double error_deadband
Definition pid.hpp:178
double tracking_time_constant
Definition pid.hpp:176
double i_max
Definition pid.hpp:171
double i_min
Definition pid.hpp:172
Store gains in a struct to allow easier realtime box usage.
Definition pid.hpp:272
double d_gain_
Definition pid.hpp:333
double i_min_
Definition pid.hpp:336
double i_gain_
Definition pid.hpp:332
AntiWindupStrategy antiwindup_strat_
Definition pid.hpp:340
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:286
double u_min_
Definition pid.hpp:339
double u_max_
Definition pid.hpp:338
double i_max_
Definition pid.hpp:334
double p_gain_
Definition pid.hpp:331