38 #ifndef ROTOR_CONTROLLER_SIMPLE_PID_H 39 #define ROTOR_CONTROLLER_SIMPLE_PID_H 70 SimplePID(
double p,
double i = 0.0,
double d = 0.0,
double max = DBL_MAX,
double min = -DBL_MAX,
double tau = 0.15);
79 double computePID(
double desired,
double current,
double dt,
double x_dot = INFINITY);
89 void setGains(
double p,
double i = 0.0,
double d = 0.0,
double tau = 0.15);
126 inline double saturate(
double val,
double &min,
double &max)
137 #endif // ROTOR_CONTROLLER_SIMPLE_PID_H
double ki_
the integral gain (zero if you don't want integral control)
double last_error_
the last p_error, for computing the derivative;
double saturate(double val, double &min, double &max)
saturate saturates the variable val
void setLimits(double max, double min)
setgains is used to set the gains for a controller after it's been initialized. It will rewrite whate...
double differentiator_
used for noise reduced differentiation
The simplePID class is a basic, tried and true PID controller. Only P (proportional) gains are necess...
This file defines a simple PID controller to be used by other classes to implement a PID control loop...
double tau_
the noise reduction term for the derivative
double last_state_
the last state, for computing the derivative;
SimplePID()
SimplePID is the basic initializer;.
double kd_
the derivative gain (zero if you don't want derivative control)
double max_
Maximum Output.
void clearIntegrator()
clearIntegrator allows you to clear the integrator, in case of integrator windup. ...
double kp_
the proportional gain
double integrator_
the integral of p_error
double min_
Minimum Output.
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 whate...
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 comp...