68 double error = desired - current;
71 if (dt < 0.00001 || std::abs(error) > 9999999)
88 double p_term = error*
kp_;
96 if (std::isfinite(x_dot))
123 double u = p_term + i_term - d_term;
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 differentiator_
used for noise reduced differentiation
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.
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...