All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | List of all members
gazebo::common::PID Class Reference

Generic PID controller class. More...

#include <common/common.hh>

Public Member Functions

 PID (double _p=0.0, double _i=0.0, double _d=0.0, double _imax=0.0, double _imin=0.0, double _cmdMax=0.0, double _cmdMin=0.0)
 Constructor, zeros out Pid values when created and initialize Pid-gains and integral term limits:[iMax:iMin]-[I1:I2].
virtual ~PID ()
 Destructor.
double GetCmd ()
 Return current command for this PID controller.
void GetErrors (double &_pe, double &_ie, double &_de)
 Return PID error terms for the controller.
void Init (double _p=0.0, double _i=0.0, double _d=0.0, double _imax=0.0, double _imin=0.0, double _cmdMax=0.0, double _cmdMin=0.0)
 Initialize PID-gains and integral term limits:[iMax:iMin]-[I1:I2].
PIDoperator= (const PID &_p)
 Assignment operator.
void Reset ()
 Reset the errors and command.
void SetCmd (double _cmd)
 Set current target command for this PID controller.
void SetCmdMax (double _c)
 Set the maximum value for the command.
void SetCmdMin (double _c)
 Set the maximum value for the command.
void SetDGain (double _d)
 Set the derivtive Gain.
void SetIGain (double _i)
 Set the integral Gain.
void SetIMax (double _i)
 Set the integral upper limit.
void SetIMin (double _i)
 Set the integral lower limit.
void SetPGain (double _p)
 Set the proportional Gain.
double Update (double _error, common::Time _dt)
 Update the Pid loop with nonuniform time step size.

Detailed Description

Generic PID controller class.

Generic proportiolnal-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.

Constructor & Destructor Documentation

gazebo::common::PID::PID ( double  _p = 0.0,
double  _i = 0.0,
double  _d = 0.0,
double  _imax = 0.0,
double  _imin = 0.0,
double  _cmdMax = 0.0,
double  _cmdMin = 0.0 
)

Constructor, zeros out Pid values when created and initialize Pid-gains and integral term limits:[iMax:iMin]-[I1:I2].

Parameters
[in]_pThe proportional gain.
[in]_iThe integral gain.
[in]_dThe derivative gain.
[in]_imaxThe integral upper limit.
[in]_iminThe integral lower limit.
virtual gazebo::common::PID::~PID ( )
virtual

Destructor.

Member Function Documentation

double gazebo::common::PID::GetCmd ( )

Return current command for this PID controller.

Returns
the command value
void gazebo::common::PID::GetErrors ( double &  _pe,
double &  _ie,
double &  _de 
)

Return PID error terms for the controller.

Parameters
[in]_peThe proportional error.
[in]_ieThe integral error.
[in]_deThe derivative error.
void gazebo::common::PID::Init ( double  _p = 0.0,
double  _i = 0.0,
double  _d = 0.0,
double  _imax = 0.0,
double  _imin = 0.0,
double  _cmdMax = 0.0,
double  _cmdMin = 0.0 
)

Initialize PID-gains and integral term limits:[iMax:iMin]-[I1:I2].

Parameters
[in]_pThe proportional gain.
[in]_iThe integral gain.
[in]_dThe derivative gain.
[in]_imaxThe integral upper limit.
[in]_iminThe integral lower limit.
PID& gazebo::common::PID::operator= ( const PID _p)
inline

Assignment operator.

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

References Reset().

void gazebo::common::PID::Reset ( )

Reset the errors and command.

Referenced by operator=().

void gazebo::common::PID::SetCmd ( double  _cmd)

Set current target command for this PID controller.

Parameters
[in]_cmdNew command
void gazebo::common::PID::SetCmdMax ( double  _c)

Set the maximum value for the command.

Parameters
[in]_cThe maximum value
void gazebo::common::PID::SetCmdMin ( double  _c)

Set the maximum value for the command.

Parameters
[in]_cThe maximum value
void gazebo::common::PID::SetDGain ( double  _d)

Set the derivtive Gain.

Parameters
[in]_pdertivative gain value
void gazebo::common::PID::SetIGain ( double  _i)

Set the integral Gain.

Parameters
[in]_pintegral gain value
void gazebo::common::PID::SetIMax ( double  _i)

Set the integral upper limit.

Parameters
[in]_pintegral upper limit value
void gazebo::common::PID::SetIMin ( double  _i)

Set the integral lower limit.

Parameters
[in]_pintegral lower limit value
void gazebo::common::PID::SetPGain ( double  _p)

Set the proportional Gain.

Parameters
[in]_pproportional gain value
double gazebo::common::PID::Update ( double  _error,
common::Time  _dt 
)

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

The documentation for this class was generated from the following file: