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);
155 if (iter == values_.end())
157 ROS_ERROR(
"Could not find parameter '%s'", param.name.c_str());
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);
182 if (iter == values_.end())
184 ROS_ERROR(
"Could not find parameter '%s'", param.name.c_str());
190 ROS_ERROR(
"Value '%s' was not a int type.", param.name.c_str());
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);
201 if (iter == values_.end())
203 ROS_ERROR(
"Could not find parameter '%s'", param.name.c_str());
209 ROS_ERROR(
"Value '%s' was not a bool type.", param.name.c_str());
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);
220 if (iter == values_.end())
222 ROS_ERROR(
"Could not find parameter '%s'", param.name.c_str());
228 ROS_ERROR(
"Value '%s' was not a string type.", param.name.c_str());
232 *iter->second.str = param.value;
235 updateCurrent(rsp.config);
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)
344 ordered_params_.clear();
346 for (std::map<std::string, DynamicValue>::iterator it = values_.begin(); it != values_.end(); it++ )
348 ordered_params_.push_back(it->first);
351 for (
size_t i = 0;
i < ordered_params_.size();
i++)
353 std::map<std::string, DynamicValue>::iterator
param = values_.find(ordered_params_[
i]);
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;
466 updateCurrent(config);
468 set_service_ = nh_->advertiseService(
"set_parameters",
471 ordered_params_.clear();
476 std::map<std::string, DynamicValue>::iterator iter = values_.find(param);
477 if (iter == values_.end())
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;
494 updateCurrent(config);
500 std::map<std::string, DynamicValue>::iterator iter = values_.find(name);
501 if (iter == values_.end())
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);
519 if (iter == values_.end())
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);
536 if (iter == values_.end())
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);
554 if (iter == values_.end())
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);
572 if (iter == values_.end())
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_);
601 void get(
const std::string &
name,
605 const float min = -100,
606 const float max = 100)
615 values_[
name] = value;
616 ordered_params_.push_back(name);
620 snh_.
ranged_param(name, *value.
flt, default_value, description, min, max,
true);
624 nh_->param(name, *value.
flt, default_value);
626 variable = *value.
flt;
627 ROS_INFO(
"Read dynamic parameter %s = %f", name.c_str(), variable);
631 void get(
const std::string &
name,
632 FloatParam &variable,
633 const float default_value,
634 const std::string description =
"None.",
635 const float min = -100,
636 const float max = 100)
645 values_[
name] = value;
646 ordered_params_.push_back(name);
648 variable.data = value.
flt;
649 variable.mutex = mutex_;
653 snh_.
ranged_param(name, *value.
flt, default_value, description, min, max,
true);
657 nh_->param(name, *value.
flt, default_value);
659 ROS_INFO(
"Read dynamic parameter %s = %f", name.c_str(), *variable);
664 void get(
const std::string &
name,
666 const double default_value,
667 const std::string description =
"None.",
668 const double min = -100,
669 const double max = 100)
678 values_[
name] = value;
679 ordered_params_.push_back(name);
683 snh_.
ranged_param(name, *value.
dbl, default_value, description, min, max,
true);
687 nh_->param(name, *value.
dbl, default_value);
689 variable = *value.
dbl;
690 ROS_INFO(
"Read dynamic parameter %s = %lf", name.c_str(), variable);
694 void get(
const std::string &
name,
695 DoubleParam &variable,
696 const double default_value,
697 const std::string description =
"None.",
698 const double min = -100,
699 const double max = 100)
708 values_[
name] = value;
709 ordered_params_.push_back(name);
711 variable.data = value.
dbl;
712 variable.mutex = mutex_;
716 snh_.
ranged_param(name, *value.
dbl, default_value, description, min, max,
true);
720 nh_->param(name, *value.
dbl, default_value);
722 ROS_INFO(
"Read dynamic parameter %s = %lf", name.c_str(), *variable);
726 void get(
const std::string &
name,
728 const int default_value,
729 const std::string description =
"None.",
730 const int min = -100,
740 values_[
name] = value;
741 ordered_params_.push_back(name);
749 nh_->param(name, *value.
integer, default_value);
752 ROS_INFO(
"Read dynamic parameter %s = %i", name.c_str(), variable);
756 void get(
const std::string &
name,
758 const int default_value,
759 const std::string description =
"None.",
760 const int min = -100,
770 values_[
name] = value;
771 ordered_params_.push_back(name);
774 variable.mutex = mutex_;
782 nh_->param(name, *value.
integer, default_value);
784 ROS_INFO(
"Read dynamic parameter %s = %i", name.c_str(), *variable);
789 void get(
const std::string &
name,
791 const bool default_value,
792 const std::string description =
"None.")
799 values_[
name] = value;
800 ordered_params_.push_back(name);
804 snh_.
param(name, *value.
boolean, default_value, description,
true);
808 nh_->param(name, *value.
boolean, default_value);
811 ROS_INFO(
"Read dynamic parameter %s = %s", name.c_str(), variable ?
"true" :
"false");
815 void get(
const std::string &
name,
817 const bool default_value,
818 const std::string description =
"None.")
825 values_[
name] = value;
826 ordered_params_.push_back(name);
829 variable.mutex = mutex_;
833 snh_.
param(name, *value.
boolean, default_value, description,
true);
837 nh_->param(name, *value.
boolean, default_value);
839 ROS_INFO(
"Read dynamic parameter %s = %s", name.c_str(), *variable ?
"true" :
"false");
844 void get(
const std::string &
name,
845 std::string &variable,
846 const std::string default_value,
847 const std::string description =
"None.")
854 values_[
name] = value;
855 ordered_params_.push_back(name);
859 snh_.
param(name, *value.
str, default_value, description,
true);
863 nh_->param(name, *value.
str, default_value);
865 variable = *value.
str;
866 ROS_INFO(
"Read dynamic parameter %s = %s", name.c_str(), variable.c_str());
870 void get(
const std::string &
name,
871 StringParam &variable,
872 const std::string default_value,
873 const std::string description =
"None.")
880 values_[
name] = value;
881 ordered_params_.push_back(name);
883 variable.data = value.
str;
884 variable.mutex = mutex_;
888 snh_.
param(name, *value.
str, default_value, description,
true);
892 nh_->param(name, *value.
str, default_value);
894 ROS_INFO(
"Read dynamic parameter %s = %s", name.c_str(), (*variable).c_str());
898 #endif // SWRI_ROSCPP_DYNAMIC_PARAMETERS_H_ ros::NodeHandle getDynamicParameterNodeHandle() const
std::vector< std::string > ordered_params_
void finalize(bool alphabetical_order=true)
boost::shared_ptr< boost::mutex > mutex
void initialize(ros::NodeHandle &pnh)
void updateCurrent(dynamic_reconfigure::Config &config)
float getFloat(const std::string &name)
boost::shared_ptr< std::string > str
std::string getString(const std::string &name)
bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req, dynamic_reconfigure::Reconfigure::Response &rsp)
std::map< std::string, DynamicValue > values_
bool getBool(const std::string &name)
boost::shared_ptr< double > dbl
TypedParam< bool > BoolParam
union swri::DynamicValue::@1 Min
double getDouble(const std::string &name)
boost::mutex::scoped_lock lock_guard()
bool ranged_param(const std::string &name, double &variable, const double default_value, const std::string description, const double min_value=0.0, const double max_value=0.0, const bool dynamic=false)
void publish(const boost::shared_ptr< M > &message) const
void setCallback(boost::function< void(DynamicParameters &)> fun)
boost::shared_ptr< bool > boolean
boost::shared_ptr< boost::mutex > mutex_
void param(swri::NodeHandle &nh, const std::string name, std::string &value, const std::string def, const std::string description)
boost::shared_ptr< float > flt
boost::shared_ptr< int > integer
std::vector< std::pair< std::string, int > > enums
boost::shared_ptr< ros::NodeHandle > nh_
TypedParam< double > DoubleParam
TypedParam< int > IntParam
void initialize(swri::NodeHandle &pnh)
boost::function< void(DynamicParameters &)> on_change_
TypedParam< std::string > StringParam
boost::shared_ptr< T > data
ros::Publisher update_pub_
union swri::DynamicValue::@0 Default
bool param(const std::string &name, double &variable, const double default_value, const std::string description, const bool dynamic=false)
TypedParam< float > FloatParam
std::string default_string
int getInt(const std::string &name)
ros::ServiceServer set_service_
union swri::DynamicValue::@2 Max
ros::Publisher descr_pub_
void addEnums(const std::string ¶m, const std::vector< std::pair< std::string, int > > &enums)