- 3.0.2 core module.
PIDController.h
Go to the documentation of this file.
1 /**********************************************************************************************************************
2 This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-toolbox), copyright by ETH Zurich.
3 Licensed under the BSD-2 license (see LICENSE file in main directory)
4 **********************************************************************************************************************/
5 
6 #pragma once
7 
8 #include <limits>
9 
10 namespace ct {
11 namespace core {
12 
14 
30 template <typename SCALAR = double>
32 {
33 public:
35 
38  struct parameters_t
39  {
41  SCALAR ki = SCALAR(0.0),
42  SCALAR kd = SCALAR(0.0),
43  Time dt_ = 0.01,
44  SCALAR Imax_ = std::numeric_limits<SCALAR>::max(),
45  SCALAR uMax_ = std::numeric_limits<SCALAR>::max(),
46  SCALAR uMin_ = -std::numeric_limits<SCALAR>::max())
47  : k_p(kp), k_i(ki), k_d(kd), dt(dt_), Imax(Imax_), uMax(uMax_), uMin(uMin_)
48  {
49  }
57  };
58 
60 
63  struct setpoint_t
64  {
65  setpoint_t(SCALAR stateDes = SCALAR(0.0), SCALAR stateDevDes = SCALAR(0.0))
66  : stateDesired_(stateDes), stateDerivativeDesired_(stateDevDes)
67  {
68  }
69 
72  };
73 
75 
80  PIDController(const parameters_t& parameters = parameters_t(), const setpoint_t& setpoint = setpoint_t());
81 
83  PIDController(const PIDController& other);
84 
86  virtual ~PIDController();
87 
89  PIDController* clone() const;
91 
95  void setInitialState(const SCALAR& state);
97 
100  void setDesiredState(const SCALAR& state);
102 
106  void setDesiredState(const SCALAR& state, const SCALAR& stateDerivative);
107 
109 
115  SCALAR computeControl(const SCALAR& state, const Time& t);
116 
118 
125  SCALAR computeControl(const SCALAR& state, const SCALAR& stateDerivative, const Time& t);
126 
128 
132  void changeParameters(const parameters_t& parameters);
134 
140 
143  void reset();
144 
145 protected:
148 
151 
152 private:
154  void saturateControl(SCALAR& u);
155 
157  void computeI(const SCALAR& error);
158 };
159 
160 } // namespace core
161 } // namespace ct
setpoint_t setpoint_
the parameters of the PID controller
Definition: PIDController.h:150
parameters_t & Parameters()
returns a reference to the parameters
Definition: PIDController-impl.h:124
parameters_t parameters_
the current I part (integrated)
Definition: PIDController.h:149
SCALAR dt
differential gain
Definition: PIDController.h:53
void reset()
resets the controller
Definition: PIDController-impl.h:130
setpoint_t(SCALAR stateDes=SCALAR(0.0), SCALAR stateDevDes=SCALAR(0.0))
Definition: PIDController.h:65
SCALAR k_d
integral gain
Definition: PIDController.h:52
PIDController * clone() const
clone operator
Definition: PIDController-impl.h:29
CppAD::AD< CppAD::cg::CG< double > > SCALAR
parameters_t(SCALAR kp=SCALAR(0.0), SCALAR ki=SCALAR(0.0), SCALAR kd=SCALAR(0.0), Time dt_=0.01, SCALAR Imax_=std::numeric_limits< SCALAR >::max(), SCALAR uMax_=std::numeric_limits< SCALAR >::max(), SCALAR uMin_=-std::numeric_limits< SCALAR >::max())
Definition: PIDController.h:40
virtual ~PIDController()
destructor
Definition: PIDController-impl.h:24
void setInitialState(const SCALAR &state)
set the initial state
Definition: PIDController-impl.h:35
SCALAR computeControl(const SCALAR &state, const Time &t)
computes the control input based on the current state and time
Definition: PIDController-impl.h:54
SCALAR uMax
anti-windup I-part saturation
Definition: PIDController.h:55
SCALAR stateDesired_
Definition: PIDController.h:70
void setDesiredState(const SCALAR &state)
set the state
Definition: PIDController-impl.h:41
SCALAR stateDerivativeDesired_
desired state
Definition: PIDController.h:71
A standard PIDController.
Definition: PIDController.h:31
SCALAR k_p
Definition: PIDController.h:50
setpoint for the PID controller
Definition: PIDController.h:63
PIDController(const parameters_t &parameters=parameters_t(), const setpoint_t &setpoint=setpoint_t())
default constructor
Definition: PIDController-impl.h:12
SCALAR k_i
proportional gain
Definition: PIDController.h:51
SCALAR uMin
max u output
Definition: PIDController.h:56
SCALAR Imax
timestep for I-part
Definition: PIDController.h:54
SCALAR statePrevious_
Definition: PIDController.h:146
Parameters of a PID Controller.
Definition: PIDController.h:38
void changeParameters(const parameters_t &parameters)
change the control parameters
Definition: PIDController-impl.h:118
SCALAR I_
the previous state used for finite differences
Definition: PIDController.h:147
double Time
Definition: Time.h:11