Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
rosflight_utils::SimplePID Class Reference

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...
 

Detailed Description

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.

Constructor & Destructor Documentation

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.

Parameters
pthe proportional controller gain (required)
ithe integral controller gain (defaults to zero)
dthe derivative controller gain (defaults to zero)
iminthe min value accepted in the output of the integral control
imaxthe max value accepted in the output of the integral control (saturation for integrator windup)
tauband limited differentiator to reduce noise

Definition at line 54 of file simple_pid.cpp.

Member Function Documentation

void rosflight_utils::SimplePID::clearIntegrator ( )
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!)

Parameters
p_erroris the "position" error (or whatever variable you are controlling)
dtis the timestep since the last control was computed.
x_dotderivative of current state (optional)
Returns
the control command

Definition at line 66 of file simple_pid.cpp.

double rosflight_utils::SimplePID::saturate ( double  val,
double &  min,
double &  max 
)
inlineprotected

saturate saturates the variable val

Parameters
valthe parameter to saturate (makes a copy)
minthe minimum value
maxthe max value
Returns
the saturated (if necessary) 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!

Parameters
pthe proportional controller gain (required)
ithe integral controller gain (defaults to zero)
dthe derivative controller gain (defaults to zero)
tauband limited differentiator to reduce noise
Todo:
Should we really be zeroing this while we are gain tuning?

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!

Parameters
maxthe largest output allowed (integrator anti-windup will kick in at this value as well)
minthe smallest output allowed (also activates integrator anti-windup

Member Data Documentation

double rosflight_utils::SimplePID::differentiator_
protected

used for noise reduced differentiation

Definition at line 112 of file simple_pid.h.

double rosflight_utils::SimplePID::integrator_
protected

the integral of p_error

Definition at line 111 of file simple_pid.h.

double rosflight_utils::SimplePID::kd_
protected

the derivative gain (zero if you don't want derivative control)

Definition at line 110 of file simple_pid.h.

double rosflight_utils::SimplePID::ki_
protected

the integral gain (zero if you don't want integral control)

Definition at line 109 of file simple_pid.h.

double rosflight_utils::SimplePID::kp_
protected

the proportional gain

Definition at line 108 of file simple_pid.h.

double rosflight_utils::SimplePID::last_error_
protected

the last p_error, for computing the derivative;

Definition at line 113 of file simple_pid.h.

double rosflight_utils::SimplePID::last_state_
protected

the last state, for computing the derivative;

Definition at line 114 of file simple_pid.h.

double rosflight_utils::SimplePID::max_
protected

Maximum Output.

Definition at line 116 of file simple_pid.h.

double rosflight_utils::SimplePID::min_
protected

Minimum Output.

Definition at line 117 of file simple_pid.h.

double rosflight_utils::SimplePID::tau_
protected

the noise reduction term for the derivative

Definition at line 115 of file simple_pid.h.


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


rosflight_utils
Author(s):
autogenerated on Wed Jul 3 2019 20:00:31