dynamic_parameters.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2019, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #ifndef SWRI_ROSCPP_DYNAMIC_PARAMETERS_H_
31 #define SWRI_ROSCPP_DYNAMIC_PARAMETERS_H_
32 
33 #include <map>
34 #include <string>
35 #include <sstream>
36 
37 #include <boost/thread/mutex.hpp>
38 
39 #include <yaml-cpp/yaml.h>
40 
41 #include <ros/console.h>
42 #include <ros/node_handle.h>
43 
45 
46 #include <dynamic_reconfigure/Config.h>
47 #include <dynamic_reconfigure/ConfigDescription.h>
48 #include <dynamic_reconfigure/GroupState.h>
49 #include <dynamic_reconfigure/Reconfigure.h>
50 
51 namespace swri
52 {
53  struct DynamicValue
54  {
55  enum Type
56  {
57  Bool = 0,
58  Float = 1,
59  Double = 2,
60  Int = 3,
61  String = 4
62  };
63 
65  std::string name;
66  std::string description;
67  std::vector<std::pair<std::string, int> > enums;
68 
69  //pointer to the parameter to update on change
75 
76  // Defaults, maximum and minimum values for this parameter
77  union
78  {
79  double d;
80  bool b;
81  int i;
82  } Default;
83  union
84  {
85  double d;
86  int i;
87  } Min;
88  union
89  {
90  double d;
91  int i;
92  } Max;
93  std::string default_string;// to get around union issues with strings
94  };
95 
96  template <class T>
97  struct TypedParam
98  {
101 
102  inline
103  T operator* ()
104  {
105  return *data;
106  }
107 
108  T get()
109  {
110  mutex->lock();
111  T d = *data;
112  mutex->unlock();
113 
114  return d;
115  }
116  };
117 
123 
124 
126  {
132 
133  std::map<std::string, DynamicValue> values_;
134 
135  // stores the order that the parameters were added in
136  std::vector<std::string> ordered_params_;
137 
138  boost::function<void(DynamicParameters&)> on_change_;
139 
140 
142 
143  bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req,
144  dynamic_reconfigure::Reconfigure::Response &rsp)
145  {
146  ROS_DEBUG("Got configuration change request");
147 
148  boost::mutex::scoped_lock lock(*mutex_);
149 
150  // update the parameters
151  for (size_t i = 0; i < req.config.doubles.size(); i++)
152  {
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())
156  {
157  ROS_ERROR("Could not find parameter '%s'", param.name.c_str());
158  continue;
159  }
160 
161  if (iter->second.type != DynamicValue::Double && iter->second.type != DynamicValue::Float)
162  {
163  ROS_ERROR("Value '%s' was not a double type.", param.name.c_str());
164  continue;
165  }
166 
167  if (iter->second.type == DynamicValue::Double)
168  {
169  *iter->second.dbl = param.value;
170  }
171 
172  if (iter->second.type == DynamicValue::Float)
173  {
174  *iter->second.flt = (float)param.value;
175  }
176  }
177 
178  for (size_t i = 0; i < req.config.ints.size(); i++)
179  {
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())
183  {
184  ROS_ERROR("Could not find parameter '%s'", param.name.c_str());
185  continue;
186  }
187 
188  if (iter->second.type != DynamicValue::Int)
189  {
190  ROS_ERROR("Value '%s' was not a int type.", param.name.c_str());
191  continue;
192  }
193 
194  *iter->second.integer = param.value;
195  }
196 
197  for (size_t i = 0; i < req.config.bools.size(); i++)
198  {
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())
202  {
203  ROS_ERROR("Could not find parameter '%s'", param.name.c_str());
204  continue;
205  }
206 
207  if (iter->second.type != DynamicValue::Bool)
208  {
209  ROS_ERROR("Value '%s' was not a bool type.", param.name.c_str());
210  continue;
211  }
212 
213  *iter->second.boolean = param.value;
214  }
215 
216  for (size_t i = 0; i < req.config.strs.size(); i++)
217  {
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())
221  {
222  ROS_ERROR("Could not find parameter '%s'", param.name.c_str());
223  continue;
224  }
225 
226  if (iter->second.type != DynamicValue::String)
227  {
228  ROS_ERROR("Value '%s' was not a string type.", param.name.c_str());
229  continue;
230  }
231 
232  *iter->second.str = param.value;
233  }
234 
235  updateCurrent(rsp.config);
236 
237  if (on_change_)
238  {
239  on_change_(*this);
240  }
241 
242  return true;
243  }
244 
245  // Updates a config with the current parameter values
246  void updateCurrent(dynamic_reconfigure::Config& config)
247  {
248  for (std::map<std::string, DynamicValue>::iterator value = values_.begin(); value != values_.end(); value++)
249  {
250  if (value->second.type == DynamicValue::Double)
251  {
252  dynamic_reconfigure::DoubleParameter param;
253  param.name = value->first;
254  param.value = *value->second.dbl;
255  config.doubles.push_back(param);
256  }
257  else if (value->second.type == DynamicValue::Float)
258  {
259  dynamic_reconfigure::DoubleParameter param;
260  param.name = value->first;
261  param.value = *value->second.flt;
262  config.doubles.push_back(param);
263  }
264  else if (value->second.type == DynamicValue::Int)
265  {
266  dynamic_reconfigure::IntParameter param;
267  param.name = value->first;
268  param.value = *value->second.integer;
269  config.ints.push_back(param);
270  }
271  else if (value->second.type == DynamicValue::Bool)
272  {
273  dynamic_reconfigure::BoolParameter param;
274  param.name = value->first;
275  param.value = *value->second.boolean;
276  config.bools.push_back(param);
277  }
278  else if (value->second.type == DynamicValue::String)
279  {
280  dynamic_reconfigure::StrParameter param;
281  param.name = value->first;
282  param.value = *value->second.str;
283  config.strs.push_back(param);
284  }
285  }
286 
287  dynamic_reconfigure::GroupState gs;
288  gs.name = "Default";
289  gs.state = true;
290  gs.id = 0;
291  gs.parent = 0;
292  config.groups.push_back(gs);
293  update_pub_.publish(config);
294  }
295 
296  public:
297 
298  DynamicParameters() : mutex_(new boost::mutex)
299  {
300 
301  }
302 
303  // Sets up the node handle and publishers. Be sure to call this before finalize or any of the 'get*' calls.
305  {
306  boost::mutex::scoped_lock lock(*mutex_);
308 
309  descr_pub_ = nh_->advertise<dynamic_reconfigure::ConfigDescription>("parameter_descriptions", 1, true);
310  update_pub_ = nh_->advertise<dynamic_reconfigure::Config>("parameter_updates", 1, true);
311  }
312 
314  {
315  boost::mutex::scoped_lock lock(*mutex_);
317  snh_ = pnh;
318  descr_pub_ = nh_->advertise<dynamic_reconfigure::ConfigDescription>("parameter_descriptions", 1, true);
319  update_pub_ = nh_->advertise<dynamic_reconfigure::Config>("parameter_updates", 1, true);
320  }
321 
322  // Publishes the configuration parameters that have been added
323  void finalize(bool alphabetical_order = true)
324  {
325  boost::mutex::scoped_lock lock(*mutex_);
326 
327  // publish the configs as one group
328  dynamic_reconfigure::ConfigDescription rdesc;
329  dynamic_reconfigure::Group group;
330  group.name = "Default";
331  group.type = "";
332  group.id = 0;
333  group.parent = 0;
334 
335  dynamic_reconfigure::GroupState gs;
336  gs.name = "Default";
337  gs.state = true;
338  gs.id = 0;
339  gs.parent = 0;
340 
341  // sort by alphabetical if we want it
342  if (alphabetical_order)
343  {
344  ordered_params_.clear();
345 
346  for (std::map<std::string, DynamicValue>::iterator it = values_.begin(); it != values_.end(); it++ )
347  {
348  ordered_params_.push_back(it->first);
349  }
350  }
351  for (size_t i = 0; i < ordered_params_.size(); i++)
352  {
353  std::map<std::string, DynamicValue>::iterator param = values_.find(ordered_params_[i]);
354 
355  std::string type;
356  if (param->second.type == DynamicValue::Bool)
357  {
358  type = "bool";
359 
360  dynamic_reconfigure::BoolParameter desc;
361  desc.name = param->first;
362  desc.value = true;
363  rdesc.max.bools.push_back(desc);
364  desc.value = false;
365  rdesc.min.bools.push_back(desc);
366  desc.value = param->second.Default.b;
367  rdesc.dflt.bools.push_back(desc);
368  }
369  else if (param->second.type == DynamicValue::Float)
370  {
371  type = "double";
372 
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);
381  }
382  else if (param->second.type == DynamicValue::Double)
383  {
384  type = "double";
385 
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);
394  }
395  else if (param->second.type == DynamicValue::Int)
396  {
397  type = "int";
398 
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);
407  }
408  else if (param->second.type == DynamicValue::String)
409  {
410  type = "str";
411  dynamic_reconfigure::StrParameter desc;
412  desc.name = param->first;
413  desc.value = "";
414  rdesc.max.strs.push_back(desc);
415  desc.value = "";
416  rdesc.min.strs.push_back(desc);
417  desc.value = param->second.default_string;
418  rdesc.dflt.strs.push_back(desc);
419  }
420 
421  dynamic_reconfigure::ParamDescription desc;
422  desc.name = param->first;
423  desc.type = type;
424  desc.level = 0;
425  desc.description = param->second.description;
426 
427  // If this is an enum, let's make the edit method string
428  if (!param->second.enums.empty())
429  {
430  YAML::Emitter emitter;
431 
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;
438 
439  for (size_t j = 0; j < param->second.enums.size(); j++)
440  {
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;
451  }
452  emitter << YAML::EndSeq << YAML::EndMap;
453 
454  desc.edit_method = emitter.c_str();
455  }
456 
457  group.parameters.push_back(desc);
458  }
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);
463  descr_pub_.publish(rdesc);
464 
465  dynamic_reconfigure::Config config;
466  updateCurrent(config);
467 
468  set_service_ = nh_->advertiseService("set_parameters",
470 
471  ordered_params_.clear();// to save memory
472  }
473 
474  void addEnums(const std::string& param, const std::vector<std::pair<std::string, int> >& enums)
475  {
476  std::map<std::string, DynamicValue>::iterator iter = values_.find(param);
477  if (iter == values_.end())
478  {
479  ROS_ERROR("Tried to add enum to nonexistant param %s", param.c_str());
480  return;
481  }
482 
483  iter->second.enums.insert(iter->second.enums.end(), enums.begin(), enums.end());
484  }
485 
486  void setCallback(boost::function<void(DynamicParameters&)> fun)
487  {
488  on_change_ = fun;
489  }
490 
491  void update()
492  {
493  dynamic_reconfigure::Config config;
494  updateCurrent(config);
495  }
496 
497  //for use in the on change callback
498  double getDouble(const std::string& name)
499  {
500  std::map<std::string, DynamicValue>::iterator iter = values_.find(name);
501  if (iter == values_.end())
502  {
503  ROS_ERROR("Tried to get nonexistant param %s", name.c_str());
504  return 0.0;
505  }
506  if (iter->second.type != DynamicValue::Double)
507  {
508  ROS_ERROR("Tried to load parameter %s with the wrong type: double.", name.c_str());
509  return 0.0;
510  }
511 
512  return *iter->second.dbl;
513  }
514 
515  //for use in the on change callback
516  float getFloat(const std::string& name)
517  {
518  std::map<std::string, DynamicValue>::iterator iter = values_.find(name);
519  if (iter == values_.end())
520  {
521  ROS_ERROR("Tried to get nonexistant param %s", name.c_str());
522  return 0.0f;
523  }
524  if (iter->second.type != DynamicValue::Float)
525  {
526  ROS_ERROR("Tried to load parameter %s with the wrong type: float.", name.c_str());
527  return 0.0f;
528  }
529 
530  return *iter->second.flt;
531  }
532 
533  int getInt(const std::string& name)
534  {
535  std::map<std::string, DynamicValue>::iterator iter = values_.find(name);
536  if (iter == values_.end())
537  {
538  ROS_ERROR("Tried to get nonexistant param %s", name.c_str());
539  return 0.0f;
540  }
541  if (iter->second.type != DynamicValue::Int)
542  {
543  ROS_ERROR("Tried to load parameter %s with the wrong type: int.", name.c_str());
544  return 0.0f;
545  }
546 
547  return *iter->second.integer;
548  }
549 
550  //for use in the on change callback
551  bool getBool(const std::string& name)
552  {
553  std::map<std::string, DynamicValue>::iterator iter = values_.find(name);
554  if (iter == values_.end())
555  {
556  ROS_ERROR("Tried to get nonexistant param %s", name.c_str());
557  return false;
558  }
559  if (iter->second.type != DynamicValue::Bool)
560  {
561  ROS_ERROR("Tried to load parameter %s with the wrong type: bool.", name.c_str());
562  return false;
563  }
564 
565  return *iter->second.boolean;
566  }
567 
568  //for use in the on change callback
569  std::string getString(const std::string& name)
570  {
571  std::map<std::string, DynamicValue>::iterator iter = values_.find(name);
572  if (iter == values_.end())
573  {
574  ROS_ERROR("Tried to get nonexistant param %s", name.c_str());
575  return "";
576  }
577  if (iter->second.type != DynamicValue::String)
578  {
579  ROS_ERROR("Tried to load parameter %s with the wrong type: string.", name.c_str());
580  return "";
581  }
582 
583  return *iter->second.str;
584  }
585 
586 
587  inline
588  boost::mutex& mutex()
589  {
590  return *mutex_;
591  }
592 
593  inline
594  boost::mutex::scoped_lock lock_guard()
595  {
596  return boost::mutex::scoped_lock(*mutex_);
597  }
598 
599  // for use with on change callbacks
600  inline
601  void get(const std::string &name,
602  float &variable,
603  const float default_value,
604  const std::string description = "None.",
605  const float min = -100,
606  const float max = 100)
607  {
608  DynamicValue value;
609  value.type = DynamicValue::Float;
610  value.description = description;
611  value.Min.d = min;
612  value.Max.d = max;
613  value.Default.d = default_value;
614  value.flt = boost::shared_ptr<float>(new float);
615  values_[name] = value;
616  ordered_params_.push_back(name);
617 
618  if (snh_)
619  {
620  snh_.ranged_param(name, *value.flt, default_value, description, min, max, true);
621  }
622  else
623  {
624  nh_->param(name, *value.flt, default_value);
625  }
626  variable = *value.flt;
627  ROS_INFO("Read dynamic parameter %s = %f", name.c_str(), variable);
628  }
629 
630  inline
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)
637  {
638  DynamicValue value;
639  value.type = DynamicValue::Float;
640  value.description = description;
641  value.Min.d = min;
642  value.Max.d = max;
643  value.Default.d = default_value;
644  value.flt = boost::shared_ptr<float>(new float);
645  values_[name] = value;
646  ordered_params_.push_back(name);
647 
648  variable.data = value.flt;
649  variable.mutex = mutex_;
650 
651  if (snh_)
652  {
653  snh_.ranged_param(name, *value.flt, default_value, description, min, max, true);
654  }
655  else
656  {
657  nh_->param(name, *value.flt, default_value);
658  }
659  ROS_INFO("Read dynamic parameter %s = %f", name.c_str(), *variable);
660  }
661 
662  // for use with on change callbacks
663  inline
664  void get(const std::string &name,
665  double &variable,
666  const double default_value,
667  const std::string description = "None.",
668  const double min = -100,
669  const double max = 100)
670  {
671  DynamicValue value;
672  value.type = DynamicValue::Double;
673  value.description = description;
674  value.Min.d = min;
675  value.Max.d = max;
676  value.Default.d = default_value;
677  value.dbl = boost::shared_ptr<double>(new double);
678  values_[name] = value;
679  ordered_params_.push_back(name);
680 
681  if (snh_)
682  {
683  snh_.ranged_param(name, *value.dbl, default_value, description, min, max, true);
684  }
685  else
686  {
687  nh_->param(name, *value.dbl, default_value);
688  }
689  variable = *value.dbl;
690  ROS_INFO("Read dynamic parameter %s = %lf", name.c_str(), variable);
691  }
692 
693  inline
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)
700  {
701  DynamicValue value;
702  value.type = DynamicValue::Double;
703  value.description = description;
704  value.Min.d = min;
705  value.Max.d = max;
706  value.Default.d = default_value;
707  value.dbl = boost::shared_ptr<double>(new double);
708  values_[name] = value;
709  ordered_params_.push_back(name);
710 
711  variable.data = value.dbl;
712  variable.mutex = mutex_;
713 
714  if (snh_)
715  {
716  snh_.ranged_param(name, *value.dbl, default_value, description, min, max, true);
717  }
718  else
719  {
720  nh_->param(name, *value.dbl, default_value);
721  }
722  ROS_INFO("Read dynamic parameter %s = %lf", name.c_str(), *variable);
723  }
724 
725  inline
726  void get(const std::string &name,
727  int &variable,
728  const int default_value,
729  const std::string description = "None.",
730  const int min = -100,
731  const int max = 100)
732  {
733  DynamicValue value;
734  value.type = DynamicValue::Int;
735  value.description = description;
736  value.Min.i = min;
737  value.Max.i = max;
738  value.Default.i = default_value;
739  value.integer = boost::shared_ptr<int>(new int);
740  values_[name] = value;
741  ordered_params_.push_back(name);
742 
743  if (snh_)
744  {
745  snh_.ranged_param(name, *value.integer, default_value, description, min, max, true);
746  }
747  else
748  {
749  nh_->param(name, *value.integer, default_value);
750  }
751  variable = *value.integer;
752  ROS_INFO("Read dynamic parameter %s = %i", name.c_str(), variable);
753  }
754 
755  inline
756  void get(const std::string &name,
757  IntParam &variable,
758  const int default_value,
759  const std::string description = "None.",
760  const int min = -100,
761  const int max = 100)
762  {
763  DynamicValue value;
764  value.type = DynamicValue::Int;
765  value.description = description;
766  value.Min.i = min;
767  value.Max.i = max;
768  value.Default.i = default_value;
769  value.integer = boost::shared_ptr<int>(new int);
770  values_[name] = value;
771  ordered_params_.push_back(name);
772 
773  variable.data = value.integer;
774  variable.mutex = mutex_;
775 
776  if (snh_)
777  {
778  snh_.ranged_param(name, *value.integer, default_value, description, min, max, true);
779  }
780  else
781  {
782  nh_->param(name, *value.integer, default_value);
783  }
784  ROS_INFO("Read dynamic parameter %s = %i", name.c_str(), *variable);
785  }
786 
787  // for use with on change callbacks
788  inline
789  void get(const std::string &name,
790  bool &variable,
791  const bool default_value,
792  const std::string description = "None.")
793  {
794  DynamicValue value;
795  value.type = DynamicValue::Bool;
796  value.description = description;
797  value.Default.b = default_value;
798  value.boolean = boost::shared_ptr<bool>(new bool);
799  values_[name] = value;
800  ordered_params_.push_back(name);
801 
802  if (snh_)
803  {
804  snh_.param(name, *value.boolean, default_value, description, true);
805  }
806  else
807  {
808  nh_->param(name, *value.boolean, default_value);
809  }
810  variable = *value.boolean;
811  ROS_INFO("Read dynamic parameter %s = %s", name.c_str(), variable ? "true" : "false");
812  }
813 
814  inline
815  void get(const std::string &name,
816  BoolParam &variable,
817  const bool default_value,
818  const std::string description = "None.")
819  {
820  DynamicValue value;
821  value.type = DynamicValue::Bool;
822  value.description = description;
823  value.Default.b = default_value;
824  value.boolean = boost::shared_ptr<bool>(new bool);
825  values_[name] = value;
826  ordered_params_.push_back(name);
827 
828  variable.data = value.boolean;
829  variable.mutex = mutex_;
830 
831  if (snh_)
832  {
833  snh_.param(name, *value.boolean, default_value, description, true);
834  }
835  else
836  {
837  nh_->param(name, *value.boolean, default_value);
838  }
839  ROS_INFO("Read dynamic parameter %s = %s", name.c_str(), *variable ? "true" : "false");
840  }
841 
842  // for use with on change callbacks
843  inline
844  void get(const std::string &name,
845  std::string &variable,
846  const std::string default_value,
847  const std::string description = "None.")
848  {
849  DynamicValue value;
850  value.type = DynamicValue::String;
851  value.description = description;
852  value.default_string = default_value;
853  value.str = boost::shared_ptr<std::string>(new std::string());
854  values_[name] = value;
855  ordered_params_.push_back(name);
856 
857  if (snh_)
858  {
859  snh_.param(name, *value.str, default_value, description, true);
860  }
861  else
862  {
863  nh_->param(name, *value.str, default_value);
864  }
865  variable = *value.str;
866  ROS_INFO("Read dynamic parameter %s = %s", name.c_str(), variable.c_str());
867  }
868 
869  inline
870  void get(const std::string &name,
871  StringParam &variable,
872  const std::string default_value,
873  const std::string description = "None.")
874  {
875  DynamicValue value;
876  value.type = DynamicValue::String;
877  value.description = description;
878  value.default_string = default_value;
879  value.str = boost::shared_ptr<std::string>(new std::string());
880  values_[name] = value;
881  ordered_params_.push_back(name);
882 
883  variable.data = value.str;
884  variable.mutex = mutex_;
885 
886  if (snh_)
887  {
888  snh_.param(name, *value.str, default_value, description, true);
889  }
890  else
891  {
892  nh_->param(name, *value.str, default_value);
893  }
894  ROS_INFO("Read dynamic parameter %s = %s", name.c_str(), (*variable).c_str());
895  }
896  };
897 } // namespace swri_param
898 #endif // SWRI_ROSCPP_DYNAMIC_PARAMETERS_H_
ros::NodeHandle getDynamicParameterNodeHandle() const
Definition: node_handle.h:81
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
def default_value(type_)
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)
Definition: node_handle.h:294
void publish(const boost::shared_ptr< M > &message) const
void setCallback(boost::function< void(DynamicParameters &)> fun)
#define ROS_INFO(...)
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)
Definition: node_handle.h:1159
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
union swri::DynamicValue::@0 Default
int min(int a, int b)
bool param(const std::string &name, double &variable, const double default_value, const std::string description, const bool dynamic=false)
Definition: node_handle.h:262
TypedParam< float > FloatParam
std::string default_string
int getInt(const std::string &name)
ros::ServiceServer set_service_
union swri::DynamicValue::@2 Max
void addEnums(const std::string &param, const std::vector< std::pair< std::string, int > > &enums)
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


swri_roscpp
Author(s):
autogenerated on Sat Jan 21 2023 03:13:16