Public Member Functions | Private Attributes
youbot::PidController Class Reference

A basic pid class. More...

#include <PidController.hpp>

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.
void initPid (double P, double I, double D, double I1, double I2)
 Initialize PID-gains and integral term limits:[iMax:iMin]-[I1:I2].
PidControlleroperator= (const PidController &p)
 PidController (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, boost::posix_time::time_duration dt)
 Update the Pid loop with nonuniform time step size.
double updatePid (double error, double error_dot, boost::posix_time::time_duration dt)
 Update the Pid loop with nonuniform time step size. This update call allows the user to pass in a precomputed derivative error.
 ~PidController ()
 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 last_i_error
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:

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 95 of file PidController.hpp.


Constructor & Destructor Documentation

youbot::PidController::PidController ( 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 PidController.cpp.

Destructor of Pid class.

Definition at line 53 of file PidController.cpp.


Member Function Documentation

Return current command for this PID controller.

Definition at line 189 of file PidController.cpp.

void youbot::PidController::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 194 of file PidController.cpp.

void youbot::PidController::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 77 of file PidController.cpp.

void youbot::PidController::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 57 of file PidController.cpp.

PidController& youbot::PidController::operator= ( const PidController p) [inline]

Definition at line 188 of file PidController.hpp.

Reset the state of this PID controller.

Definition at line 68 of file PidController.cpp.

Set current command for this PID controller.

Definition at line 184 of file PidController.cpp.

void youbot::PidController::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 86 of file PidController.cpp.

double youbot::PidController::updatePid ( double  p_error,
boost::posix_time::time_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 95 of file PidController.cpp.

double youbot::PidController::updatePid ( double  error,
double  error_dot,
boost::posix_time::time_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 142 of file PidController.cpp.


Member Data Documentation

double youbot::PidController::cmd_ [private]

Command to send.

Definition at line 213 of file PidController.hpp.

Derivative error.

Definition at line 206 of file PidController.hpp.

Derivative gain.

Definition at line 210 of file PidController.hpp.

Integator error.

Definition at line 207 of file PidController.hpp.

Integral gain.

Definition at line 209 of file PidController.hpp.

Maximum allowable integral term.

Definition at line 211 of file PidController.hpp.

Minimum allowable integral term.

Definition at line 212 of file PidController.hpp.

Definition at line 214 of file PidController.hpp.

Position error.

Definition at line 205 of file PidController.hpp.

_Save position state for derivative state calculation.

Definition at line 204 of file PidController.hpp.

Proportional gain.

Definition at line 208 of file PidController.hpp.


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


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Oct 6 2014 09:08:04