The simplePID class is a basic, tried and true PID controller. Only P (proportional) gains are necessary, the I (integral) and D (derivative) default to zero. The I control is computed using a first-order numerical integral of the error, the derivative is the numerical first-order derivative of the error. Due to these crude integration techniques, it is best if the control be computed fast (i.e. small dt). More...
#include <simple_pid.h>
Public Member Functions | |
void | clearIntegrator () |
clearIntegrator allows you to clear the integrator, in case of integrator windup. More... | |
double | computePID (double desired, double current, double dt, double x_dot=INFINITY) |
computePID computes the PID control for the given error and timestep (since the last control was computed!) More... | |
void | setGains (double p, double i=0.0, double d=0.0, double tau=0.15) |
setgains is used to set the gains for a controller after it's been initialized. It will rewrite whatever is already there! More... | |
void | setLimits (double max, double min) |
setgains is used to set the gains for a controller after it's been initialized. It will rewrite whatever is already there! More... | |
SimplePID () | |
SimplePID is the basic initializer;. More... | |
SimplePID (double p, double i=0.0, double d=0.0, double max=DBL_MAX, double min=-DBL_MAX, double tau=0.15) | |
SimplePID initializes the class. More... | |
Protected Member Functions | |
double | saturate (double val, double &min, double &max) |
saturate saturates the variable val More... | |
Protected Attributes | |
double | differentiator_ |
used for noise reduced differentiation More... | |
double | integrator_ |
the integral of p_error More... | |
double | kd_ |
the derivative gain (zero if you don't want derivative control) More... | |
double | ki_ |
the integral gain (zero if you don't want integral control) More... | |
double | kp_ |
the proportional gain More... | |
double | last_error_ |
the last p_error, for computing the derivative; More... | |
double | last_state_ |
the last state, for computing the derivative; More... | |
double | max_ |
Maximum Output. More... | |
double | min_ |
Minimum Output. More... | |
double | tau_ |
the noise reduction term for the derivative More... | |
The simplePID class is a basic, tried and true PID controller. Only P (proportional) gains are necessary, the I (integral) and D (derivative) default to zero. The I control is computed using a first-order numerical integral of the error, the derivative is the numerical first-order derivative of the error. Due to these crude integration techniques, it is best if the control be computed fast (i.e. small dt).
Definition at line 53 of file simple_pid.h.
rosflight_utils::SimplePID::SimplePID | ( | ) |
SimplePID is the basic initializer;.
Definition at line 39 of file simple_pid.cpp.
rosflight_utils::SimplePID::SimplePID | ( | double | p, |
double | i = 0.0 , |
||
double | d = 0.0 , |
||
double | max = DBL_MAX , |
||
double | min = -DBL_MAX , |
||
double | tau = 0.15 |
||
) |
SimplePID initializes the class.
p | the proportional controller gain (required) |
i | the integral controller gain (defaults to zero) |
d | the derivative controller gain (defaults to zero) |
imin | the min value accepted in the output of the integral control |
imax | the max value accepted in the output of the integral control (saturation for integrator windup) |
tau | band limited differentiator to reduce noise |
Definition at line 54 of file simple_pid.cpp.
|
inline |
clearIntegrator allows you to clear the integrator, in case of integrator windup.
Definition at line 102 of file simple_pid.h.
double rosflight_utils::SimplePID::computePID | ( | double | desired, |
double | current, | ||
double | dt, | ||
double | x_dot = INFINITY |
||
) |
computePID computes the PID control for the given error and timestep (since the last control was computed!)
p_error | is the "position" error (or whatever variable you are controlling) |
dt | is the timestep since the last control was computed. |
x_dot | derivative of current state (optional) |
Definition at line 66 of file simple_pid.cpp.
|
inlineprotected |
saturate saturates the variable val
val | the parameter to saturate (makes a copy) |
min | the minimum value |
max | the max value |
Definition at line 126 of file simple_pid.h.
void rosflight_utils::SimplePID::setGains | ( | double | p, |
double | i = 0.0 , |
||
double | d = 0.0 , |
||
double | tau = 0.15 |
||
) |
setgains is used to set the gains for a controller after it's been initialized. It will rewrite whatever is already there!
p | the proportional controller gain (required) |
i | the integral controller gain (defaults to zero) |
d | the derivative controller gain (defaults to zero) |
tau | band limited differentiator to reduce noise |
Definition at line 144 of file simple_pid.cpp.
void rosflight_utils::SimplePID::setLimits | ( | double | max, |
double | min | ||
) |
setgains is used to set the gains for a controller after it's been initialized. It will rewrite whatever is already there!
max | the largest output allowed (integrator anti-windup will kick in at this value as well) |
min | the smallest output allowed (also activates integrator anti-windup |
|
protected |
used for noise reduced differentiation
Definition at line 112 of file simple_pid.h.
|
protected |
the integral of p_error
Definition at line 111 of file simple_pid.h.
|
protected |
the derivative gain (zero if you don't want derivative control)
Definition at line 110 of file simple_pid.h.
|
protected |
the integral gain (zero if you don't want integral control)
Definition at line 109 of file simple_pid.h.
|
protected |
the proportional gain
Definition at line 108 of file simple_pid.h.
|
protected |
the last p_error, for computing the derivative;
Definition at line 113 of file simple_pid.h.
|
protected |
the last state, for computing the derivative;
Definition at line 114 of file simple_pid.h.
|
protected |
Maximum Output.
Definition at line 116 of file simple_pid.h.
|
protected |
Minimum Output.
Definition at line 117 of file simple_pid.h.
|
protected |
the noise reduction term for the derivative
Definition at line 115 of file simple_pid.h.