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 __costmap_2d__COSTMAP2DCONFIG_H__
00048 #define __costmap_2d__COSTMAP2DCONFIG_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 costmap_2d
00058 {
00059 class Costmap2DConfigStatics;
00060
00061 class Costmap2DConfig
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(Costmap2DConfig &config, const Costmap2DConfig &max, const Costmap2DConfig &min) const = 0;
00078 virtual void calcLevel(uint32_t &level, const Costmap2DConfig &config1, const Costmap2DConfig &config2) const = 0;
00079 virtual void fromServer(const ros::NodeHandle &nh, Costmap2DConfig &config) const = 0;
00080 virtual void toServer(const ros::NodeHandle &nh, const Costmap2DConfig &config) const = 0;
00081 virtual bool fromMessage(const dynamic_reconfigure::Config &msg, Costmap2DConfig &config) const = 0;
00082 virtual void toMessage(dynamic_reconfigure::Config &msg, const Costmap2DConfig &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 Costmap2DConfig::* f) :
00094 AbstractParamDescription(name, type, level, description, edit_method),
00095 field(f)
00096 {}
00097
00098 T (Costmap2DConfig::* field);
00099
00100 virtual void clamp(Costmap2DConfig &config, const Costmap2DConfig &max, const Costmap2DConfig &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 Costmap2DConfig &config1, const Costmap2DConfig &config2) const
00110 {
00111 if (config1.*field != config2.*field)
00112 comb_level |= level;
00113 }
00114
00115 virtual void fromServer(const ros::NodeHandle &nh, Costmap2DConfig &config) const
00116 {
00117 nh.getParam(name, config.*field);
00118 }
00119
00120 virtual void toServer(const ros::NodeHandle &nh, const Costmap2DConfig &config) const
00121 {
00122 nh.setParam(name, config.*field);
00123 }
00124
00125 virtual bool fromMessage(const dynamic_reconfigure::Config &msg, Costmap2DConfig &config) const
00126 {
00127 return dynamic_reconfigure::ConfigTools::getParameter(msg, name, config.*field);
00128 }
00129
00130 virtual void toMessage(dynamic_reconfigure::Config &msg, const Costmap2DConfig &config) const
00131 {
00132 dynamic_reconfigure::ConfigTools::appendParameter(msg, name, config.*field);
00133 }
00134 };
00135
00136
00137 double transform_tolerance;
00138
00139 double update_frequency;
00140
00141 double publish_frequency;
00142
00143 double max_obstacle_height;
00144
00145 double max_obstacle_range;
00146
00147 double raytrace_range;
00148
00149 double cost_scaling_factor;
00150
00151 double inflation_radius;
00152
00153 std::string footprint;
00154
00155 double robot_radius;
00156
00157 bool static_map;
00158
00159 bool rolling_window;
00160
00161 int unknown_cost_value;
00162
00163 int width;
00164
00165 int height;
00166
00167 double resolution;
00168
00169 double origin_x;
00170
00171 double origin_y;
00172
00173 bool publish_voxel_map;
00174
00175 int lethal_cost_threshold;
00176
00177 std::string map_topic;
00178
00179 std::string map_type;
00180
00181 double origin_z;
00182
00183 double z_resolution;
00184
00185 int z_voxels;
00186
00187 int unknown_threshold;
00188
00189 int mark_threshold;
00190
00191 bool track_unknown_space;
00192
00193 bool restore_defaults;
00194
00195
00196 bool __fromMessage__(dynamic_reconfigure::Config &msg)
00197 {
00198 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00199 int count = 0;
00200 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00201 if ((*i)->fromMessage(msg, *this))
00202 count++;
00203 if (count != dynamic_reconfigure::ConfigTools::size(msg))
00204 {
00205 ROS_ERROR("Costmap2DConfig::__fromMessage__ called with an unexpected parameter.");
00206 ROS_ERROR("Booleans:");
00207 for (unsigned int i = 0; i < msg.bools.size(); i++)
00208 ROS_ERROR(" %s", msg.bools[i].name.c_str());
00209 ROS_ERROR("Integers:");
00210 for (unsigned int i = 0; i < msg.ints.size(); i++)
00211 ROS_ERROR(" %s", msg.ints[i].name.c_str());
00212 ROS_ERROR("Doubles:");
00213 for (unsigned int i = 0; i < msg.doubles.size(); i++)
00214 ROS_ERROR(" %s", msg.doubles[i].name.c_str());
00215 ROS_ERROR("Strings:");
00216 for (unsigned int i = 0; i < msg.strs.size(); i++)
00217 ROS_ERROR(" %s", msg.strs[i].name.c_str());
00218
00219
00220 return false;
00221 }
00222 return true;
00223 }
00224
00225
00226
00227 void __toMessage__(dynamic_reconfigure::Config &msg, const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__) const
00228 {
00229 dynamic_reconfigure::ConfigTools::clear(msg);
00230 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00231 (*i)->toMessage(msg, *this);
00232 }
00233
00234 void __toMessage__(dynamic_reconfigure::Config &msg) const
00235 {
00236 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00237 __toMessage__(msg, __param_descriptions__);
00238 }
00239
00240 void __toServer__(const ros::NodeHandle &nh) const
00241 {
00242 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00243 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00244 (*i)->toServer(nh, *this);
00245 }
00246
00247 void __fromServer__(const ros::NodeHandle &nh)
00248 {
00249 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00250 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00251 (*i)->fromServer(nh, *this);
00252 }
00253
00254 void __clamp__()
00255 {
00256 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00257 const Costmap2DConfig &__max__ = __getMax__();
00258 const Costmap2DConfig &__min__ = __getMin__();
00259 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00260 (*i)->clamp(*this, __max__, __min__);
00261 }
00262
00263 uint32_t __level__(const Costmap2DConfig &config) const
00264 {
00265 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00266 uint32_t level = 0;
00267 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00268 (*i)->calcLevel(level, config, *this);
00269 return level;
00270 }
00271
00272 static const dynamic_reconfigure::ConfigDescription &__getDescriptionMessage__();
00273 static const Costmap2DConfig &__getDefault__();
00274 static const Costmap2DConfig &__getMax__();
00275 static const Costmap2DConfig &__getMin__();
00276 static const std::vector<AbstractParamDescriptionConstPtr> &__getParamDescriptions__();
00277
00278 private:
00279 static const Costmap2DConfigStatics *__get_statics__();
00280 };
00281
00282 template <>
00283 inline void Costmap2DConfig::ParamDescription<std::string>::clamp(Costmap2DConfig &config, const Costmap2DConfig &max, const Costmap2DConfig &min) const
00284 {
00285 return;
00286 }
00287
00288 class Costmap2DConfigStatics
00289 {
00290 friend class Costmap2DConfig;
00291
00292 Costmap2DConfigStatics()
00293 {
00294
00295 __min__.transform_tolerance = 0.0;
00296
00297 __max__.transform_tolerance = 10.0;
00298
00299 __default__.transform_tolerance = 0.3;
00300
00301 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("transform_tolerance", "double", 0, "Specifies the delay in transform (tf) data that is tolerable in seconds.", "", &Costmap2DConfig::transform_tolerance)));
00302
00303 __min__.update_frequency = 0.0;
00304
00305 __max__.update_frequency = 100.0;
00306
00307 __default__.update_frequency = 5.0;
00308
00309 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("update_frequency", "double", 0, "The frequency in Hz for the map to be updated.", "", &Costmap2DConfig::update_frequency)));
00310
00311 __min__.publish_frequency = 0.0;
00312
00313 __max__.publish_frequency = 100.0;
00314
00315 __default__.publish_frequency = 0.0;
00316
00317 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("publish_frequency", "double", 0, "The frequency in Hz for the map to be publish display information.", "", &Costmap2DConfig::publish_frequency)));
00318
00319 __min__.max_obstacle_height = 0.0;
00320
00321 __max__.max_obstacle_height = 50.0;
00322
00323 __default__.max_obstacle_height = 2.0;
00324
00325 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("max_obstacle_height", "double", 0, "The maximum height of any obstacle to be inserted into the costmap in meters.", "", &Costmap2DConfig::max_obstacle_height)));
00326
00327 __min__.max_obstacle_range = 0.0;
00328
00329 __max__.max_obstacle_range = 50.0;
00330
00331 __default__.max_obstacle_range = 2.5;
00332
00333 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("max_obstacle_range", "double", 0, "The default maximum distance from the robot at which an obstacle will be inserted into the cost map in meters.", "", &Costmap2DConfig::max_obstacle_range)));
00334
00335 __min__.raytrace_range = 0.0;
00336
00337 __max__.raytrace_range = 50.0;
00338
00339 __default__.raytrace_range = 3.0;
00340
00341 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("raytrace_range", "double", 0, "The default range in meters at which to raytrace out obstacles from the map using sensor data.", "", &Costmap2DConfig::raytrace_range)));
00342
00343 __min__.cost_scaling_factor = 0.0;
00344
00345 __max__.cost_scaling_factor = 100.0;
00346
00347 __default__.cost_scaling_factor = 10.0;
00348
00349 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("cost_scaling_factor", "double", 0, "A scaling factor to apply to cost values during inflation.", "", &Costmap2DConfig::cost_scaling_factor)));
00350
00351 __min__.inflation_radius = 0.0;
00352
00353 __max__.inflation_radius = 50.0;
00354
00355 __default__.inflation_radius = 0.55;
00356
00357 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("inflation_radius", "double", 0, "The radius in meters to which the map inflates obstacle cost values.", "", &Costmap2DConfig::inflation_radius)));
00358
00359 __min__.footprint = "";
00360
00361 __max__.footprint = "";
00362
00363 __default__.footprint = "[]";
00364
00365 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<std::string>("footprint", "str", 0, "The footprint of the robot specified in the robot_base_frame coordinate frame as a list in the format: [ [x1, y1], [x2, y2], ...., [xn, yn] ].", "", &Costmap2DConfig::footprint)));
00366
00367 __min__.robot_radius = 0.0;
00368
00369 __max__.robot_radius = 10.0;
00370
00371 __default__.robot_radius = 0.46;
00372
00373 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("robot_radius", "double", 0, "The radius of the robot in meters, this parameter should only be set for circular robots, all others should use the footprint parameter described above.", "", &Costmap2DConfig::robot_radius)));
00374
00375 __min__.static_map = 0;
00376
00377 __max__.static_map = 1;
00378
00379 __default__.static_map = 1;
00380
00381 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<bool>("static_map", "bool", 0, "Whether or not to use the static map to initialize the costmap.", "", &Costmap2DConfig::static_map)));
00382
00383 __min__.rolling_window = 0;
00384
00385 __max__.rolling_window = 1;
00386
00387 __default__.rolling_window = 0;
00388
00389 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<bool>("rolling_window", "bool", 0, "Whether or not to use a rolling window version of the costmap.", "", &Costmap2DConfig::rolling_window)));
00390
00391 __min__.unknown_cost_value = 0;
00392
00393 __max__.unknown_cost_value = 255;
00394
00395 __default__.unknown_cost_value = 0;
00396
00397 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<int>("unknown_cost_value", "int", 0, "The value for which a cost should be considered unknown when reading in a map from the map server.", "", &Costmap2DConfig::unknown_cost_value)));
00398
00399 __min__.width = 0;
00400
00401 __max__.width = 20;
00402
00403 __default__.width = 0;
00404
00405 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<int>("width", "int", 0, "The width of the map in meters.", "", &Costmap2DConfig::width)));
00406
00407 __min__.height = 0;
00408
00409 __max__.height = 20;
00410
00411 __default__.height = 10;
00412
00413 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<int>("height", "int", 0, "The height of the map in meters.", "", &Costmap2DConfig::height)));
00414
00415 __min__.resolution = 0.0;
00416
00417 __max__.resolution = 50.0;
00418
00419 __default__.resolution = 0.05;
00420
00421 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("resolution", "double", 0, "The resolution of the map in meters/cell.", "", &Costmap2DConfig::resolution)));
00422
00423 __min__.origin_x = 0.0;
00424
00425 __max__.origin_x = std::numeric_limits<double>::infinity();
00426
00427 __default__.origin_x = 0.0;
00428
00429 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("origin_x", "double", 0, "The x origin of the map in the global frame in meters.", "", &Costmap2DConfig::origin_x)));
00430
00431 __min__.origin_y = 0.0;
00432
00433 __max__.origin_y = std::numeric_limits<double>::infinity();
00434
00435 __default__.origin_y = 0.0;
00436
00437 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("origin_y", "double", 0, "The y origin of the map in the global frame in meters.", "", &Costmap2DConfig::origin_y)));
00438
00439 __min__.publish_voxel_map = 0;
00440
00441 __max__.publish_voxel_map = 1;
00442
00443 __default__.publish_voxel_map = 0;
00444
00445 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<bool>("publish_voxel_map", "bool", 0, "Whether or not to publish the underlying voxel grid for visualization purposes.", "", &Costmap2DConfig::publish_voxel_map)));
00446
00447 __min__.lethal_cost_threshold = 0;
00448
00449 __max__.lethal_cost_threshold = 255;
00450
00451 __default__.lethal_cost_threshold = 100;
00452
00453 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<int>("lethal_cost_threshold", "int", 0, "The threshold value at which to consider a cost lethal when reading in a map from the map server.", "", &Costmap2DConfig::lethal_cost_threshold)));
00454
00455 __min__.map_topic = "";
00456
00457 __max__.map_topic = "";
00458
00459 __default__.map_topic = "map";
00460
00461 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<std::string>("map_topic", "str", 0, "The topic that the costmap subscribes to for the static map.", "", &Costmap2DConfig::map_topic)));
00462
00463 __min__.map_type = "";
00464
00465 __max__.map_type = "";
00466
00467 __default__.map_type = "costmap";
00468
00469 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<std::string>("map_type", "str", 0, "What map type to use. voxel or costmap are the supported types", "{'enum_description': 'An enum to set the map type', 'enum': [{'srcline': 13, 'description': 'Use VoxelCostmap2D', 'srcfile': '../cfg/Costmap2D.cfg', 'cconsttype': 'const char * const', 'value': 'voxel', 'ctype': 'std::string', 'type': 'str', 'name': 'voxel_const'}, {'srcline': 13, 'description': 'Use Costmap2D', 'srcfile': '../cfg/Costmap2D.cfg', 'cconsttype': 'const char * const', 'value': 'costmap', 'ctype': 'std::string', 'type': 'str', 'name': 'costmap_const'}]}", &Costmap2DConfig::map_type)));
00470
00471 __min__.origin_z = 0.0;
00472
00473 __max__.origin_z = std::numeric_limits<double>::infinity();
00474
00475 __default__.origin_z = 0.0;
00476
00477 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("origin_z", "double", 0, "The z origin of the map in meters.", "", &Costmap2DConfig::origin_z)));
00478
00479 __min__.z_resolution = 0.0;
00480
00481 __max__.z_resolution = 50.0;
00482
00483 __default__.z_resolution = 0.2;
00484
00485 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<double>("z_resolution", "double", 0, "The z resolution of the map in meters/cell.", "", &Costmap2DConfig::z_resolution)));
00486
00487 __min__.z_voxels = 0;
00488
00489 __max__.z_voxels = 16;
00490
00491 __default__.z_voxels = 10;
00492
00493 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<int>("z_voxels", "int", 0, "The number of voxels to in each vertical column.", "", &Costmap2DConfig::z_voxels)));
00494
00495 __min__.unknown_threshold = 0;
00496
00497 __max__.unknown_threshold = 16;
00498
00499 __default__.unknown_threshold = 15;
00500
00501 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<int>("unknown_threshold", "int", 0, "The number of unknown cells allowed in a column considered to be known", "", &Costmap2DConfig::unknown_threshold)));
00502
00503 __min__.mark_threshold = 0;
00504
00505 __max__.mark_threshold = 16;
00506
00507 __default__.mark_threshold = 0;
00508
00509 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<int>("mark_threshold", "int", 0, "The maximum number of marked cells allowed in a column considered to be free", "", &Costmap2DConfig::mark_threshold)));
00510
00511 __min__.track_unknown_space = 0;
00512
00513 __max__.track_unknown_space = 1;
00514
00515 __default__.track_unknown_space = 0;
00516
00517 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<bool>("track_unknown_space", "bool", 0, "Specifies whether or not to track what space in the costmap is unknown", "", &Costmap2DConfig::track_unknown_space)));
00518
00519 __min__.restore_defaults = 0;
00520
00521 __max__.restore_defaults = 1;
00522
00523 __default__.restore_defaults = 0;
00524
00525 __param_descriptions__.push_back(Costmap2DConfig::AbstractParamDescriptionConstPtr(new Costmap2DConfig::ParamDescription<bool>("restore_defaults", "bool", 0, "Restore to the original configuration", "", &Costmap2DConfig::restore_defaults)));
00526
00527
00528 for (std::vector<Costmap2DConfig::AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00529 __description_message__.parameters.push_back(**i);
00530 __max__.__toMessage__(__description_message__.max, __param_descriptions__);
00531 __min__.__toMessage__(__description_message__.min, __param_descriptions__);
00532 __default__.__toMessage__(__description_message__.dflt, __param_descriptions__);
00533 }
00534 std::vector<Costmap2DConfig::AbstractParamDescriptionConstPtr> __param_descriptions__;
00535 Costmap2DConfig __max__;
00536 Costmap2DConfig __min__;
00537 Costmap2DConfig __default__;
00538 dynamic_reconfigure::ConfigDescription __description_message__;
00539 static const Costmap2DConfigStatics *get_instance()
00540 {
00541
00542
00543
00544
00545 static Costmap2DConfigStatics instance;
00546 return &instance;
00547 }
00548 };
00549
00550 inline const dynamic_reconfigure::ConfigDescription &Costmap2DConfig::__getDescriptionMessage__()
00551 {
00552 return __get_statics__()->__description_message__;
00553 }
00554
00555 inline const Costmap2DConfig &Costmap2DConfig::__getDefault__()
00556 {
00557 return __get_statics__()->__default__;
00558 }
00559
00560 inline const Costmap2DConfig &Costmap2DConfig::__getMax__()
00561 {
00562 return __get_statics__()->__max__;
00563 }
00564
00565 inline const Costmap2DConfig &Costmap2DConfig::__getMin__()
00566 {
00567 return __get_statics__()->__min__;
00568 }
00569
00570 inline const std::vector<Costmap2DConfig::AbstractParamDescriptionConstPtr> &Costmap2DConfig::__getParamDescriptions__()
00571 {
00572 return __get_statics__()->__param_descriptions__;
00573 }
00574
00575 inline const Costmap2DConfigStatics *Costmap2DConfig::__get_statics__()
00576 {
00577 const static Costmap2DConfigStatics *statics;
00578
00579 if (statics)
00580 return statics;
00581
00582 boost::mutex::scoped_lock lock(dynamic_reconfigure::__init_mutex__);
00583
00584 if (statics)
00585 return statics;
00586
00587 statics = Costmap2DConfigStatics::get_instance();
00588
00589 return statics;
00590 }
00591
00592
00593 const char * const Costmap2D_voxel_const = "voxel";
00594
00595 const char * const Costmap2D_costmap_const = "costmap";
00596 }
00597
00598 #endif // __COSTMAP2DRECONFIGURATOR_H__