37 #ifndef ROBOT_CONTROLLERS_PID_H 38 #define ROBOT_CONTROLLERS_PID_H 56 PID(
double p,
double i,
double d,
double i_max,
double i_min);
75 double update(
double error,
double dt);
84 double update(
double error,
double error_dot,
double dt);
112 #endif // ROBOT_CONTROLLERS_PID_H
PID()
Constructor. Starts all gains and limits at zero.
double i_term_
integral wind-up term
bool checkGains()
Checks and fixes gain settings.
double error_last_
Last error value, used for calculating error_dot when not provided.
double update(double error, double dt)
Run PID calculation and return control result.
double i_max_
integral gain min and max limits
void reset()
Reset integral wind-up term.
double p_gain_
proportial gain
double i_gain_
integral gain
bool init(const ros::NodeHandle &nh)
initialize gain settings from ROS parameter values
double d_gain_
derivative gain