Public Member Functions | Private Attributes
control_toolbox::Pid Class Reference

A basic pid class. More...

#include <pid.h>

List of all members.

Public Member Functions

double getCurrentCmd ()
 Return current command for this PID controller.
void getCurrentPIDErrors (double *pe, double *ie, double *de)
 Return PID error terms for the controller.
void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
 Get PID gains for the controller.
bool init (const ros::NodeHandle &n)
 Initialize PID with the parameters in a NodeHandle namespace.
bool initParam (const std::string &prefix)
 Initialize PID with the parameters in a namespace.
void initPid (double P, double I, double D, double I1, double I2)
 Initialize PID-gains and integral term limits:[iMax:iMin]-[I1:I2].
bool initXml (TiXmlElement *config)
Pidoperator= (const Pid &p)
 Pid (double P=0.0, double I=0.0, double D=0.0, double I1=0.0, double I2=-0.0)
 Constructor, zeros out Pid values when created and initialize Pid-gains and integral term limits:[iMax:iMin]-[I1:I2].
void reset ()
 Reset the state of this PID controller.
void setCurrentCmd (double cmd)
 Set current command for this PID controller.
void setGains (double P, double I, double D, double i_max, double i_min)
 Set PID gains for the controller.
double updatePid (double p_error, ros::Duration dt)
 Update the Pid loop with nonuniform time step size.
double updatePid (double error, double error_dot, ros::Duration dt)
 Update the Pid loop with nonuniform time step size. This update call allows the user to pass in a precomputed derivative error.
 ~Pid ()
 Destructor of Pid class.

Private Attributes

double cmd_
double d_error_
double d_gain_
double i_error_
double i_gain_
double i_max_
double i_min_
double p_error_
double p_error_last_
double p_gain_

Detailed Description

A basic pid class.

This class implements a generic structure that can be used to create a wide range of pid controllers. It can function independently or be subclassed to provide more specific controls based on a particular control loop.

In particular, this class implements the standard pid equation:

$command = -p_{term} - i_{term} - d_{term} $

where:

given:

ROS interface

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_clampMin/max bounds for the integral windup, the clamp is applied to the $i_{term}$ and not the $i_{error}$

Usage

To use the Pid class, you should first call some version of init() (in non-realtime) and then call updatePid() at every update step. For example:

control_toolbox::Pid pid;
pid.initPid(6.0, 1.0, 2.0, 0.3, -0.3);
double position_desi_ = 0.5;
...
ros::Time last_time = ros::Time::now();
while (true) {
  ros::Time time = ros::Time::now();
  double effort = pid.updatePid(currentPosition() - position_desi_, time - last_time);
  last_time = time;
}

Definition at line 106 of file pid.h.


Constructor & Destructor Documentation

control_toolbox::Pid::Pid ( double  P = 0.0,
double  I = 0.0,
double  D = 0.0,
double  I1 = 0.0,
double  I2 = -0.0 
)

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

Parameters:
PThe proportional gain.
IThe integral gain.
DThe derivative gain.
I1The integral upper limit.
I2The integral lower limit.

Definition at line 42 of file pid.cpp.

Destructor of Pid class.

Definition at line 52 of file pid.cpp.


Member Function Documentation

Return current command for this PID controller.

Definition at line 228 of file pid.cpp.

void control_toolbox::Pid::getCurrentPIDErrors ( double *  pe,
double *  ie,
double *  de 
)

Return PID error terms for the controller.

Parameters:
peThe proportional error.
ieThe integral error.
deThe derivative error.

Definition at line 233 of file pid.cpp.

void control_toolbox::Pid::getGains ( double &  p,
double &  i,
double &  d,
double &  i_max,
double &  i_min 
)

Get PID gains for the controller.

Parameters:
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxThe max integral windup.
i_mimThe min integral windup.

Definition at line 76 of file pid.cpp.

Initialize PID with the parameters in a NodeHandle namespace.

Parameters:
nThe NodeHandle.

Definition at line 123 of file pid.cpp.

bool control_toolbox::Pid::initParam ( const std::string &  prefix)

Initialize PID with the parameters in a namespace.

Parameters:
nThe namespace prefix.

Definition at line 94 of file pid.cpp.

void control_toolbox::Pid::initPid ( double  P,
double  I,
double  D,
double  I1,
double  I2 
)

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

Parameters:
PThe proportional gain.
IThe integral gain.
DThe derivative gain.
I1The integral upper limit.
I2The integral lower limit.

Definition at line 56 of file pid.cpp.

bool control_toolbox::Pid::initXml ( TiXmlElement *  config)

Definition at line 111 of file pid.cpp.

Pid& control_toolbox::Pid::operator= ( const Pid p) [inline]

Definition at line 213 of file pid.h.

Reset the state of this PID controller.

Definition at line 67 of file pid.cpp.

Set current command for this PID controller.

Definition at line 223 of file pid.cpp.

void control_toolbox::Pid::setGains ( double  P,
double  I,
double  D,
double  i_max,
double  i_min 
)

Set PID gains for the controller.

Parameters:
PThe proportional gain.
IThe integral gain.
DThe derivative gain.
i_max
i_min

Definition at line 85 of file pid.cpp.

double control_toolbox::Pid::updatePid ( double  p_error,
ros::Duration  dt 
)

Update the Pid loop with nonuniform time step size.

Parameters:
p_errorError since last call (p_state-p_target)
dtChange in time since last call

Definition at line 140 of file pid.cpp.

double control_toolbox::Pid::updatePid ( double  error,
double  error_dot,
ros::Duration  dt 
)

Update the Pid loop with nonuniform time step size. This update call allows the user to pass in a precomputed derivative error.

Parameters:
errorError since last call (p_state-p_target)
error_dotd(Error)/dt since last call
dtChange in time since last call

Definition at line 183 of file pid.cpp.


Member Data Documentation

double control_toolbox::Pid::cmd_ [private]

Command to send.

Definition at line 238 of file pid.h.

Derivative error.

Definition at line 231 of file pid.h.

Derivative gain.

Definition at line 235 of file pid.h.

Integator error.

Definition at line 232 of file pid.h.

Integral gain.

Definition at line 234 of file pid.h.

double control_toolbox::Pid::i_max_ [private]

Maximum allowable integral term.

Definition at line 236 of file pid.h.

double control_toolbox::Pid::i_min_ [private]

Minimum allowable integral term.

Definition at line 237 of file pid.h.

Position error.

Definition at line 230 of file pid.h.

_Save position state for derivative state calculation.

Definition at line 229 of file pid.h.

Proportional gain.

Definition at line 233 of file pid.h.


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


control_toolbox
Author(s): Melonee Wise, Sachin Chitta, John Hsu
autogenerated on Thu Apr 24 2014 15:44:31