ros2_control - rolling
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 <memory>
37 #include <string>
38 
39 #include "rclcpp/clock.hpp"
40 #include "rclcpp/duration.hpp"
41 #include "rclcpp/node.hpp"
42 
43 #include "realtime_tools/realtime_buffer.h"
44 #include "realtime_tools/realtime_publisher.h"
45 
46 #include "control_toolbox/visibility_control.hpp"
47 
48 namespace control_toolbox
49 {
50 /***************************************************/
106 /***************************************************/
107 
108 class CONTROL_TOOLBOX_PUBLIC Pid
109 {
110 public:
114  struct Gains
115  {
127  Gains(double p, double i, double d, double i_max, double i_min)
128  : p_gain_(p), i_gain_(i), d_gain_(d), i_max_(i_max), i_min_(i_min), antiwindup_(true)
129  {
130  }
131 
144  Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
145  : p_gain_(p), i_gain_(i), d_gain_(d), i_max_(i_max), i_min_(i_min), antiwindup_(antiwindup)
146  {
147  }
148  // Default constructor
149  Gains() : p_gain_(0.0), i_gain_(0.0), d_gain_(0.0), i_max_(0.0), i_min_(0.0), antiwindup_(false)
150  {
151  }
152  double p_gain_;
153  double i_gain_;
154  double d_gain_;
155  double i_max_;
156  double i_min_;
157  bool antiwindup_;
158  };
159 
174  Pid(
175  double p = 0.0, double i = 0.0, double d = 0.0, double i_max = 0.0, double i_min = -0.0,
176  bool antiwindup = false);
177 
182  Pid(const Pid & source);
183 
187  ~Pid();
188 
202  void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
203 
207  void reset();
208 
217  void getGains(double & p, double & i, double & d, double & i_max, double & i_min);
227  void getGains(
228  double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
229 
234  Gains getGains();
235 
247  void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
248 
255  void setGains(const Gains & gains);
256 
267  [[nodiscard]] double computeCommand(double error, uint64_t dt);
268 
280  [[nodiscard]] double computeCommand(double error, double error_dot, uint64_t dt);
281 
285  void setCurrentCmd(double cmd);
286 
290  double getCurrentCmd();
291 
295  double getDerivativeError();
296 
303  void getCurrentPIDErrors(double & pe, double & ie, double & de);
304 
309  Pid & operator=(const Pid & source)
310  {
311  if (this == &source) {
312  return *this;
313  }
314 
315  // Copy the realtime buffer to then new PID class
316  gains_buffer_ = source.gains_buffer_;
317 
318  // Reset the state of this PID controller
319  reset();
320 
321  return *this;
322  }
323 
324 protected:
325  // Store the PID gains in a realtime buffer to allow dynamic reconfigure to update it without
326  // blocking the realtime update loop
328 
329  double p_error_last_;
330  double p_error_;
331  double i_error_;
332  double d_error_;
333  double cmd_;
334  double error_dot_;
335 };
336 
337 } // namespace control_toolbox
338 
339 #endif // CONTROL_TOOLBOX__PID_HPP_
A basic pid class.
Definition: pid.hpp:109
double error_dot_
Definition: pid.hpp:334
double p_error_
Definition: pid.hpp:330
double p_error_last_
Definition: pid.hpp:329
double d_error_
Definition: pid.hpp:332
Pid & operator=(const Pid &source)
Custom assignment operator Does not initialize dynamic reconfigure for PID gains.
Definition: pid.hpp:309
double cmd_
Definition: pid.hpp:333
double i_error_
Definition: pid.hpp:331
Definition: realtime_buffer.h:49
Definition: dither.hpp:46
Store gains in a struct to allow easier realtime buffer usage.
Definition: pid.hpp:115
double d_gain_
Definition: pid.hpp:154
double i_min_
Definition: pid.hpp:156
double i_gain_
Definition: pid.hpp:153
Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Optional constructor for passing in values.
Definition: pid.hpp:144
Gains(double p, double i, double d, double i_max, double i_min)
Optional constructor for passing in values without antiwindup.
Definition: pid.hpp:127
bool antiwindup_
Definition: pid.hpp:157
double i_max_
Definition: pid.hpp:155
double p_gain_
Definition: pid.hpp:152