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/node_handle.h"
00040
00041 class TiXmlElement;
00042
00043 namespace control_toolbox {
00044
00045
00104
00105
00106 class Pid
00107 {
00108 public:
00109
00120 Pid(double P = 0.0, double I = 0.0, double D = 0.0, double I1 = 0.0, double I2 = -0.0);
00121
00125 ~Pid();
00126
00133 double updatePid(double p_error, ros::Duration dt);
00134
00144 void initPid(double P, double I, double D, double I1, double I2);
00145
00151 bool initParam(const std::string& prefix);
00152 bool initXml(TiXmlElement *config);
00158 bool init(const ros::NodeHandle &n);
00159
00163 void reset();
00164
00168 void setCurrentCmd(double cmd);
00169
00173 double getCurrentCmd();
00174
00181 void getCurrentPIDErrors(double *pe, double *ie, double *de);
00182
00191 void setGains(double P, double I, double D, double i_max, double i_min);
00192
00201 void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
00202
00211 double updatePid(double error, double error_dot, ros::Duration dt);
00212
00213 Pid &operator =(const Pid& p)
00214 {
00215 if (this == &p)
00216 return *this;
00217
00218 p_gain_ = p.p_gain_;
00219 i_gain_ = p.i_gain_;
00220 d_gain_ = p.d_gain_;
00221 i_max_ = p.i_max_;
00222 i_min_ = p.i_min_;
00223
00224 p_error_last_ = p_error_ = i_error_ = d_error_ = cmd_ = 0.0;
00225 return *this;
00226 }
00227
00228 private:
00229 double p_error_last_;
00230 double p_error_;
00231 double d_error_;
00232 double i_error_;
00233 double p_gain_;
00234 double i_gain_;
00235 double d_gain_;
00236 double i_max_;
00237 double i_min_;
00238 double cmd_;
00239 };
00240
00241 }
00242
00243 #endif