35 #ifndef SR_MECHANISM_CONTROLLERS_SR_PLAIN_PID_HPP 36 #define SR_MECHANISM_CONTROLLERS_SR_PLAIN_PID_HPP 41 #include <control_msgs/PidState.h> 119 Gains(
double p,
double i,
double d,
double i_max,
double i_min)
128 Gains(
double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup)
169 bool antiwindup =
false);
186 void initPid(
double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup =
false);
195 bool initParam(
const std::string& prefix,
const bool quiet =
false);
212 bool initXml(TiXmlElement *config);
227 void getGains(
double &p,
double &i,
double &d,
double &i_max,
double &i_min);
228 void getGains(
double &p,
double &i,
double &d,
double &i_max,
double &i_min,
bool &antiwindup);
244 void setGains(
double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup =
false);
void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Set PID gains for the controller.
~PlainPid()
Destructor of Pid class.
double computeCommand(double error, ros::Duration dt)
Set PID gains for the controller.
Gains pid_gains
Get PID gains for the controller.
double getCurrentCmd()
Return current command for this PID controller.
ROS_DEPRECATED double updatePid(double p_error, ros::Duration dt)
Update the Pid loop with nonuniform time step size.
bool init(const ros::NodeHandle &n, const bool quiet=false)
Initialize PID with the parameters in a NodeHandle namespace Initializes dynamic reconfigure for PID ...
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get PID gains for the controller.
void getCurrentPIDErrors(double *pe, double *ie, double *de)
Return PID error terms for the controller.
Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Zeros out Pid values and initialize Pid-gains and integral term limits Does not initialize dynamic re...
Gains(double p, double i, double d, double i_max, double i_min)
void setCurrentCmd(double cmd)
Set current command for this PID controller.
void printValues()
Print to console the current parameters.
Store gains in a struct to allow easier realtime buffer usage.
void reset()
Reset the state of this PID controller.
PlainPid(double p=0.0, double i=0.0, double d=0.0, double i_max=0.0, double i_min=-0.0, bool antiwindup=false)
Constructor, zeros out Pid values when created and initialize Pid-gains and integral term limits...
bool initXml(TiXmlElement *config)
Initialize PID with the parameters in an XML element Initializes dynamic reconfigure for PID gains...
bool initParam(const std::string &prefix, const bool quiet=false)
Initialize PID with the parameters in a namespace Initializes dynamic reconfigure for PID gains...