Generic PID controller class. More...
#include <ignition/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]. | |
~PID ()=default | |
Destructor. | |
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 maximum 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]. | |
PID & | operator= (const PID &_p) |
Assignment operator. | |
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 derivtive 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. | |
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).
ignition::math::IGNITION_MATH_VERSION_NAMESPACE::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.
[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). |
|
default |
Destructor.
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::Cmd | ( | ) | const |
Return current command for this PID controller.
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::CmdMax | ( | ) | const |
Get the maximum value for the command.
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::CmdMin | ( | ) | const |
Get the maximum value for the command.
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::CmdOffset | ( | ) | const |
Get the offset value for the command.
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::DGain | ( | ) | const |
Get the derivative Gain.
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::Errors | ( | double & | _pe, |
double & | _ie, | ||
double & | _de ) const |
Return PID error terms for the controller.
[in] | _pe | The proportional error. |
[in] | _ie | The integral of gain times error. |
[in] | _de | The derivative error. |
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::IGain | ( | ) | const |
Get the integral Gain.
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::IMax | ( | ) | const |
Get the integral upper limit.
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::IMin | ( | ) | const |
Get the integral lower limit.
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::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.
[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). |
Assignment operator.
[in] | _p | a reference to a PID to assign values from |
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::PGain | ( | ) | const |
Get the proportional Gain.
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::Reset | ( | ) |
Reset the errors and command.
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::SetCmd | ( | const double | _cmd | ) |
Set current target command for this PID controller.
[in] | _cmd | New command |
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::SetCmdMax | ( | const double | _c | ) |
Set the maximum value for the command.
[in] | _c | The maximum value |
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::SetCmdMin | ( | const double | _c | ) |
Set the minimum value for the command.
[in] | _c | The minimum value |
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::SetCmdOffset | ( | const double | _c | ) |
Set the offset value for the command, which is added to the result of the PID controller.
[in] | _c | The offset value |
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::SetDGain | ( | const double | _d | ) |
Set the derivtive Gain.
[in] | _d | derivative gain value |
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::SetIGain | ( | const double | _i | ) |
Set the integral Gain.
[in] | _i | integral gain value |
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::SetIMax | ( | const double | _i | ) |
Set the integral upper limit.
[in] | _i | integral upper limit value |
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::SetIMin | ( | const double | _i | ) |
Set the integral lower limit.
[in] | _i | integral lower limit value |
void ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::SetPGain | ( | const double | _p | ) |
Set the proportional Gain.
[in] | _p | proportional gain value |
double ignition::math::IGNITION_MATH_VERSION_NAMESPACE::PID::Update | ( | const double | _error, |
const std::chrono::duration< double > & | _dt ) |
Update the Pid loop with nonuniform time step size.
[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. |