Generic PID controller class. Generic proportional-integral-derivative controller class that keeps track of PID-error states and control inputs given the state of a system and a user specified target state. It includes a user-adjustable command offset term (feed-forward). More...
#include <gz/math/PID.hh>
Public Member Functions | |
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:[iMax:iMin]-[I1:I2]. | |
double | Cmd () const |
Return current command for this PID controller. | |
double | CmdMax () const |
Get the maximum value for the command. | |
double | CmdMin () const |
Get the minimun value for the command. | |
double | CmdOffset () const |
Get the offset value for the command. | |
double | DGain () const |
Get the derivative Gain. | |
void | Errors (double &_pe, double &_ie, double &_de) const |
Return PID error terms for the controller. | |
double | IGain () const |
Get the integral Gain. | |
double | IMax () const |
Get the integral upper limit. | |
double | IMin () const |
Get the integral lower limit. | |
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]. | |
double | PGain () const |
Get the proportional Gain. | |
void | Reset () |
Reset the errors and command. | |
void | SetCmd (const double _cmd) |
Set current target command for this PID controller. | |
void | SetCmdMax (const double _c) |
Set the maximum value for the command. | |
void | SetCmdMin (const double _c) |
Set the minimum value for the command. | |
void | SetCmdOffset (const double _c) |
Set the offset value for the command, which is added to the result of the PID controller. | |
void | SetDGain (const double _d) |
Set the derivative Gain. | |
void | SetIGain (const double _i) |
Set the integral Gain. | |
void | SetIMax (const double _i) |
Set the integral upper limit. | |
void | SetIMin (const double _i) |
Set the integral lower limit. | |
void | SetPGain (const double _p) |
Set the proportional Gain. | |
double | Update (const double _error, const std::chrono::duration< double > &_dt) |
Update the Pid loop with nonuniform time step size. | |
double | Update (const double _error, double _errorRate, const std::chrono::duration< double > &_dt) |
Update the Pid loop with nonuniform time step size. | |
Detailed Description
Generic PID controller class. Generic proportional-integral-derivative controller class that keeps track of PID-error states and control inputs given the state of a system and a user specified target state. It includes a user-adjustable command offset term (feed-forward).
Constructor & Destructor Documentation
◆ PID()
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:[iMax:iMin]-[I1:I2].
Disable command clamping by setting _cmdMin to a value larger than _cmdMax. Command clamping is disabled by default.
Disable integral clamping by setting _iMin to a value larger than _iMax. Integral clamping is disabled by default.
- Parameters
-
[in] _p The proportional gain. [in] _i The integral gain. [in] _d The derivative gain. [in] _imax The integral upper limit. [in] _imin The integral lower limit. [in] _cmdMax Output max value. [in] _cmdMin Output min value. [in] _cmdOffset Command offset (feed-forward).
Member Function Documentation
◆ Cmd()
◆ CmdMax()
double CmdMax | ( | ) | const |
Get the maximum value for the command.
- Returns
- The maximum value
◆ CmdMin()
double CmdMin | ( | ) | const |
Get the minimun value for the command.
- Returns
- The maximum value
◆ CmdOffset()
double CmdOffset | ( | ) | const |
Get the offset value for the command.
- Returns
- The offset value
◆ DGain()
double DGain | ( | ) | const |
Get the derivative Gain.
- Returns
- The derivative gain value
◆ Errors()
Return PID error terms for the controller.
- Parameters
-
[in] _pe The proportional error. [in] _ie The integral of gain times error. [in] _de The derivative error.
◆ IGain()
double IGain | ( | ) | const |
Get the integral Gain.
- Returns
- The integral gain value
◆ IMax()
double IMax | ( | ) | const |
Get the integral upper limit.
- Returns
- The integral upper limit value
◆ IMin()
double IMin | ( | ) | const |
Get the integral lower limit.
- Returns
- The integral lower limit value
◆ Init()
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].
Disable command clamping by setting _cmdMin to a value larger than _cmdMax. Command clamping is disabled by default.
Disable integral clamping by setting _iMin to a value larger than _iMax. Integral clamping is disabled by default.
- Parameters
-
[in] _p The proportional gain. [in] _i The integral gain. [in] _d The derivative gain. [in] _imax The integral upper limit. [in] _imin The integral lower limit. [in] _cmdMax Output max value. [in] _cmdMin Output min value. [in] _cmdOffset Command offset (feed-forward).
◆ PGain()
double PGain | ( | ) | const |
Get the proportional Gain.
- Returns
- The proportional gain value
◆ Reset()
void Reset | ( | ) |
Reset the errors and command.
◆ SetCmd()
Set current target command for this PID controller.
- Parameters
-
[in] _cmd New command
◆ SetCmdMax()
Set the maximum value for the command.
- Parameters
-
[in] _c The maximum value
◆ SetCmdMin()
Set the minimum value for the command.
- Parameters
-
[in] _c The minimum value
◆ SetCmdOffset()
Set the offset value for the command, which is added to the result of the PID controller.
- Parameters
-
[in] _c The offset value
◆ SetDGain()
◆ SetIGain()
◆ SetIMax()
Set the integral upper limit.
- Parameters
-
[in] _i integral upper limit value
◆ SetIMin()
Set the integral lower limit.
- Parameters
-
[in] _i integral lower limit value
◆ SetPGain()
Set the proportional Gain.
- Parameters
-
[in] _p proportional gain value
◆ Update() [1/2]
Update the Pid loop with nonuniform time step size.
- Parameters
-
[in] _error Error since last call (p_state - p_target). [in] _dt Change in time since last update call. Normally, this is called at every time step, The return value is an updated command to be passed to the object being controlled.
- Returns
- the command value
◆ Update() [2/2]
double Update | ( | const double | _error, |
double | _errorRate, | ||
const std::chrono::duration< double > & | _dt | ||
) |
Update the Pid loop with nonuniform time step size.
- Parameters
-
[in] _error Error since last call (p_state - p_target). [in] _errorRate Estimate of error rate, that can be used when a smoother estimate is available than the finite difference used by Update(const double _error, const std::chrono::duration<double> &_dt) [in] _dt Change in time since last update call. Normally, this is called at every time step, The return value is an updated command to be passed to the object being controlled.
- Returns
- the command value
The documentation for this class was generated from the following file: