38 #include <boost/math/special_functions/fpclassify.hpp>    43   p_gain_(P), i_gain_(I), d_gain_(D), i_max_(I1), i_min_(I2)
    98   double p_term, d_term, i_term;
   100   double deltatime = (double)dt.total_microseconds()/1000.0; 
   103   if (deltatime == 0.0 || boost::math::isnan(error) || boost::math::isinf(error))
   137   cmd_ = -p_term - i_term - d_term;
   147   double p_term, d_term, i_term;
   150   double deltatime = (double)dt.total_microseconds()/1000.0;  
   152   if (deltatime == 0.0 || boost::math::isnan(error) || boost::math::isinf(error) || boost::math::isnan(error_dot) || boost::math::isinf(error_dot))
   183   cmd_ = -p_term - i_term - d_term;
 
void setGains(double P, double I, double D, double i_max, double i_min)
Set PID gains for the controller. 
void setCurrentCmd(double cmd)
Set current command for this PID controller. 
double getCurrentCmd()
Return current command for this PID controller. 
double updatePid(double p_error, boost::posix_time::time_duration dt)
Update the Pid loop with nonuniform time step size. 
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller. 
~PidController()
Destructor of Pid class. 
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:[iMa...
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get PID gains for the controller. 
void reset()
Reset the state of this PID controller. 
void initPid(double P, double I, double D, double I1, double I2)
Initialize PID-gains and integral term limits:[iMax:iMin]-[I1:I2].