PidController Class Reference

A basic pid class. More...

#include <PidController.hpp>

Public Member Functions

 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].
 ~PidController ()
 Destructor of Pid class.
double updatePid (double p_error, boost::posix_time::time_duration dt)
 Update the Pid loop with nonuniform time step size.
void initPid (double P, double I, double D, double I1, double I2)
 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.
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 setGains (double P, double I, double D, double i_max, double i_min)
 Set PID gains for the controller.
void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
 Get PID gains for the controller.
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.
PidControlleroperator= (const PidController &p)

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


Constructor & Destructor Documentation

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:
P The proportional gain.
I The integral gain.
D The derivative gain.
I1 The integral upper limit.
I2 The integral lower limit.

Definition at line 41 of file PidController.cpp.

~PidController (  ) 

Destructor of Pid class.

Definition at line 52 of file PidController.cpp.


Member Function Documentation

double getCurrentCmd (  ) 

Return current command for this PID controller.

Definition at line 194 of file PidController.cpp.

void getCurrentPIDErrors ( double &  pe,
double &  ie,
double &  de 
)

Return PID error terms for the controller.

Parameters:
pe The proportional error.
ie The integral error.
de The derivative error.

Definition at line 199 of file PidController.cpp.

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

Get PID gains for the controller.

Parameters:
p The proportional gain.
i The integral gain.
d The derivative gain.
i_max The max integral windup.
i_mim The min integral windup.

Definition at line 76 of file PidController.cpp.

Here is the caller graph for this function:

void initPid ( double  P,
double  I,
double  D,
double  I1,
double  I2 
)

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

Parameters:
P The proportional gain.
I The integral gain.
D The derivative gain.
I1 The integral upper limit.
I2 The integral lower limit.

Definition at line 56 of file PidController.cpp.

Here is the call graph for this function:

Here is the caller graph for this function:

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

Definition at line 189 of file PidController.hpp.

void reset (  ) 

Reset the state of this PID controller.

Definition at line 67 of file PidController.cpp.

Here is the caller graph for this function:

void setCurrentCmd ( double  cmd  ) 

Set current command for this PID controller.

Definition at line 189 of file PidController.cpp.

void setGains ( double  P,
double  I,
double  D,
double  i_max,
double  i_min 
)

Set PID gains for the controller.

Parameters:
P The proportional gain.
I The integral gain.
D The derivative gain.
i_max 
i_min 

Definition at line 85 of file PidController.cpp.

Here is the caller graph for this function:

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.

Parameters:
error Error since last call (p_state-p_target)
error_dot d(Error)/dt since last call
dt Change in time since last call

Definition at line 144 of file PidController.cpp.

double updatePid ( double  p_error,
boost::posix_time::time_duration  dt 
)

Update the Pid loop with nonuniform time step size.

Parameters:
p_error Error since last call (p_state-p_target)
dt Change in time since last call

Definition at line 95 of file PidController.cpp.

Here is the caller graph for this function:


The documentation for this class was generated from the following files:
Generated by  doxygen 1.6.3