A basic pid class. More...
#include <PidController.hpp>
Public Member Functions | |
double | getCurrentCmd () |
Return current command for this PID controller. More... | |
void | getCurrentPIDErrors (double &pe, double &ie, double &de) |
Return PID error terms for the controller. More... | |
void | getGains (double &p, double &i, double &d, double &i_max, double &i_min) |
Get PID gains for the controller. More... | |
void | initPid (double P, double I, double D, double I1, double I2) |
Initialize PID-gains and integral term limits:[iMax:iMin]-[I1:I2]. More... | |
PidController & | operator= (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]. More... | |
void | reset () |
Reset the state of this PID controller. More... | |
void | setCurrentCmd (double cmd) |
Set current command for this PID controller. More... | |
void | setGains (double P, double I, double D, double i_max, double i_min) |
Set PID gains for the controller. More... | |
double | updatePid (double p_error, boost::posix_time::time_duration dt) |
Update the Pid loop with nonuniform time step size. More... | |
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. More... | |
~PidController () | |
Destructor of Pid class. More... | |
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_ |
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:
where:
given:
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.
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].
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 42 of file PidController.cpp.
youbot::PidController::~PidController | ( | ) |
Destructor of Pid class.
Definition at line 53 of file PidController.cpp.
double youbot::PidController::getCurrentCmd | ( | ) |
Return current command for this PID controller.
Definition at line 195 of file PidController.cpp.
void youbot::PidController::getCurrentPIDErrors | ( | double & | pe, |
double & | ie, | ||
double & | de | ||
) |
Return PID error terms for the controller.
pe | The proportional error. |
ie | The integral error. |
de | The derivative error. |
Definition at line 200 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.
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 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].
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 57 of file PidController.cpp.
|
inline |
Definition at line 189 of file PidController.hpp.
void youbot::PidController::reset | ( | ) |
Reset the state of this PID controller.
Definition at line 68 of file PidController.cpp.
void youbot::PidController::setCurrentCmd | ( | double | cmd | ) |
Set current command for this PID controller.
Definition at line 190 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.
P | The proportional gain. |
I | The integral gain. |
D | The 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.
p_error | Error since last call (p_state-p_target) |
dt | Change in time since last call |
Definition at line 96 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.
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 145 of file PidController.cpp.
|
private |
Command to send.
Definition at line 214 of file PidController.hpp.
|
private |
Derivative error.
Definition at line 207 of file PidController.hpp.
|
private |
Derivative gain.
Definition at line 211 of file PidController.hpp.
|
private |
Integator error.
Definition at line 208 of file PidController.hpp.
|
private |
Integral gain.
Definition at line 210 of file PidController.hpp.
|
private |
Maximum allowable integral term.
Definition at line 212 of file PidController.hpp.
|
private |
Minimum allowable integral term.
Definition at line 213 of file PidController.hpp.
|
private |
Definition at line 215 of file PidController.hpp.
|
private |
Position error.
Definition at line 206 of file PidController.hpp.
|
private |
_Save position state for derivative state calculation.
Definition at line 205 of file PidController.hpp.
|
private |
Proportional gain.
Definition at line 209 of file PidController.hpp.