ros2_control - rolling
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
38#include "rclcpp/duration.hpp"
39#include "realtime_tools/realtime_buffer.hpp"
40
41namespace control_toolbox
42{
43/***************************************************/
107/***************************************************/
108
109class Pid
110{
111public:
115 struct Gains
116 {
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
146 Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
147 : p_gain_(p), i_gain_(i), d_gain_(d), i_max_(i_max), i_min_(i_min), antiwindup_(antiwindup)
148 {
149 }
150
151 // Default constructor
152 Gains() : p_gain_(0.0), i_gain_(0.0), d_gain_(0.0), i_max_(0.0), i_min_(0.0), antiwindup_(false)
153 {
154 }
155
156 double p_gain_;
157 double i_gain_;
158 double d_gain_;
159 double i_max_;
160 double i_min_;
162 };
163
181 Pid(
182 double p = 0.0, double i = 0.0, double d = 0.0, double i_max = 0.0, double i_min = -0.0,
183 bool antiwindup = false);
184
189 Pid(const Pid & source);
190
194 ~Pid();
195
212 void initialize(
213 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
214
231 [[deprecated("Use initialize() instead")]] void initPid(
232 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
233
238 void reset();
239
245 void reset(bool save_iterm);
246
250 void clear_saved_iterm();
251
260 void get_gains(double & p, double & i, double & d, double & i_max, double & i_min);
261
270 [[deprecated("Use get_gains() instead")]] void getGains(
271 double & p, double & i, double & d, double & i_max, double & i_min);
272
285 void get_gains(
286 double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
287
300 [[deprecated("Use get_gains() instead")]] void getGains(
301 double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);
302
308
313 [[deprecated("Use get_gains() instead")]] Gains getGains();
314
329 void set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
330
345 [[deprecated("Use set_gains() instead")]] void setGains(
346 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
347
354 void set_gains(const Gains & gains);
355
362 [[deprecated("Use set_gains() instead")]] void setGains(const Gains & gains);
363
374 [[nodiscard]] double compute_command(double error, const double & dt_s);
375
386 [[deprecated("Use compute_command() instead")]] [[nodiscard]] double computeCommand(
387 double error, uint64_t dt);
388
399 [[nodiscard]] double compute_command(double error, const rcl_duration_value_t & dt_ns);
400
411 [[nodiscard]] double compute_command(double error, const rclcpp::Duration & dt);
412
423 [[nodiscard]] double compute_command(double error, const std::chrono::nanoseconds & dt_ns);
424
436 [[nodiscard]] double compute_command(double error, double error_dot, const double & dt_s);
437
449 [[deprecated("Use compute_command() instead")]] [[nodiscard]] double computeCommand(
450 double error, double error_dot, uint64_t dt);
451
463 [[nodiscard]] double compute_command(
464 double error, double error_dot, const rcl_duration_value_t & dt_ns);
465
477 [[nodiscard]] double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
478
490 [[nodiscard]] double compute_command(
491 double error, double error_dot, const std::chrono::nanoseconds & dt_ns);
492
496 void set_current_cmd(double cmd);
497
501 [[deprecated("Use set_current_cmd() instead")]] void setCurrentCmd(double cmd);
502
506 double get_current_cmd();
507
511 [[deprecated("Use get_current_cmd() instead")]] double getCurrentCmd();
512
516 [[deprecated("Use get_current_pid_errors() instead")]] double getDerivativeError();
517
524 void get_current_pid_errors(double & pe, double & ie, double & de);
525
532 [[deprecated("Use get_current_pid_errors() instead")]] void getCurrentPIDErrors(
533 double & pe, double & ie, double & de);
534
539 Pid & operator=(const Pid & source)
540 {
541 if (this == &source) {
542 return *this;
543 }
544
545 // Copy the realtime buffer to then new PID class
546 gains_buffer_ = source.gains_buffer_;
547
548 // Reset the state of this PID controller
549 reset();
550
551 return *this;
552 }
553
554protected:
555 // Store the PID gains in a realtime buffer to allow dynamic reconfigure to update it without
556 // blocking the realtime update loop
558
559 double p_error_last_;
560 double p_error_;
561 double i_error_;
562 double d_error_;
563 double cmd_;
564 // TODO(christophfroehlich) remove this -> breaks ABI
565 [[deprecated("Use d_error_")]] double error_dot_;
566};
567
568} // namespace control_toolbox
569
570#endif // CONTROL_TOOLBOX__PID_HPP_
A basic pid class.
Definition pid.hpp:110
void clear_saved_iterm()
Clear the saved integrator output of this controller.
Definition pid.cpp:113
double error_dot_
Definition pid.hpp:565
double getDerivativeError()
Return derivative error.
Definition pid.cpp:273
Pid & operator=(const Pid &source)
Custom assignment operator Does not initialize dynamic reconfigure for PID gains.
Definition pid.hpp:539
Gains getGains()
Get PID gains for the controller.
Definition pid.cpp:299
Gains get_gains()
Get PID gains for the controller.
Definition pid.cpp:137
~Pid()
Destructor of Pid class.
Definition pid.cpp:81
void set_current_cmd(double cmd)
Set current command for this PID controller.
Definition pid.cpp:242
double p_error_
Definition pid.hpp:560
void reset()
Reset the state of this PID controller.
Definition pid.cpp:90
double getCurrentCmd()
Return current command for this PID controller.
Definition pid.cpp:269
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid.cpp:246
void setCurrentCmd(double cmd)
Set current command for this PID controller.
Definition pid.cpp:265
double d_error_
Definition pid.hpp:562
void 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 integral term limits Does not initialize the node's...
Definition pid.cpp:83
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:255
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:284
void 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:139
double get_current_cmd()
Return current command for this PID controller.
Definition pid.cpp:244
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:155
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid.cpp:279
double cmd_
Definition pid.hpp:563
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:303
double i_error_
Definition pid.hpp:561
Definition realtime_buffer.hpp:44
Definition dither.hpp:46
Store gains in a struct to allow easier realtime buffer usage.
Definition pid.hpp:116
double d_gain_
Definition pid.hpp:158
double i_min_
Definition pid.hpp:160
double i_gain_
Definition pid.hpp:157
Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Optional constructor for passing in values.
Definition pid.hpp:146
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:161
double i_max_
Definition pid.hpp:159
double p_gain_
Definition pid.hpp:156