30 #ifndef SWRI_ROSCPP_DYNAMIC_PARAMETERS_H_
31 #define SWRI_ROSCPP_DYNAMIC_PARAMETERS_H_
37 #include <boost/thread/mutex.hpp>
39 #include <yaml-cpp/yaml.h>
46 #include <dynamic_reconfigure/Config.h>
47 #include <dynamic_reconfigure/ConfigDescription.h>
48 #include <dynamic_reconfigure/GroupState.h>
49 #include <dynamic_reconfigure/Reconfigure.h>
67 std::vector<std::pair<std::string, int> >
enums;
144 dynamic_reconfigure::Reconfigure::Response &rsp)
146 ROS_DEBUG(
"Got configuration change request");
148 boost::mutex::scoped_lock lock(*
mutex_);
151 for (
size_t i = 0; i < req.config.doubles.size(); i++)
153 dynamic_reconfigure::DoubleParameter
param = req.config.doubles[i];
154 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
param.name);
163 ROS_ERROR(
"Value '%s' was not a double type.",
param.name.c_str());
169 *iter->second.dbl =
param.value;
174 *iter->second.flt = (float)
param.value;
178 for (
size_t i = 0; i < req.config.ints.size(); i++)
180 dynamic_reconfigure::IntParameter
param = req.config.ints[i];
181 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
param.name);
194 *iter->second.integer =
param.value;
197 for (
size_t i = 0; i < req.config.bools.size(); i++)
199 dynamic_reconfigure::BoolParameter
param = req.config.bools[i];
200 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
param.name);
213 *iter->second.boolean =
param.value;
216 for (
size_t i = 0; i < req.config.strs.size(); i++)
218 dynamic_reconfigure::StrParameter
param = req.config.strs[i];
219 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
param.name);
228 ROS_ERROR(
"Value '%s' was not a string type.",
param.name.c_str());
232 *iter->second.str =
param.value;
248 for (std::map<std::string, DynamicValue>::iterator value =
values_.begin(); value !=
values_.end(); value++)
252 dynamic_reconfigure::DoubleParameter
param;
253 param.name = value->first;
254 param.value = *value->second.dbl;
255 config.doubles.push_back(
param);
259 dynamic_reconfigure::DoubleParameter
param;
260 param.name = value->first;
261 param.value = *value->second.flt;
262 config.doubles.push_back(
param);
266 dynamic_reconfigure::IntParameter
param;
267 param.name = value->first;
268 param.value = *value->second.integer;
269 config.ints.push_back(
param);
273 dynamic_reconfigure::BoolParameter
param;
274 param.name = value->first;
275 param.value = *value->second.boolean;
276 config.bools.push_back(
param);
280 dynamic_reconfigure::StrParameter
param;
281 param.name = value->first;
282 param.value = *value->second.str;
283 config.strs.push_back(
param);
287 dynamic_reconfigure::GroupState gs;
292 config.groups.push_back(gs);
306 boost::mutex::scoped_lock lock(*
mutex_);
309 descr_pub_ =
nh_->advertise<dynamic_reconfigure::ConfigDescription>(
"parameter_descriptions", 1,
true);
310 update_pub_ =
nh_->advertise<dynamic_reconfigure::Config>(
"parameter_updates", 1,
true);
315 boost::mutex::scoped_lock lock(*
mutex_);
318 descr_pub_ =
nh_->advertise<dynamic_reconfigure::ConfigDescription>(
"parameter_descriptions", 1,
true);
319 update_pub_ =
nh_->advertise<dynamic_reconfigure::Config>(
"parameter_updates", 1,
true);
325 boost::mutex::scoped_lock lock(*
mutex_);
328 dynamic_reconfigure::ConfigDescription rdesc;
329 dynamic_reconfigure::Group group;
330 group.name =
"Default";
335 dynamic_reconfigure::GroupState gs;
342 if (alphabetical_order)
346 for (std::map<std::string, DynamicValue>::iterator it =
values_.begin(); it !=
values_.end(); it++ )
360 dynamic_reconfigure::BoolParameter desc;
361 desc.name =
param->first;
363 rdesc.max.bools.push_back(desc);
365 rdesc.min.bools.push_back(desc);
366 desc.value =
param->second.Default.b;
367 rdesc.dflt.bools.push_back(desc);
373 dynamic_reconfigure::DoubleParameter desc;
374 desc.name =
param->first;
375 desc.value =
param->second.Max.d;
376 rdesc.max.doubles.push_back(desc);
377 desc.value =
param->second.Min.d;
378 rdesc.min.doubles.push_back(desc);
379 desc.value =
param->second.Default.d;
380 rdesc.dflt.doubles.push_back(desc);
386 dynamic_reconfigure::DoubleParameter desc;
387 desc.name =
param->first;
388 desc.value =
param->second.Max.d;
389 rdesc.max.doubles.push_back(desc);
390 desc.value =
param->second.Min.d;
391 rdesc.min.doubles.push_back(desc);
392 desc.value =
param->second.Default.d;
393 rdesc.dflt.doubles.push_back(desc);
399 dynamic_reconfigure::IntParameter desc;
400 desc.name =
param->first;
401 desc.value =
param->second.Max.i;
402 rdesc.max.ints.push_back(desc);
403 desc.value =
param->second.Min.i;
404 rdesc.min.ints.push_back(desc);
405 desc.value =
param->second.Default.i;
406 rdesc.dflt.ints.push_back(desc);
411 dynamic_reconfigure::StrParameter desc;
412 desc.name =
param->first;
414 rdesc.max.strs.push_back(desc);
416 rdesc.min.strs.push_back(desc);
417 desc.value =
param->second.default_string;
418 rdesc.dflt.strs.push_back(desc);
421 dynamic_reconfigure::ParamDescription desc;
422 desc.name =
param->first;
425 desc.description =
param->second.description;
428 if (!
param->second.enums.empty())
430 YAML::Emitter emitter;
432 emitter << YAML::Flow << YAML::SingleQuoted;
433 emitter << YAML::BeginMap;
434 emitter << YAML::Key <<
"enum_description";
435 emitter << YAML::Value << desc.description;
436 emitter << YAML::Key <<
"enum";
437 emitter << YAML::Value << YAML::BeginSeq;
439 for (
size_t j = 0; j <
param->second.enums.size(); j++)
441 emitter << YAML::BeginMap;
442 emitter << YAML::Key <<
"srcline" << YAML::Value << 0;
443 emitter << YAML::Key <<
"description" << YAML::Value <<
"Unknown";
444 emitter << YAML::Key <<
"srcfile" << YAML::Value <<
"dynamic_parameters.h";
445 emitter << YAML::Key <<
"cconsttype" << YAML::Value <<
"const int";
446 emitter << YAML::Key <<
"value" << YAML::Value <<
param->second.enums[j].second;
447 emitter << YAML::Key <<
"ctype" << YAML::Value <<
"int";
448 emitter << YAML::Key <<
"type" << YAML::Value <<
"int";
449 emitter << YAML::Key <<
"name" << YAML::Value <<
param->second.enums[j].first;
450 emitter << YAML::EndMap;
452 emitter << YAML::EndSeq << YAML::EndMap;
454 desc.edit_method = emitter.c_str();
457 group.parameters.push_back(desc);
459 rdesc.max.groups.push_back(gs);
460 rdesc.min.groups.push_back(gs);
461 rdesc.dflt.groups.push_back(gs);
462 rdesc.groups.push_back(group);
465 dynamic_reconfigure::Config config;
474 void addEnums(
const std::string&
param,
const std::vector<std::pair<std::string, int> >& enums)
476 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
param);
479 ROS_ERROR(
"Tried to add enum to nonexistant param %s",
param.c_str());
483 iter->second.enums.insert(iter->second.enums.end(), enums.begin(), enums.end());
493 dynamic_reconfigure::Config config;
500 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
name);
503 ROS_ERROR(
"Tried to get nonexistant param %s",
name.c_str());
508 ROS_ERROR(
"Tried to load parameter %s with the wrong type: double.",
name.c_str());
512 return *iter->second.dbl;
518 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
name);
521 ROS_ERROR(
"Tried to get nonexistant param %s",
name.c_str());
526 ROS_ERROR(
"Tried to load parameter %s with the wrong type: float.",
name.c_str());
530 return *iter->second.flt;
535 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
name);
538 ROS_ERROR(
"Tried to get nonexistant param %s",
name.c_str());
543 ROS_ERROR(
"Tried to load parameter %s with the wrong type: int.",
name.c_str());
547 return *iter->second.integer;
553 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
name);
556 ROS_ERROR(
"Tried to get nonexistant param %s",
name.c_str());
561 ROS_ERROR(
"Tried to load parameter %s with the wrong type: bool.",
name.c_str());
565 return *iter->second.boolean;
571 std::map<std::string, DynamicValue>::iterator iter =
values_.find(
name);
574 ROS_ERROR(
"Tried to get nonexistant param %s",
name.c_str());
579 ROS_ERROR(
"Tried to load parameter %s with the wrong type: string.",
name.c_str());
583 return *iter->second.str;
596 return boost::mutex::scoped_lock(*
mutex_);
603 const float default_value,
604 const std::string description =
"None.",
605 const float min = -100,
606 const float max = 100)
626 variable = *value.
flt;
627 ROS_INFO(
"Read dynamic parameter %s = %f",
name.c_str(), variable);
633 const float default_value,
634 const std::string description =
"None.",
635 const float min = -100,
636 const float max = 100)
659 ROS_INFO(
"Read dynamic parameter %s = %f",
name.c_str(), *variable);
666 const double default_value,
667 const std::string description =
"None.",
668 const double min = -100,
669 const double max = 100)
689 variable = *value.
dbl;
690 ROS_INFO(
"Read dynamic parameter %s = %lf",
name.c_str(), variable);
696 const double default_value,
697 const std::string description =
"None.",
698 const double min = -100,
699 const double max = 100)
722 ROS_INFO(
"Read dynamic parameter %s = %lf",
name.c_str(), *variable);
728 const int default_value,
729 const std::string description =
"None.",
730 const int min = -100,
752 ROS_INFO(
"Read dynamic parameter %s = %i",
name.c_str(), variable);
758 const int default_value,
759 const std::string description =
"None.",
760 const int min = -100,
784 ROS_INFO(
"Read dynamic parameter %s = %i",
name.c_str(), *variable);
791 const bool default_value,
792 const std::string description =
"None.")
811 ROS_INFO(
"Read dynamic parameter %s = %s",
name.c_str(), variable ?
"true" :
"false");
817 const bool default_value,
818 const std::string description =
"None.")
839 ROS_INFO(
"Read dynamic parameter %s = %s",
name.c_str(), *variable ?
"true" :
"false");
845 std::string &variable,
846 const std::string default_value,
847 const std::string description =
"None.")
865 variable = *value.
str;
866 ROS_INFO(
"Read dynamic parameter %s = %s",
name.c_str(), variable.c_str());
872 const std::string default_value,
873 const std::string description =
"None.")
894 ROS_INFO(
"Read dynamic parameter %s = %s",
name.c_str(), (*variable).c_str());
898 #endif // SWRI_ROSCPP_DYNAMIC_PARAMETERS_H_