Go to the documentation of this file.
17 #ifndef GZ_MATH_PID_HH_
18 #define GZ_MATH_PID_HH_
22 #include <gz/math/config.hh>
29 inline namespace IGNITION_MATH_VERSION_NAMESPACE {
38 class IGNITION_MATH_VISIBLE
PID
57 public:
PID(
const double _p = 0.0,
58 const double _i = 0.0,
59 const double _d = 0.0,
60 const double _imax = -1.0,
61 const double _imin = 0.0,
62 const double _cmdMax = -1.0,
63 const double _cmdMin = 0.0,
64 const double _cmdOffset = 0.0);
67 public: ~
PID() =
default;
86 public:
void Init(
const double _p = 0.0,
87 const double _i = 0.0,
88 const double _d = 0.0,
89 const double _imax = -1.0,
90 const double _imin = 0.0,
91 const double _cmdMax = -1.0,
92 const double _cmdMin = 0.0,
93 const double _cmdOffset = 0.0);
97 public:
void SetPGain(
const double _p);
101 public:
void SetIGain(
const double _i);
105 public:
void SetDGain(
const double _d);
109 public:
void SetIMax(
const double _i);
113 public:
void SetIMin(
const double _i);
117 public:
void SetCmdMax(
const double _c);
121 public:
void SetCmdMin(
const double _c);
126 public:
void SetCmdOffset(
const double _c);
130 public:
double PGain()
const;
134 public:
double IGain()
const;
138 public:
double DGain()
const;
142 public:
double IMax()
const;
146 public:
double IMin()
const;
150 public:
double CmdMax()
const;
154 public:
double CmdMin()
const;
158 public:
double CmdOffset()
const;
171 public:
double Update(
const double _error,
182 public:
double Update(
const double _error,
187 public:
void SetCmd(
const double _cmd);
191 public:
double Cmd()
const;
197 public:
void Errors(
double &_pe,
double &_ie,
double &_de)
const;
202 public:
PID &operator=(
const PID &_p);
205 public:
void Reset();
208 private:
double pErrLast = 0.0;
211 private:
double pErr = 0.0;
214 private:
double iErr = 0.0;
217 private:
double dErr = 0.0;
220 private:
double pGain;
223 private:
double iGain = 0.0;
226 private:
double dGain = 0.0;
229 private:
double iMax = -1.0;
232 private:
double iMin = 0.0;
235 private:
double cmd = 0.0;
238 private:
double cmdMax = -1.0;
241 private:
double cmdMin = 0.0;
244 private:
double cmdOffset = 0.0;
Definition: gz/math/AdditivelySeparableScalarField3.hh:27
void SetCmdOffset(const double _c)
Set the offset value for the command, which is added to the result of the PID controller.
void SetIGain(const double _i)
Set the integral Gain.
double CmdMin() const
Get the minimun value for the command.
double CmdMax() const
Get the maximum value for the command.
double Update(const double _error, double _errorRate, const std::chrono::duration< double > &_dt)
Update the Pid loop with nonuniform time step size.
double IMin() const
Get the integral lower limit.
double PGain() const
Get the proportional Gain.
void Errors(double &_pe, double &_ie, double &_de) const
Return PID error terms for the controller.
~PID()=default
Destructor.
void SetDGain(const double _d)
Set the derivative Gain.
double Cmd() const
Return current command for this PID controller.
void Init(const double _p=0.0, const double _i=0.0, const double _d=0.0, const double _imax=-1.0, const double _imin=0.0, const double _cmdMax=-1.0, const double _cmdMin=0.0, const double _cmdOffset=0.0)
Initialize PID-gains and integral term limits:[iMax:iMin]-[I1:I2].
void SetCmdMax(const double _c)
Set the maximum value for the command.
void SetCmdMin(const double _c)
Set the minimum value for the command.
Generic PID controller class. Generic proportional-integral-derivative controller class that keeps tr...
Definition: gz/math/PID.hh:38
void Reset()
Reset the errors and command.
void SetIMax(const double _i)
Set the integral upper limit.
void SetIMin(const double _i)
Set the integral lower limit.
PID & operator=(const PID &_p)
Assignment operator.
double IGain() const
Get the integral Gain.
void SetCmd(const double _cmd)
Set current target command for this PID controller.
PID(const double _p=0.0, const double _i=0.0, const double _d=0.0, const double _imax=-1.0, const double _imin=0.0, const double _cmdMax=-1.0, const double _cmdMin=0.0, const double _cmdOffset=0.0)
Constructor, zeros out Pid values when created and initialize Pid-gains and integral term limits:[iMa...
double DGain() const
Get the derivative Gain.
double IMax() const
Get the integral upper limit.
void SetPGain(const double _p)
Set the proportional Gain.
double CmdOffset() const
Get the offset value for the command.