46 #include <boost/algorithm/clamp.hpp> 47 #include <boost/algorithm/minmax.hpp> 54 setGains(p, i, d, i_max, i_min, antiwindup);
63 void PlainPid::initPid(
double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup)
65 setGains(p, i, d, i_max, i_min, antiwindup);
73 return init(nh, quiet);
97 nh.
param(
"i_clamp", i_clamp, 0.0);
98 gains.
i_max_ = std::abs(i_clamp);
99 gains.
i_min_ = -std::abs(i_clamp);
122 i_clamp = config->Attribute(
"iClamp") ? atof(config->Attribute(
"iClamp")) : 0.0;
125 config->Attribute(
"p") ? atof(config->Attribute(
"p")) : 0.0,
126 config->Attribute(
"i") ? atof(config->Attribute(
"i")) : 0.0,
127 config->Attribute(
"d") ? atof(config->Attribute(
"d")) : 0.0,
130 config->Attribute(
"antiwindup") ? atof(config->Attribute(
"antiwindup")) :
false);
149 getGains(p, i, d, i_max, i_min, antiwindup);
152 void PlainPid::getGains(
double &p,
double &i,
double &d,
double &i_max,
double &i_min,
bool &antiwindup)
174 if (dt ==
ros::Duration(0.0) || std::isnan(error) || std::isinf(error))
180 if (dt.
toSec() > 0.0)
196 double p_term, d_term, i_term;
203 std::isnan(error_dot) ||
204 std::isinf(error_dot))
218 i_error_ = boost::algorithm::clamp(i_error_, bounds.get<0>(), bounds.get<1>());
234 cmd_ = p_term + i_term + d_term;
274 <<
" Command: " <<
cmd_);
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.
#define ROS_INFO_STREAM_NAMED(name, args)
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.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool getParam(const std::string &key, std::string &s) const
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...
void setCurrentCmd(double cmd)
Set current command for this PID controller.
bool hasParam(const std::string &key) const
void printValues()
Print to console the current parameters.
const std::string & getNamespace() const
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...