ddynamic_reconfigure.cpp
Go to the documentation of this file.
2 #include <boost/make_unique.hpp>
3 namespace ddynamic_reconfigure
4 {
6  : node_handle_(nh), advertised_(false), auto_update_(auto_update), new_config_avail_(false)
7 {
11 }
12 
14 {
18 }
19 
21 {
22  if (advertised_)
23  {
24  return;
25  }
26  descr_pub_ = node_handle_.advertise<dynamic_reconfigure::ConfigDescription>(
27  "parameter_descriptions", 1, true);
28  const dynamic_reconfigure::ConfigDescription config_description = generateConfigDescription();
29  descr_pub_.publish(config_description);
30 
31  config_groups_.clear();
32  for (const auto &g : config_description.groups)
33  {
34  config_groups_.push_back(g.name);
35  }
36 
37  update_pub_ =
38  node_handle_.advertise<dynamic_reconfigure::Config>("parameter_updates", 1, true);
39 
41 
42  set_service_ = node_handle_.advertiseService("set_parameters",
44 
45  advertised_ = true;
46 }
47 
48 template <>
49 std::vector<std::unique_ptr<RegisteredParam<int>>> &DDynamicReconfigure::getRegisteredVector()
50 {
51  return registered_int_;
52 }
53 
54 template <>
55 std::vector<std::unique_ptr<RegisteredParam<double>>> &DDynamicReconfigure::getRegisteredVector()
56 {
57  return registered_double_;
58 }
59 
60 template <>
61 std::vector<std::unique_ptr<RegisteredParam<bool>>> &DDynamicReconfigure::getRegisteredVector()
62 {
63  return registered_bool_;
64 }
65 
66 template <>
67 std::vector<std::unique_ptr<RegisteredParam<std::string>>> &DDynamicReconfigure::getRegisteredVector()
68 {
69  return registered_string_;
70 }
71 
72 
73 template <typename T>
74 void DDynamicReconfigure::registerVariable(const std::string &name, T *variable,
75  const std::string &description, T min, T max,
76  const std::string &group)
77 {
78  registerVariable(name, variable, {}, description, min, max, group);
79 }
80 
81 template <typename T>
82 void DDynamicReconfigure::registerEnumVariable(const std::string &name, T *variable,
83  const std::string &description,
84  std::map<std::string, T> enum_dict,
85  const std::string &enum_description,
86  const std::string &group)
87 {
88  registerEnumVariable(name, variable, {}, description, enum_dict, enum_description, group);
89 }
90 
91 template <typename T>
92 void DDynamicReconfigure::registerVariable(const std::string &name, T *variable,
93  const boost::function<void(T value)> &callback,
94  const std::string &description, T min, T max,
95  const std::string &group)
96 {
97  attemptGetParam(node_handle_, name, *variable, *variable);
98  getRegisteredVector<T>().push_back(boost::make_unique<PointerRegisteredParam<T>>(
99  name, description, min, max, variable, callback, std::map<std::string, T>(), "", group));
100 }
101 
102 template <typename T>
103 void DDynamicReconfigure::registerEnumVariable(const std::string &name, T *variable,
104  const boost::function<void(T value)> &callback,
105  const std::string &description,
106  std::map<std::string, T> enum_dict,
107  const std::string &enum_description,
108  const std::string &group)
109 {
110  T min, max;
111  std::tie(min, max) = getMinMax(enum_dict);
112  attemptGetParam(node_handle_, name, *variable, *variable);
113  getRegisteredVector<T>().push_back(boost::make_unique<PointerRegisteredParam<T>>(
114  name, description, min, max, variable, callback, enum_dict, enum_description, group));
115 }
116 
117 template <typename T>
118 void DDynamicReconfigure::registerVariable(const std::string &name, T current_value,
119  const boost::function<void(T value)> &callback,
120  const std::string &description, T min, T max,
121  const std::string &group)
122 {
123  attemptGetParam(node_handle_, name, current_value, current_value);
124  getRegisteredVector<T>().push_back(boost::make_unique<CallbackRegisteredParam<T>>(
125  name, description, min, max, current_value, callback, std::map<std::string, T>(), "", group));
126 }
127 
128 
129 template <typename T>
130 void DDynamicReconfigure::registerEnumVariable(const std::string &name, T current_value,
131  const boost::function<void(T)> &callback,
132  const std::string &description,
133  std::map<std::string, T> enum_dict,
134  const std::string &enum_description,
135  const std::string &group)
136 {
137  T min, max;
138  std::tie(min, max) = getMinMax(enum_dict);
139  attemptGetParam(node_handle_, name, current_value, current_value);
140  getRegisteredVector<T>().push_back(boost::make_unique<CallbackRegisteredParam<T>>(
141  name, description, min, max, current_value, callback, enum_dict, enum_description, group));
142 }
143 
144 template <typename ParamType>
145 bool confCompare(const ParamType &a, const ParamType &b)
146 {
147  return (a.name == b.name) && (a.value == b.value);
148 }
149 
150 template <>
151 bool confCompare(const dynamic_reconfigure::DoubleParameter &a,
152  const dynamic_reconfigure::DoubleParameter &b)
153 {
154  return (a.name == b.name) &&
155  (std::fabs(a.value - b.value) < std::numeric_limits<double>::epsilon());
156 }
157 
159 {
160  dynamic_reconfigure::Config config_msg = generateConfig();
161 
162  bool has_changed = false;
163  has_changed = has_changed || config_msg.ints.size() != last_config_.ints.size();
164  has_changed = has_changed || config_msg.doubles.size() != last_config_.doubles.size();
165  has_changed = has_changed || config_msg.bools.size() != last_config_.bools.size();
166 
167  has_changed = has_changed ||
168  !std::equal(config_msg.ints.begin(), config_msg.ints.end(),
169  last_config_.ints.begin(),
170  confCompare<dynamic_reconfigure::IntParameter>);
171  has_changed = has_changed ||
172  !std::equal(config_msg.doubles.begin(), config_msg.doubles.end(),
173  last_config_.doubles.begin(),
174  confCompare<dynamic_reconfigure::DoubleParameter>);
175  has_changed = has_changed ||
176  !std::equal(config_msg.bools.begin(), config_msg.bools.end(),
177  last_config_.bools.begin(),
178  confCompare<dynamic_reconfigure::BoolParameter>);
179 
180  if (has_changed)
181  {
182  last_config_ = config_msg;
183  ROS_DEBUG_STREAM("Publishing ddr");
184  update_pub_.publish(config_msg);
185  }
186 }
187 
188 bool DDynamicReconfigure::setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req,
189  dynamic_reconfigure::Reconfigure::Response &rsp)
190 {
191  ROS_DEBUG_STREAM("Called config callback of ddynamic_reconfigure");
192 
194  {
195  try
196  {
198  }
199  catch (std::exception &e)
200  {
201  ROS_WARN("Reconfigure pre update callback failed with exception %s: ", e.what());
202  }
203  catch (...)
204  {
205  ROS_WARN("Reconfigure pre update callback failed with unprintable exception.");
206  }
207  }
208 
209  updated_config_ = req.config;
210  if (auto_update_)
211  {
213  }
214  else
215  {
216  new_config_avail_ = true;
217  const ros::Time start_time = ros::Time::now();
218  const ros::Duration timeout = ros::Duration(2.0);
219  while ((ros::Time::now() - start_time) < timeout && new_config_avail_)
220  {
221  // Wait until the updateRegisteredVariablesData method is called by the user or
222  // until the timeout
223  ros::Duration(0.01).sleep();
224  }
225  if ((ros::Time::now() - start_time) > timeout)
226  {
228  "Timeout waiting to update the registered variable data! Registered Variable data update failed!");
229  return true;
230  }
231  }
232 
233  /*
234  boost::recursive_mutex::scoped_lock lock(mutex_);
235 
236  ConfigType new_config = config_;
237  new_config.__fromMessage__(req.config);
238  new_config.__clamp__();
239  uint32_t level = config_.__level__(new_config);
240 
241  callCallback(new_config, level);
242 
243  updateConfigInternal(new_config);
244  new_config.__toMessage__(rsp.config);
245  */
246 
247  /*
248  ConfigType new_config = config_;
249  new_config.__fromMessage__(req.config);
250  new_config.__clamp__();
251  uint32_t level = config_.__level__(new_config);
252 
253  callCallback(new_config, level);
254 
255  updateConfigInternal(new_config);
256  new_config.__toMessage__(rsp.config);
257  */
258  // std::cerr<<req.config<<std::endl;
259 
261  {
262  try
263  {
265  }
266  catch (std::exception &e)
267  {
268  ROS_WARN("Reconfigure post update callback failed with exception %s: ", e.what());
269  }
270  catch (...)
271  {
272  ROS_WARN("Reconfigure post update callback failed with unprintable exception.");
273  }
274  }
275 
276  dynamic_reconfigure::Config config_msg = generateConfig();
277  update_pub_.publish(config_msg);
278  rsp.config = config_msg;
279 
281  return true;
282 }
283 
284 void DDynamicReconfigure::updateConfigData(const dynamic_reconfigure::Config &config)
285 {
286  for (unsigned int i = 0; i < config.ints.size(); ++i)
287  {
288  if (!assignValue(registered_int_, config.ints[i].name, config.ints[i].value))
289  {
290  ROS_ERROR_STREAM("Variable :" << config.ints[i].name << " not registered");
291  }
292  }
293  for (unsigned int i = 0; i < config.doubles.size(); ++i)
294  {
295  if (!assignValue(registered_double_, config.doubles[i].name, config.doubles[i].value))
296  {
297  ROS_ERROR_STREAM("Variable :" << config.doubles[i].name << " not registered");
298  }
299  }
300  for (unsigned int i = 0; i < config.bools.size(); ++i)
301  {
302  if (!assignValue(registered_bool_, config.bools[i].name, config.bools[i].value))
303  {
304  ROS_ERROR_STREAM("Variable :" << config.bools[i].name << " not registered");
305  }
306  }
307  for (unsigned int i = 0; i < config.strs.size(); ++i)
308  {
309  if (!assignValue(registered_string_, config.strs[i].name, config.strs[i].value))
310  {
311  ROS_ERROR_STREAM("Variable :" << config.strs[i].name << " not registered");
312  }
313  }
314 }
315 
317 {
318  setPostUpdateCallback(callback);
319 }
320 
322 {
324 }
325 
327 {
328  pre_update_callback_ = callback;
329 }
330 
332 {
333  pre_update_callback_.clear();
334 }
335 
337 {
338  post_update_callback_ = callback;
339 }
340 
342 {
343  post_update_callback_.clear();
344 }
345 
346 void DDynamicReconfigure::RegisterVariable(double *variable, std::string id, double min, double max)
347 {
348  registerVariable(id, variable, "", min, max);
349 }
350 
351 void DDynamicReconfigure::RegisterVariable(int *variable, std::string id, int min, int max)
352 {
353  registerVariable(id, variable, "", min, max);
354 }
355 
356 void DDynamicReconfigure::RegisterVariable(bool *variable, std::string id)
357 {
358  registerVariable(id, variable, "");
359 }
360 
361 dynamic_reconfigure::ConfigDescription DDynamicReconfigure::generateConfigDescription() const
362 {
363  dynamic_reconfigure::ConfigDescription config_description;
364 
365  std::map<std::string, dynamic_reconfigure::Group> groups;
366 
367  for (unsigned int i = 0; i < registered_int_.size(); ++i)
368  {
369  const RegisteredParam<int> &ri = *registered_int_[i];
370  dynamic_reconfigure::ParamDescription p = ri.getParamDescription();
371 
372  auto &gp = groups[ri.group_];
373  gp.parameters.push_back(p);
374 
375  // Max min def
376  dynamic_reconfigure::IntParameter ip;
377  ip.name = ri.name_;
378  ip.value = ri.getCurrentValue();
379  config_description.dflt.ints.push_back(ip);
380  ip.value = ri.max_value_;
381  config_description.max.ints.push_back(ip);
382  ip.value = ri.min_value_;
383  config_description.min.ints.push_back(ip);
384  }
385 
386  for (unsigned int i = 0; i < registered_double_.size(); ++i)
387  {
389  dynamic_reconfigure::ParamDescription p = rd.getParamDescription();
390 
391  auto &gp = groups[rd.group_];
392  gp.parameters.push_back(p);
393  // Max min def
394  dynamic_reconfigure::DoubleParameter dp;
395  dp.name = rd.name_;
396  dp.value = rd.getCurrentValue();
397  config_description.dflt.doubles.push_back(dp);
398  dp.value = rd.max_value_;
399  config_description.max.doubles.push_back(dp);
400  dp.value = rd.min_value_;
401  config_description.min.doubles.push_back(dp);
402  }
403 
404  for (unsigned int i = 0; i < registered_bool_.size(); ++i)
405  {
406  const RegisteredParam<bool> &rb = *registered_bool_[i];
407  dynamic_reconfigure::ParamDescription p = rb.getParamDescription();
408 
409  auto &gp = groups[rb.group_];
410  gp.parameters.push_back(p);
411 
412  // Max min def
413  dynamic_reconfigure::BoolParameter bp;
414  bp.name = rb.name_;
415  bp.value = rb.getCurrentValue();
416  config_description.dflt.bools.push_back(bp);
417  bp.value = rb.max_value_;
418  config_description.max.bools.push_back(bp);
419  bp.value = rb.min_value_;
420  config_description.min.bools.push_back(bp);
421  }
422  for (unsigned int i = 0; i < registered_string_.size(); ++i)
423  {
425  dynamic_reconfigure::ParamDescription p = rs.getParamDescription();
426 
427  auto &gp = groups[rs.group_];
428  gp.parameters.push_back(p);
429 
430  // Max min def
431  dynamic_reconfigure::StrParameter sp;
432  sp.name = rs.name_;
433  sp.value = rs.getCurrentValue();
434  config_description.dflt.strs.push_back(sp);
435  sp.value = rs.max_value_;
436  config_description.max.strs.push_back(sp);
437  sp.value = rs.min_value_;
438  config_description.min.strs.push_back(sp);
439  }
440 
441  auto default_group = groups["Default"];
442  default_group.name = "Default";
443  config_description.groups.push_back(default_group);
444 
445  dynamic_reconfigure::GroupState default_gs;
446  default_gs.name = "Default";
447  default_gs.state = true;
448  config_description.dflt.groups.push_back(default_gs);
449  config_description.min.groups.push_back(default_gs);
450  config_description.max.groups.push_back(default_gs);
451 
452  size_t i = 1;
453  for (auto &group : groups)
454  {
455  if (group.first == "Default")
456  {
457  continue;
458  }
459  group.second.name = group.first;
460  group.second.type = "tab";
461  group.second.id = i++;
462  config_description.groups.push_back(group.second);
463 
464  dynamic_reconfigure::GroupState gs;
465  gs.id = group.second.id;
466  gs.name = group.second.name;
467  gs.state = true;
468  config_description.dflt.groups.push_back(gs);
469  config_description.min.groups.push_back(gs);
470  config_description.max.groups.push_back(gs);
471  }
472  return config_description;
473 }
474 
475 
476 dynamic_reconfigure::Config DDynamicReconfigure::generateConfig()
477 {
478  dynamic_reconfigure::Config c;
479 
480  for (unsigned int i = 0; i < registered_int_.size(); ++i)
481  {
482  dynamic_reconfigure::IntParameter ip;
483  ip.name = registered_int_[i]->name_;
484  ip.value = registered_int_[i]->getCurrentValue();
485  c.ints.push_back(ip);
486  }
487 
488  for (unsigned int i = 0; i < registered_double_.size(); ++i)
489  {
490  dynamic_reconfigure::DoubleParameter dp;
491  dp.name = registered_double_[i]->name_;
492  dp.value = registered_double_[i]->getCurrentValue();
493  c.doubles.push_back(dp);
494  }
495 
496  for (unsigned int i = 0; i < registered_bool_.size(); ++i)
497  {
498  dynamic_reconfigure::BoolParameter bp;
499  bp.name = registered_bool_[i]->name_;
500  bp.value = registered_bool_[i]->getCurrentValue();
501  c.bools.push_back(bp);
502  }
503 
504  for (unsigned int i = 0; i < registered_string_.size(); ++i)
505  {
506  dynamic_reconfigure::StrParameter bs;
507  bs.name = registered_string_[i]->name_;
508  bs.value = registered_string_[i]->getCurrentValue();
509  c.strs.push_back(bs);
510  }
511 
512  for (size_t i = 0; i < config_groups_.size(); ++i)
513  {
514  dynamic_reconfigure::GroupState gs;
515  gs.name = config_groups_[i];
516  gs.id = i;
517  gs.state = true;
518  c.groups.push_back(gs);
519  }
520 
521  return c;
522 }
523 
524 
525 
527 {
529 }
530 
532 {
534  return;
536  new_config_avail_ = false;
537 }
538 
539 
540 // Explicit int instantations
541 template void DDynamicReconfigure::registerVariable(const std::string &name, int *variable,
542  const std::string &description, int min,
543  int max, const std::string &group);
544 
545 
546 template void DDynamicReconfigure::registerEnumVariable(const std::string &name, int *variable,
547  const std::string &description,
548  std::map<std::string, int> enum_dict,
549  const std::string &enum_description,
550  const std::string &group);
551 template void DDynamicReconfigure::registerVariable(const std::string &name, int current_value,
552  const boost::function<void(int value)> &callback,
553  const std::string &description, int min,
554  int max, const std::string &group);
555 
557  const std::string &name, int current_value, const boost::function<void(int)> &callback,
558  const std::string &description, std::map<std::string, int> enum_dict,
559  const std::string &enum_description, const std::string &group);
560 
561 
562 // Explicit double instantations
563 template void DDynamicReconfigure::registerVariable(const std::string &name, double *variable,
564  const std::string &description, double min,
565  double max, const std::string &group);
566 
567 
568 template void DDynamicReconfigure::registerEnumVariable(const std::string &name, double *variable,
569  const std::string &description,
570  std::map<std::string, double> enum_dict,
571  const std::string &enum_description,
572  const std::string &group);
574  const std::string &name, double current_value,
575  const boost::function<void(double value)> &callback, const std::string &description,
576  double min, double max, const std::string &group);
577 
579  const std::string &name, double current_value, const boost::function<void(double)> &callback,
580  const std::string &description, std::map<std::string, double> enum_dict,
581  const std::string &enum_description, const std::string &group);
582 
583 
584 
585 // Explicit bool instantations
586 template void DDynamicReconfigure::registerVariable(const std::string &name, bool *variable,
587  const std::string &description, bool min,
588  bool max, const std::string &group);
589 
590 
591 template void DDynamicReconfigure::registerEnumVariable(const std::string &name, bool *variable,
592  const std::string &description,
593  std::map<std::string, bool> enum_dict,
594  const std::string &enum_description,
595  const std::string &group);
596 template void DDynamicReconfigure::registerVariable(const std::string &name, bool current_value,
597  const boost::function<void(bool value)> &callback,
598  const std::string &description, bool min,
599  bool max, const std::string &group);
600 
602  const std::string &name, bool current_value, const boost::function<void(bool)> &callback,
603  const std::string &description, std::map<std::string, bool> enum_dict,
604  const std::string &enum_description, const std::string &group);
605 
606 
607 // Explicit std::string instantations
608 template void DDynamicReconfigure::registerVariable(const std::string &name, std::string *variable,
609  const std::string &description,
610  std::string min, std::string max,
611  const std::string &group);
612 
613 
615  const std::string &name, std::string *variable, const std::string &description,
616  std::map<std::string, std::string> enum_dict, const std::string &enum_description,
617  const std::string &group);
619  const std::string &name, std::string current_value,
620  const boost::function<void(std::string value)> &callback, const std::string &description,
621  std::string min, std::string max, const std::string &group);
622 
624  const std::string &name, std::string current_value,
625  const boost::function<void(std::string)> &callback, const std::string &description,
626  std::map<std::string, std::string> enum_dict, const std::string &enum_description,
627  const std::string &group);
628 }
ddynamic_reconfigure::RegisteredParam::getCurrentValue
virtual T getCurrentValue() const =0
ddynamic_reconfigure::DDynamicReconfigure::generateConfigDescription
virtual dynamic_reconfigure::ConfigDescription generateConfigDescription() const
Definition: ddynamic_reconfigure.cpp:361
min
int min(int a, int b)
ddynamic_reconfigure::RegisteredParam::name_
const std::string name_
Definition: registered_param.h:154
ddynamic_reconfigure.h
ddynamic_reconfigure::DDynamicReconfigure::node_handle_
ros::NodeHandle node_handle_
setUserCallback Set a function to be called when parameters have changed
Definition: ddynamic_reconfigure.h:194
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ddynamic_reconfigure::DDynamicReconfigure::getRegisteredVector
std::vector< std::unique_ptr< RegisteredParam< T > > > & getRegisteredVector()
ddynamic_reconfigure::DDynamicReconfigure::new_config_avail_
std::atomic_bool new_config_avail_
Definition: ddynamic_reconfigure.h:202
ddynamic_reconfigure::DDynamicReconfigure::config_groups_
std::vector< std::string > config_groups_
Definition: ddynamic_reconfigure.h:209
ddynamic_reconfigure::DDynamicReconfigure::post_update_callback_
UserCallbackType post_update_callback_
Definition: ddynamic_reconfigure.h:212
ddynamic_reconfigure::DDynamicReconfigure::setConfigCallback
virtual bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req, dynamic_reconfigure::Reconfigure::Response &rsp)
Definition: ddynamic_reconfigure.cpp:188
ddynamic_reconfigure
Definition: ddynamic_reconfigure.h:42
ddynamic_reconfigure::DDynamicReconfigure::advertised_
bool advertised_
Definition: ddynamic_reconfigure.h:199
ddynamic_reconfigure::DDynamicReconfigure::set_service_
ros::ServiceServer set_service_
Definition: ddynamic_reconfigure.h:195
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
ddynamic_reconfigure::DDynamicReconfigure::clearUserCallback
virtual void clearUserCallback()
Definition: ddynamic_reconfigure.cpp:321
ddynamic_reconfigure::PointerRegisteredParam
Definition: registered_param.h:165
ddynamic_reconfigure::DDynamicReconfigure::updateConfigData
virtual void updateConfigData(const dynamic_reconfigure::Config &config)
Definition: ddynamic_reconfigure.cpp:284
ddynamic_reconfigure::DDynamicReconfigure::registerEnumVariable
void registerEnumVariable(const std::string &name, T *variable, const std::string &description="", std::map< std::string, T > enum_dict={}, const std::string &enum_description="", const std::string &group="Default")
Definition: ddynamic_reconfigure.cpp:82
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ddynamic_reconfigure::DDynamicReconfigure::registered_double_
std::vector< std::unique_ptr< RegisteredParam< double > > > registered_double_
Definition: ddynamic_reconfigure.h:206
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ddynamic_reconfigure::DDynamicReconfigure::last_config_
dynamic_reconfigure::Config last_config_
Definition: ddynamic_reconfigure.h:215
assignValue
bool assignValue(const std::vector< T > &v, const std::string &name, const V &value)
Definition: ddynamic_reconfigure_utils.h:74
ddynamic_reconfigure::DDynamicReconfigure::registered_bool_
std::vector< std::unique_ptr< RegisteredParam< bool > > > registered_bool_
Definition: ddynamic_reconfigure.h:207
ddynamic_reconfigure::DDynamicReconfigure::PublishServicesTopics
virtual void PublishServicesTopics()
Definition: ddynamic_reconfigure.cpp:526
ddynamic_reconfigure::confCompare
bool confCompare(const ParamType &a, const ParamType &b)
Definition: ddynamic_reconfigure.cpp:145
ddynamic_reconfigure::DDynamicReconfigure::registerVariable
void registerVariable(const std::string &name, T *variable, const std::string &description="", T min=getMin< T >(), T max=getMax< T >(), const std::string &group="Default")
registerVariable register a variable to be modified via the dynamic_reconfigure API....
Definition: ddynamic_reconfigure.cpp:74
ddynamic_reconfigure::DDynamicReconfigure::updateRegisteredVariablesData
virtual void updateRegisteredVariablesData()
updateRegisteredVariablesData - Method to be called to update the registered variable,...
Definition: ddynamic_reconfigure.cpp:531
ddynamic_reconfigure::DDynamicReconfigure::clearPostUpdateCallback
virtual void clearPostUpdateCallback()
Definition: ddynamic_reconfigure.cpp:341
ddynamic_reconfigure::DDynamicReconfigure::setUserCallback
virtual void setUserCallback(const UserCallbackType &callback)
setUserCallback An optional callback that will be called whenever a value is changed....
Definition: ddynamic_reconfigure.cpp:316
ddynamic_reconfigure::DDynamicReconfigure::pre_update_callback_
UserCallbackType pre_update_callback_
Definition: ddynamic_reconfigure.h:211
ros::Publisher::shutdown
void shutdown()
ros::Timer::setPeriod
void setPeriod(const Duration &period, bool reset=true)
ddynamic_reconfigure::DDynamicReconfigure::~DDynamicReconfigure
virtual ~DDynamicReconfigure()
Definition: ddynamic_reconfigure.cpp:13
ddynamic_reconfigure::DDynamicReconfigure::clearPreUpdateCallback
virtual void clearPreUpdateCallback()
Definition: ddynamic_reconfigure.cpp:331
ROS_WARN
#define ROS_WARN(...)
ddynamic_reconfigure::RegisteredParam::getParamDescription
virtual dynamic_reconfigure::ParamDescription getParamDescription() const
Definition: registered_param.h:98
attemptGetParam
void attemptGetParam(ros::NodeHandle &nh, const std::string &name, T &param, T default_value)
Definition: ddynamic_reconfigure_utils.h:88
ddynamic_reconfigure::DDynamicReconfigure::generateConfig
virtual dynamic_reconfigure::Config generateConfig()
Definition: ddynamic_reconfigure.cpp:476
ddynamic_reconfigure::DDynamicReconfigure::descr_pub_
ros::Publisher descr_pub_
Definition: ddynamic_reconfigure.h:197
ddynamic_reconfigure::RegisteredParam
Definition: registered_param.h:42
ddynamic_reconfigure::DDynamicReconfigure::RegisterVariable
virtual void RegisterVariable(double *variable, std::string id, double min=-100, double max=100)
Definition: ddynamic_reconfigure.cpp:346
ddynamic_reconfigure::DDynamicReconfigure::UserCallbackType
boost::function< void()> UserCallbackType
Definition: ddynamic_reconfigure.h:131
ros::Time
ddynamic_reconfigure::DDynamicReconfigure::pub_config_timer_
ros::Timer pub_config_timer_
Definition: ddynamic_reconfigure.h:214
ddynamic_reconfigure::DDynamicReconfigure::setPostUpdateCallback
virtual void setPostUpdateCallback(const UserCallbackType &callback)
setPostUpdateCallback An optional callback that will be called right after any value is changed.
Definition: ddynamic_reconfigure.cpp:336
ddynamic_reconfigure::DDynamicReconfigure::publishServicesTopics
virtual void publishServicesTopics()
publishServicesTopics starts the server once all the needed variables are registered
Definition: ddynamic_reconfigure.cpp:20
ddynamic_reconfigure::RegisteredParam::min_value_
const T min_value_
Definition: registered_param.h:156
ddynamic_reconfigure::DDynamicReconfigure::setPreUpdateCallback
virtual void setPreUpdateCallback(const UserCallbackType &callback)
setPreUpdateCallback An optional callback that will be called right before any value is changed
Definition: ddynamic_reconfigure.cpp:326
ddynamic_reconfigure::DDynamicReconfigure::updated_config_
dynamic_reconfigure::Config updated_config_
Definition: ddynamic_reconfigure.h:216
ddynamic_reconfigure::DDynamicReconfigure::auto_update_
bool auto_update_
Definition: ddynamic_reconfigure.h:200
ros::ServiceServer::shutdown
void shutdown()
ddynamic_reconfigure::RegisteredParam::max_value_
const T max_value_
Definition: registered_param.h:157
ros::Duration::sleep
bool sleep() const
ddynamic_reconfigure::DDynamicReconfigure::DDynamicReconfigure
DDynamicReconfigure(const ros::NodeHandle &nh=ros::NodeHandle("~"), bool auto_update=true)
Definition: ddynamic_reconfigure.cpp:5
ddynamic_reconfigure::DDynamicReconfigure::registered_string_
std::vector< std::unique_ptr< RegisteredParam< std::string > > > registered_string_
Definition: ddynamic_reconfigure.h:208
ddynamic_reconfigure::DDynamicReconfigure::updatePublishedInformation
virtual void updatePublishedInformation()
Definition: ddynamic_reconfigure.cpp:158
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ddynamic_reconfigure::RegisteredParam::group_
const std::string group_
Definition: registered_param.h:160
ddynamic_reconfigure::CallbackRegisteredParam
Definition: registered_param.h:197
ddynamic_reconfigure::DDynamicReconfigure::registered_int_
std::vector< std::unique_ptr< RegisteredParam< int > > > registered_int_
Definition: ddynamic_reconfigure.h:205
getMinMax
std::pair< T, T > getMinMax(const std::map< std::string, T > &enum_map)
Definition: ddynamic_reconfigure_utils.h:96
ros::NodeHandle
ros::Time::now
static Time now()
ddynamic_reconfigure::DDynamicReconfigure::update_pub_
ros::Publisher update_pub_
Definition: ddynamic_reconfigure.h:196


ddynamic_reconfigure
Author(s): Hilario Tome
autogenerated on Tue Apr 22 2025 02:22:29