Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef CONTROL_TOOLBOX__PID_H
00035 #define CONTROL_TOOLBOX__PID_H
00036
00037
00038 #include <string>
00039 #include <ros/ros.h>
00040
00041
00042 #include <dynamic_reconfigure/server.h>
00043 #include <control_toolbox/ParametersConfig.h>
00044 #include <boost/thread/mutex.hpp>
00045
00046
00047 #include <realtime_tools/realtime_buffer.h>
00048
00049 class TiXmlElement;
00050
00051 namespace control_toolbox {
00052
00053
00111
00112
00113 class Pid
00114 {
00115 public:
00116
00120 struct Gains
00121 {
00122
00123 Gains(double p, double i, double d, double i_max, double i_min)
00124 : p_gain_(p),
00125 i_gain_(i),
00126 d_gain_(d),
00127 i_max_(i_max),
00128 i_min_(i_min)
00129 {}
00130
00131 Gains() {}
00132 double p_gain_;
00133 double i_gain_;
00134 double d_gain_;
00135 double i_max_;
00136 double i_min_;
00137 };
00138
00150 Pid(double p = 0.0, double i = 0.0, double d = 0.0, double i_max = 0.0, double i_min = -0.0);
00151
00156 Pid(const Pid &source);
00157
00161 ~Pid();
00162
00173 void initPid(double p, double i, double d, double i_max, double i_min);
00174
00185 void initPid(double p, double i, double d, double i_max, double i_min, const ros::NodeHandle& );
00186
00194 bool initParam(const std::string& prefix, const bool quiet=false);
00195
00203 bool init(const ros::NodeHandle &n, const bool quiet=false);
00204
00211 bool initXml(TiXmlElement *config);
00212
00217 void initDynamicReconfig(ros::NodeHandle &node);
00218
00222 void reset();
00223
00232 void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
00233
00238 Gains getGains();
00239
00248 void setGains(double p, double i, double d, double i_max, double i_min);
00249
00254 void setGains(const Gains &gains);
00255
00259 void updateDynamicReconfig();
00260 void updateDynamicReconfig(Gains gains_config);
00261 void updateDynamicReconfig(control_toolbox::ParametersConfig config);
00262
00266 void dynamicReconfigCallback(control_toolbox::ParametersConfig &config, uint32_t );
00267
00278 double computeCommand(double error, ros::Duration dt);
00279
00291 double computeCommand(double error, double error_dot, ros::Duration dt);
00292
00305 ROS_DEPRECATED double updatePid(double p_error, ros::Duration dt);
00306
00321 ROS_DEPRECATED double updatePid(double error, double error_dot, ros::Duration dt);
00322
00326 void setCurrentCmd(double cmd);
00327
00331 double getCurrentCmd();
00332
00339 void getCurrentPIDErrors(double *pe, double *ie, double *de);
00340
00341
00345 void printValues();
00346
00351 Pid &operator =(const Pid& source)
00352 {
00353 if (this == &source)
00354 return *this;
00355
00356
00357 gains_buffer_ = source.gains_buffer_;
00358
00359
00360 reset();
00361
00362 return *this;
00363 }
00364
00365 private:
00366
00367
00368
00369 realtime_tools::RealtimeBuffer<Gains> gains_buffer_;
00370
00371 double p_error_last_;
00372 double p_error_;
00373 double i_error_;
00374 double d_error_;
00375 double cmd_;
00377
00378 bool dynamic_reconfig_initialized_;
00379 typedef dynamic_reconfigure::Server<control_toolbox::ParametersConfig> DynamicReconfigServer;
00380 boost::shared_ptr<DynamicReconfigServer> param_reconfig_server_;
00381 DynamicReconfigServer::CallbackType param_reconfig_callback_;
00382
00383 boost::recursive_mutex param_reconfig_mutex_;
00384
00385 };
00386
00387 }
00388
00389 #endif