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
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047 #ifndef __art_pilot__PILOTCONFIG_H__
00048 #define __art_pilot__PILOTCONFIG_H__
00049
00050 #include <dynamic_reconfigure/config_tools.h>
00051 #include <limits>
00052 #include <ros/node_handle.h>
00053 #include <dynamic_reconfigure/ConfigDescription.h>
00054 #include <dynamic_reconfigure/ParamDescription.h>
00055 #include <dynamic_reconfigure/config_init_mutex.h>
00056
00057 namespace art_pilot
00058 {
00059 class PilotConfigStatics;
00060
00061 class PilotConfig
00062 {
00063 public:
00064 class AbstractParamDescription : public dynamic_reconfigure::ParamDescription
00065 {
00066 public:
00067 AbstractParamDescription(std::string n, std::string t, uint32_t l,
00068 std::string d, std::string e)
00069 {
00070 name = n;
00071 type = t;
00072 level = l;
00073 description = d;
00074 edit_method = e;
00075 }
00076
00077 virtual void clamp(PilotConfig &config, const PilotConfig &max, const PilotConfig &min) const = 0;
00078 virtual void calcLevel(uint32_t &level, const PilotConfig &config1, const PilotConfig &config2) const = 0;
00079 virtual void fromServer(const ros::NodeHandle &nh, PilotConfig &config) const = 0;
00080 virtual void toServer(const ros::NodeHandle &nh, const PilotConfig &config) const = 0;
00081 virtual bool fromMessage(const dynamic_reconfigure::Config &msg, PilotConfig &config) const = 0;
00082 virtual void toMessage(dynamic_reconfigure::Config &msg, const PilotConfig &config) const = 0;
00083 };
00084
00085 typedef boost::shared_ptr<AbstractParamDescription> AbstractParamDescriptionPtr;
00086 typedef boost::shared_ptr<const AbstractParamDescription> AbstractParamDescriptionConstPtr;
00087
00088 template <class T>
00089 class ParamDescription : public AbstractParamDescription
00090 {
00091 public:
00092 ParamDescription(std::string name, std::string type, uint32_t level,
00093 std::string description, std::string edit_method, T PilotConfig::* f) :
00094 AbstractParamDescription(name, type, level, description, edit_method),
00095 field(f)
00096 {}
00097
00098 T (PilotConfig::* field);
00099
00100 virtual void clamp(PilotConfig &config, const PilotConfig &max, const PilotConfig &min) const
00101 {
00102 if (config.*field > max.*field)
00103 config.*field = max.*field;
00104
00105 if (config.*field < min.*field)
00106 config.*field = min.*field;
00107 }
00108
00109 virtual void calcLevel(uint32_t &comb_level, const PilotConfig &config1, const PilotConfig &config2) const
00110 {
00111 if (config1.*field != config2.*field)
00112 comb_level |= level;
00113 }
00114
00115 virtual void fromServer(const ros::NodeHandle &nh, PilotConfig &config) const
00116 {
00117 nh.getParam(name, config.*field);
00118 }
00119
00120 virtual void toServer(const ros::NodeHandle &nh, const PilotConfig &config) const
00121 {
00122 nh.setParam(name, config.*field);
00123 }
00124
00125 virtual bool fromMessage(const dynamic_reconfigure::Config &msg, PilotConfig &config) const
00126 {
00127 return dynamic_reconfigure::ConfigTools::getParameter(msg, name, config.*field);
00128 }
00129
00130 virtual void toMessage(dynamic_reconfigure::Config &msg, const PilotConfig &config) const
00131 {
00132 dynamic_reconfigure::ConfigTools::appendParameter(msg, name, config.*field);
00133 }
00134 };
00135
00136
00137 int acceleration_controller;
00138
00139 double brake_hold;
00140
00141 bool human_steering;
00142
00143 double limit_forward;
00144
00145 double limit_reverse;
00146
00147 double timeout;
00148
00149 double brake_kp;
00150
00151 double brake_ki;
00152
00153 double brake_kd;
00154
00155 double throttle_kp;
00156
00157 double throttle_ki;
00158
00159 double throttle_kd;
00160
00161
00162 bool __fromMessage__(dynamic_reconfigure::Config &msg)
00163 {
00164 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00165 int count = 0;
00166 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00167 if ((*i)->fromMessage(msg, *this))
00168 count++;
00169 if (count != dynamic_reconfigure::ConfigTools::size(msg))
00170 {
00171 ROS_ERROR("PilotConfig::__fromMessage__ called with an unexpected parameter.");
00172 ROS_ERROR("Booleans:");
00173 for (unsigned int i = 0; i < msg.bools.size(); i++)
00174 ROS_ERROR(" %s", msg.bools[i].name.c_str());
00175 ROS_ERROR("Integers:");
00176 for (unsigned int i = 0; i < msg.ints.size(); i++)
00177 ROS_ERROR(" %s", msg.ints[i].name.c_str());
00178 ROS_ERROR("Doubles:");
00179 for (unsigned int i = 0; i < msg.doubles.size(); i++)
00180 ROS_ERROR(" %s", msg.doubles[i].name.c_str());
00181 ROS_ERROR("Strings:");
00182 for (unsigned int i = 0; i < msg.strs.size(); i++)
00183 ROS_ERROR(" %s", msg.strs[i].name.c_str());
00184
00185
00186 return false;
00187 }
00188 return true;
00189 }
00190
00191
00192
00193 void __toMessage__(dynamic_reconfigure::Config &msg, const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__) const
00194 {
00195 dynamic_reconfigure::ConfigTools::clear(msg);
00196 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00197 (*i)->toMessage(msg, *this);
00198 }
00199
00200 void __toMessage__(dynamic_reconfigure::Config &msg) const
00201 {
00202 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00203 __toMessage__(msg, __param_descriptions__);
00204 }
00205
00206 void __toServer__(const ros::NodeHandle &nh) const
00207 {
00208 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00209 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00210 (*i)->toServer(nh, *this);
00211 }
00212
00213 void __fromServer__(const ros::NodeHandle &nh)
00214 {
00215 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00216 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00217 (*i)->fromServer(nh, *this);
00218 }
00219
00220 void __clamp__()
00221 {
00222 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00223 const PilotConfig &__max__ = __getMax__();
00224 const PilotConfig &__min__ = __getMin__();
00225 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00226 (*i)->clamp(*this, __max__, __min__);
00227 }
00228
00229 uint32_t __level__(const PilotConfig &config) const
00230 {
00231 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00232 uint32_t level = 0;
00233 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00234 (*i)->calcLevel(level, config, *this);
00235 return level;
00236 }
00237
00238 static const dynamic_reconfigure::ConfigDescription &__getDescriptionMessage__();
00239 static const PilotConfig &__getDefault__();
00240 static const PilotConfig &__getMax__();
00241 static const PilotConfig &__getMin__();
00242 static const std::vector<AbstractParamDescriptionConstPtr> &__getParamDescriptions__();
00243
00244 private:
00245 static const PilotConfigStatics *__get_statics__();
00246 };
00247
00248 template <>
00249 inline void PilotConfig::ParamDescription<std::string>::clamp(PilotConfig &config, const PilotConfig &max, const PilotConfig &min) const
00250 {
00251 return;
00252 }
00253
00254 class PilotConfigStatics
00255 {
00256 friend class PilotConfig;
00257
00258 PilotConfigStatics()
00259 {
00260
00261 __min__.acceleration_controller = -2147483648;
00262
00263 __max__.acceleration_controller = 2147483647;
00264
00265 __default__.acceleration_controller = 0;
00266
00267 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<int>("acceleration_controller", "int", 3, "Acceleration controller.", "{'enum_description': 'Acceleration controller options', 'enum': [{'srcline': 50, 'description': 'Plan-based controller', 'srcfile': '../cfg/Pilot.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Accel_Plan'}, {'srcline': 51, 'description': 'Acceleration control example', 'srcfile': '../cfg/Pilot.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Accel_Example'}, {'srcline': 52, 'description': 'Speed control PID', 'srcfile': '../cfg/Pilot.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Speed_PID'}, {'srcline': 53, 'description': 'Speed control matrix', 'srcfile': '../cfg/Pilot.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Speed_Matrix'}, {'srcline': 54, 'description': 'Learned speed control', 'srcfile': '../cfg/Pilot.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'Speed_Learned'}]}", &PilotConfig::acceleration_controller)));
00268
00269 __min__.brake_hold = 0.0;
00270
00271 __max__.brake_hold = 1.0;
00272
00273 __default__.brake_hold = 0.7;
00274
00275 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("brake_hold", "double", 0, "Brake hold command when stopped.", "", &PilotConfig::brake_hold)));
00276
00277 __min__.human_steering = 0;
00278
00279 __max__.human_steering = 1;
00280
00281 __default__.human_steering = 0;
00282
00283 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<bool>("human_steering", "bool", 0, "Allow human driver to steer (otherwise pilot steers the car).", "", &PilotConfig::human_steering)));
00284
00285 __min__.limit_forward = 0.0;
00286
00287 __max__.limit_forward = 25.0;
00288
00289 __default__.limit_forward = 14.0;
00290
00291 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("limit_forward", "double", 0, "Speed limit going forward (m/s).", "", &PilotConfig::limit_forward)));
00292
00293 __min__.limit_reverse = 0.0;
00294
00295 __max__.limit_reverse = 4.0;
00296
00297 __default__.limit_reverse = 3.0;
00298
00299 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("limit_reverse", "double", 0, "Speed limit going in reverse (m/s).", "", &PilotConfig::limit_reverse)));
00300
00301 __min__.timeout = 0.0;
00302
00303 __max__.timeout = 1.0;
00304
00305 __default__.timeout = 0.5;
00306
00307 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("timeout", "double", 0, "Device message timeout (s).", "", &PilotConfig::timeout)));
00308
00309 __min__.brake_kp = -10.0;
00310
00311 __max__.brake_kp = 0.0;
00312
00313 __default__.brake_kp = -0.2;
00314
00315 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("brake_kp", "double", 0, "Brake PID proportional gain (Kp).", "", &PilotConfig::brake_kp)));
00316
00317 __min__.brake_ki = -10.0;
00318
00319 __max__.brake_ki = 0.0;
00320
00321 __default__.brake_ki = -0.0002;
00322
00323 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("brake_ki", "double", 0, "Brake PID integral gain (Ki).", "", &PilotConfig::brake_ki)));
00324
00325 __min__.brake_kd = -10.0;
00326
00327 __max__.brake_kd = 0.0;
00328
00329 __default__.brake_kd = -1.6;
00330
00331 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("brake_kd", "double", 0, "Brake PID derivative gain (Kd).", "", &PilotConfig::brake_kd)));
00332
00333 __min__.throttle_kp = 0.0;
00334
00335 __max__.throttle_kp = 10.0;
00336
00337 __default__.throttle_kp = 0.12;
00338
00339 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("throttle_kp", "double", 0, "Throttle PID proportional gain (Kp).", "", &PilotConfig::throttle_kp)));
00340
00341 __min__.throttle_ki = 0.0;
00342
00343 __max__.throttle_ki = 10.0;
00344
00345 __default__.throttle_ki = 0.001;
00346
00347 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("throttle_ki", "double", 0, "Throttle PID integral gain (Ki).", "", &PilotConfig::throttle_ki)));
00348
00349 __min__.throttle_kd = 0.0;
00350
00351 __max__.throttle_kd = 10.0;
00352
00353 __default__.throttle_kd = 0.54;
00354
00355 __param_descriptions__.push_back(PilotConfig::AbstractParamDescriptionConstPtr(new PilotConfig::ParamDescription<double>("throttle_kd", "double", 0, "Throttle PID derivative gain (Kd).", "", &PilotConfig::throttle_kd)));
00356
00357
00358 for (std::vector<PilotConfig::AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00359 __description_message__.parameters.push_back(**i);
00360 __max__.__toMessage__(__description_message__.max, __param_descriptions__);
00361 __min__.__toMessage__(__description_message__.min, __param_descriptions__);
00362 __default__.__toMessage__(__description_message__.dflt, __param_descriptions__);
00363 }
00364 std::vector<PilotConfig::AbstractParamDescriptionConstPtr> __param_descriptions__;
00365 PilotConfig __max__;
00366 PilotConfig __min__;
00367 PilotConfig __default__;
00368 dynamic_reconfigure::ConfigDescription __description_message__;
00369 static const PilotConfigStatics *get_instance()
00370 {
00371
00372
00373
00374
00375 static PilotConfigStatics instance;
00376 return &instance;
00377 }
00378 };
00379
00380 inline const dynamic_reconfigure::ConfigDescription &PilotConfig::__getDescriptionMessage__()
00381 {
00382 return __get_statics__()->__description_message__;
00383 }
00384
00385 inline const PilotConfig &PilotConfig::__getDefault__()
00386 {
00387 return __get_statics__()->__default__;
00388 }
00389
00390 inline const PilotConfig &PilotConfig::__getMax__()
00391 {
00392 return __get_statics__()->__max__;
00393 }
00394
00395 inline const PilotConfig &PilotConfig::__getMin__()
00396 {
00397 return __get_statics__()->__min__;
00398 }
00399
00400 inline const std::vector<PilotConfig::AbstractParamDescriptionConstPtr> &PilotConfig::__getParamDescriptions__()
00401 {
00402 return __get_statics__()->__param_descriptions__;
00403 }
00404
00405 inline const PilotConfigStatics *PilotConfig::__get_statics__()
00406 {
00407 const static PilotConfigStatics *statics;
00408
00409 if (statics)
00410 return statics;
00411
00412 boost::mutex::scoped_lock lock(dynamic_reconfigure::__init_mutex__);
00413
00414 if (statics)
00415 return statics;
00416
00417 statics = PilotConfigStatics::get_instance();
00418
00419 return statics;
00420 }
00421
00422
00423 const int Pilot_Accel_Plan = 0;
00424
00425 const int Pilot_Accel_Example = 1;
00426
00427 const int Pilot_Speed_PID = 2;
00428
00429 const int Pilot_Speed_Matrix = 3;
00430
00431 const int Pilot_Speed_Learned = 4;
00432 }
00433
00434 #endif // __PILOTRECONFIGURATOR_H__