ros2_control - humble
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 <iostream>
37#include <memory>
38#include <stdexcept>
39#include <string>
40
41#include "realtime_tools/realtime_buffer.hpp"
42
43namespace control_toolbox
44{
45/***************************************************/
101/***************************************************/
102
103class Pid
104{
105public:
109 struct Gains
110 {
122 Gains(double p, double i, double d, double i_max, double i_min)
123 : p_gain_(p), i_gain_(i), d_gain_(d), i_max_(i_max), i_min_(i_min), antiwindup_(true)
124 {
125 }
126
139 Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
140 : p_gain_(p), i_gain_(i), d_gain_(d), i_max_(i_max), i_min_(i_min), antiwindup_(antiwindup)
141 {
142 }
143 // Default constructor
144 Gains() : p_gain_(0.0), i_gain_(0.0), d_gain_(0.0), i_max_(0.0), i_min_(0.0), antiwindup_(false)
145 {
146 }
147 double p_gain_;
148 double i_gain_;
149 double d_gain_;
150 double i_max_;
151 double i_min_;
153 };
154
169 Pid(
170 double p = 0.0, double i = 0.0, double d = 0.0, double i_max = 0.0, double i_min = -0.0,
171 bool antiwindup = false);
172
177 Pid(const Pid & source);
178
182 ~Pid();
183
197 void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
198
202 void reset();
203
212 void getGains(double & p, double & i, double & d, double & i_max, double & i_min);
222 void getGains(
223 double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
224
229 Gains getGains();
230
242 void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
243
250 void setGains(const Gains & gains);
251
262 [[nodiscard]] double computeCommand(double error, uint64_t dt);
263
275 [[nodiscard]] double computeCommand(double error, double error_dot, uint64_t dt);
276
280 void setCurrentCmd(double cmd);
281
285 double getCurrentCmd();
286
290 double getDerivativeError();
291
298 void getCurrentPIDErrors(double & pe, double & ie, double & de);
299
304 Pid & operator=(const Pid & source)
305 {
306 if (this == &source) {
307 return *this;
308 }
309
310 // Copy the realtime buffer to then new PID class
311 gains_buffer_ = source.gains_buffer_;
312
313 // Reset the state of this PID controller
314 reset();
315
316 return *this;
317 }
318
319protected:
320 // Store the PID gains in a realtime buffer to allow dynamic reconfigure to update it without
321 // blocking the realtime update loop
323
325 double p_error_;
326 double i_error_;
327 double d_error_;
328 double cmd_;
329 double error_dot_;
330};
331
332} // namespace control_toolbox
333
334#endif // CONTROL_TOOLBOX__PID_HPP_
A basic pid class.
Definition pid.hpp:104
double error_dot_
Definition pid.hpp:329
double getDerivativeError()
Return derivative error.
Definition pid.cpp:186
Pid & operator=(const Pid &source)
Custom assignment operator Does not initialize dynamic reconfigure for PID gains.
Definition pid.hpp:304
Gains getGains()
Get PID gains for the controller.
Definition pid.cpp:106
~Pid()
Destructor of Pid class.
Definition pid.cpp:69
double p_error_
Definition pid.hpp:325
void reset()
Reset the state of this PID controller.
Definition pid.cpp:78
double getCurrentCmd()
Return current command for this PID controller.
Definition pid.cpp:188
double p_error_last_
Definition pid.hpp:324
void setCurrentCmd(double cmd)
Set current command for this PID controller.
Definition pid.cpp:184
double d_error_
Definition pid.hpp:327
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:124
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Zeros out Pid values and initialize Pid-gains and integral term limits Does not initialize the node's...
Definition pid.cpp:71
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid.cpp:190
double cmd_
Definition pid.hpp:328
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:108
double i_error_
Definition pid.hpp:326
Definition realtime_buffer.hpp:44
Definition dither.hpp:46
Store gains in a struct to allow easier realtime buffer usage.
Definition pid.hpp:110
double d_gain_
Definition pid.hpp:149
double i_min_
Definition pid.hpp:151
double i_gain_
Definition pid.hpp:148
Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Optional constructor for passing in values.
Definition pid.hpp:139
Gains(double p, double i, double d, double i_max, double i_min)
Optional constructor for passing in values without antiwindup.
Definition pid.hpp:122
bool antiwindup_
Definition pid.hpp:152
double i_max_
Definition pid.hpp:150
double p_gain_
Definition pid.hpp:147