2 #include <boost/make_unique.hpp>
6 : node_handle_(nh), advertised_(false), auto_update_(auto_update), new_config_avail_(false)
27 "parameter_descriptions", 1,
true);
32 for (
const auto &g : config_description.groups)
75 const std::string &description, T min, T max,
76 const std::string &group)
83 const std::string &description,
84 std::map<std::string, T> enum_dict,
85 const std::string &enum_description,
86 const std::string &group)
93 const boost::function<
void(T value)> &callback,
94 const std::string &description, T min, T max,
95 const std::string &group)
99 name, description,
min, max, variable, callback, std::map<std::string, T>(),
"", group));
102 template <
typename T>
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)
114 name, description,
min, max, variable, callback, enum_dict, enum_description, group));
117 template <
typename T>
119 const boost::function<
void(T value)> &callback,
120 const std::string &description, T min, T max,
121 const std::string &group)
125 name, description,
min, max, current_value, callback, std::map<std::string, T>(),
"", group));
129 template <
typename T>
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)
141 name, description,
min, max, current_value, callback, enum_dict, enum_description, group));
144 template <
typename ParamType>
147 return (a.name == b.name) && (a.value == b.value);
152 const dynamic_reconfigure::DoubleParameter &b)
154 return (a.name == b.name) &&
155 (std::fabs(a.value - b.value) < std::numeric_limits<double>::epsilon());
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();
167 has_changed = has_changed ||
168 !std::equal(config_msg.ints.begin(), config_msg.ints.end(),
170 confCompare<dynamic_reconfigure::IntParameter>);
171 has_changed = has_changed ||
172 !std::equal(config_msg.doubles.begin(), config_msg.doubles.end(),
174 confCompare<dynamic_reconfigure::DoubleParameter>);
175 has_changed = has_changed ||
176 !std::equal(config_msg.bools.begin(), config_msg.bools.end(),
178 confCompare<dynamic_reconfigure::BoolParameter>);
189 dynamic_reconfigure::Reconfigure::Response &rsp)
199 catch (std::exception &e)
201 ROS_WARN(
"Reconfigure pre update callback failed with exception %s: ", e.what());
205 ROS_WARN(
"Reconfigure pre update callback failed with unprintable exception.");
228 "Timeout waiting to update the registered variable data! Registered Variable data update failed!");
266 catch (std::exception &e)
268 ROS_WARN(
"Reconfigure post update callback failed with exception %s: ", e.what());
272 ROS_WARN(
"Reconfigure post update callback failed with unprintable exception.");
278 rsp.config = config_msg;
286 for (
unsigned int i = 0; i < config.ints.size(); ++i)
293 for (
unsigned int i = 0; i < config.doubles.size(); ++i)
297 ROS_ERROR_STREAM(
"Variable :" << config.doubles[i].name <<
" not registered");
300 for (
unsigned int i = 0; i < config.bools.size(); ++i)
304 ROS_ERROR_STREAM(
"Variable :" << config.bools[i].name <<
" not registered");
307 for (
unsigned int i = 0; i < config.strs.size(); ++i)
363 dynamic_reconfigure::ConfigDescription config_description;
365 std::map<std::string, dynamic_reconfigure::Group> groups;
372 auto &gp = groups[ri.
group_];
373 gp.parameters.push_back(p);
376 dynamic_reconfigure::IntParameter ip;
379 config_description.dflt.ints.push_back(ip);
381 config_description.max.ints.push_back(ip);
383 config_description.min.ints.push_back(ip);
391 auto &gp = groups[rd.
group_];
392 gp.parameters.push_back(p);
394 dynamic_reconfigure::DoubleParameter dp;
397 config_description.dflt.doubles.push_back(dp);
399 config_description.max.doubles.push_back(dp);
401 config_description.min.doubles.push_back(dp);
409 auto &gp = groups[rb.
group_];
410 gp.parameters.push_back(p);
413 dynamic_reconfigure::BoolParameter bp;
416 config_description.dflt.bools.push_back(bp);
418 config_description.max.bools.push_back(bp);
420 config_description.min.bools.push_back(bp);
427 auto &gp = groups[rs.
group_];
428 gp.parameters.push_back(p);
431 dynamic_reconfigure::StrParameter sp;
434 config_description.dflt.strs.push_back(sp);
436 config_description.max.strs.push_back(sp);
438 config_description.min.strs.push_back(sp);
441 auto default_group = groups[
"Default"];
442 default_group.name =
"Default";
443 config_description.groups.push_back(default_group);
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);
453 for (
auto &group : groups)
455 if (group.first ==
"Default")
459 group.second.name = group.first;
460 group.second.type =
"tab";
461 group.second.id = i++;
462 config_description.groups.push_back(group.second);
464 dynamic_reconfigure::GroupState gs;
465 gs.id = group.second.id;
466 gs.name = group.second.name;
468 config_description.dflt.groups.push_back(gs);
469 config_description.min.groups.push_back(gs);
470 config_description.max.groups.push_back(gs);
472 return config_description;
478 dynamic_reconfigure::Config c;
482 dynamic_reconfigure::IntParameter ip;
485 c.ints.push_back(ip);
490 dynamic_reconfigure::DoubleParameter dp;
493 c.doubles.push_back(dp);
498 dynamic_reconfigure::BoolParameter bp;
501 c.bools.push_back(bp);
506 dynamic_reconfigure::StrParameter bs;
509 c.strs.push_back(bs);
514 dynamic_reconfigure::GroupState gs;
518 c.groups.push_back(gs);
542 const std::string &description,
int min,
543 int max,
const std::string &group);
547 const std::string &description,
548 std::map<std::string, int> enum_dict,
549 const std::string &enum_description,
550 const std::string &group);
552 const boost::function<
void(
int value)> &callback,
553 const std::string &description,
int min,
554 int max,
const std::string &group);
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);
564 const std::string &description,
double min,
565 double max,
const std::string &group);
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);
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);
587 const std::string &description,
bool min,
588 bool max,
const std::string &group);
592 const std::string &description,
593 std::map<std::string, bool> enum_dict,
594 const std::string &enum_description,
595 const std::string &group);
597 const boost::function<
void(
bool value)> &callback,
598 const std::string &description,
bool min,
599 bool max,
const std::string &group);
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);
609 const std::string &description,
610 std::string min, std::string max,
611 const std::string &group);
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);
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);