Ignition Math

API Reference

6.9.3~pre2

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

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]_pThe proportional gain.
[in]_iThe integral gain.
[in]_dThe derivative gain.
[in]_imaxThe integral upper limit.
[in]_iminThe integral lower limit.
[in]_cmdMaxOutput max value.
[in]_cmdMinOutput min value.
[in]_cmdOffsetCommand offset (feed-forward).

◆ ~PID()

~PID ( )
default

Destructor.

Member Function Documentation

◆ Cmd()

double Cmd ( ) const

Return current command for this PID controller.

Returns
the command value

◆ 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()

void Errors ( double &  _pe,
double &  _ie,
double &  _de 
) const

Return PID error terms for the controller.

Parameters
[in]_peThe proportional error.
[in]_ieThe integral of gain times error.
[in]_deThe 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]_pThe proportional gain.
[in]_iThe integral gain.
[in]_dThe derivative gain.
[in]_imaxThe integral upper limit.
[in]_iminThe integral lower limit.
[in]_cmdMaxOutput max value.
[in]_cmdMinOutput min value.
[in]_cmdOffsetCommand offset (feed-forward).

◆ operator=()

PID& operator= ( const PID _p)

Assignment operator.

Parameters
[in]_pa reference to a PID to assign values from
Returns
reference to this instance

◆ PGain()

double PGain ( ) const

Get the proportional Gain.

Returns
The proportional gain value

◆ Reset()

void Reset ( )

Reset the errors and command.

◆ SetCmd()

void SetCmd ( const double  _cmd)

Set current target command for this PID controller.

Parameters
[in]_cmdNew command

◆ SetCmdMax()

void SetCmdMax ( const double  _c)

Set the maximum value for the command.

Parameters
[in]_cThe maximum value

◆ SetCmdMin()

void SetCmdMin ( const double  _c)

Set the minimum value for the command.

Parameters
[in]_cThe minimum value

◆ SetCmdOffset()

void SetCmdOffset ( const double  _c)

Set the offset value for the command, which is added to the result of the PID controller.

Parameters
[in]_cThe offset value

◆ SetDGain()

void SetDGain ( const double  _d)

Set the derivative Gain.

Parameters
[in]_dderivative gain value

◆ SetIGain()

void SetIGain ( const double  _i)

Set the integral Gain.

Parameters
[in]_iintegral gain value

◆ SetIMax()

void SetIMax ( const double  _i)

Set the integral upper limit.

Parameters
[in]_iintegral upper limit value

◆ SetIMin()

void SetIMin ( const double  _i)

Set the integral lower limit.

Parameters
[in]_iintegral lower limit value

◆ SetPGain()

void SetPGain ( const double  _p)

Set the proportional Gain.

Parameters
[in]_pproportional gain value

◆ Update()

double Update ( const double  _error,
const std::chrono::duration< double > &  _dt 
)

Update the Pid loop with nonuniform time step size.

Parameters
[in]_errorError since last call (p_state - p_target).
[in]_dtChange 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: