registered_param.h
Go to the documentation of this file.
1 
30 #ifndef REGISTERED_PARAM_H
31 #define REGISTERED_PARAM_H
32 
33 #include <string>
34 #include <map>
35 #include <sstream>
36 #include <type_traits>
37 #include <boost/function.hpp>
38 #include <dynamic_reconfigure/ParamDescription.h>
39 namespace ddynamic_reconfigure
40 {
41 template <typename T>
43 {
44 public:
45  RegisteredParam(const std::string &name, const std::string &description, T min_value,
46  T max_value, std::map<std::string, T> enum_dictionary = {},
47  const std::string &enum_description = "", const std::string &group = "")
48  : name_(name)
49  , description_(description)
50  , min_value_(min_value)
51  , max_value_(max_value)
52  , enum_dictionary_(enum_dictionary)
53  , enum_description_(enum_description)
54  , group_(group)
55  {
56  }
57 
58  virtual ~RegisteredParam()
59  {
60  }
61 
62  virtual T getCurrentValue() const = 0;
63  virtual void updateValue(T new_value) = 0;
64 
65  std::string getTypeName() const
66  {
67  if (std::is_same<T, int>::value)
68  {
69  return "int";
70  }
71  else if (std::is_same<T, double>::value)
72  {
73  return "double";
74  }
75  else if (std::is_same<T, bool>::value)
76  {
77  return "bool";
78  }
79  else if (std::is_same<T, std::string>::value)
80  {
81  return "str";
82  }
83  throw std::runtime_error("Unexpected type for param " + name_);
84  }
85 
86  std::string getValueString(T value) const
87  {
88  std::stringstream ss;
89  ss << value;
90 
91  if (std::is_same<T, std::string>::value)
92  {
93  return "'" + ss.str() + "'";
94  }
95  return ss.str();
96  }
97 
98  virtual dynamic_reconfigure::ParamDescription getParamDescription() const
99  {
100  dynamic_reconfigure::ParamDescription p;
101  p.name = name_;
102  p.description = description_;
103  p.level = 0;
104  p.type = getTypeName();
105  if (!enum_dictionary_.empty())
106  {
107  p.edit_method = getEditMethod();
108  }
109  return p;
110  }
111 
112  std::string getEditMethod() const
113  {
114  // Based on https://github.com/awesomebytes/ddynamic_reconfigure's implementation
115  std::stringstream ret;
116  ret << "{";
117  {
118  ret << "'enum_description': '" << enum_description_ << "', ";
119  ret << "'enum': [";
120  {
121  auto it = enum_dictionary_.cbegin();
122  ret << makeConst(it->first, it->second, "");
123  for (it++; it != enum_dictionary_.cend(); it++)
124  {
125  ret << ", " << makeConst(it->first, it->second, "");
126  };
127  }
128  ret << "]";
129  }
130  ret << "}";
131  return ret.str();
132  }
133 
134  std::string makeConst(const std::string &name, T value, const std::string &desc) const
135  {
136  std::stringstream ret;
137  ret << "{";
138  {
139  ret << "'srcline': 0, "; // the sole reason this is here is because dynamic placed
140  // it in its enum JSON.
141  ret << "'description': '" << desc << "', ";
142  ret << "'srcfile': '/does/this/really/matter.cfg', "; // the answer is no. This is
143  // useless.
144  ret << "'cconsttype': 'const " << getTypeName() << "', ";
145  ret << "'value': " << getValueString(value) << ", ";
146  ret << "'ctype': '" << getTypeName() << "', ";
147  ret << "'type': '" << getTypeName() << "', ";
148  ret << "'name': '" << name << "'";
149  }
150  ret << "}";
151  return ret.str();
152  }
153 
154  const std::string name_;
155  const std::string description_;
156  const T min_value_;
157  const T max_value_;
158  const std::map<std::string, T> enum_dictionary_;
159  const std::string enum_description_;
160  const std::string group_;
161 };
162 
163 
164 template <typename T>
166 {
167 public:
168  PointerRegisteredParam(const std::string &name, const std::string &description,
169  T min_value, T max_value, T *variable,
170  boost::function<void(T value)> callback = {},
171  std::map<std::string, T> enum_dictionary = {},
172  const std::string &enum_description = "", const std::string &group = "")
173  : RegisteredParam<T>(name, description, min_value, max_value, enum_dictionary,
174  enum_description, group)
175  , variable_(variable)
176  , callback_(callback)
177  {
178  }
179 
180  T getCurrentValue() const override
181  {
182  return *variable_;
183  }
184  void updateValue(T new_value) override
185  {
186  *variable_ = new_value;
187  if (!callback_.empty())
188  callback_(new_value);
189  }
190 
191 protected:
193  boost::function<void(T value)> callback_;
194 };
195 
196 template <typename T>
198 {
199 public:
200  CallbackRegisteredParam(const std::string &name, const std::string &description, T min_value,
201  T max_value, T current_value, boost::function<void(T value)> callback,
202  std::map<std::string, T> enum_dictionary = {},
203  const std::string &enum_description = "",
204  const std::string &group = "")
205  : RegisteredParam<T>(name, description, min_value, max_value, enum_dictionary,
206  enum_description, group)
207  , current_value_(current_value)
208  , callback_(callback)
209  {
210  }
211 
212  T getCurrentValue() const override
213  {
214  return current_value_;
215  }
216 
217  void updateValue(T new_value) override
218  {
219  callback_(new_value);
220  current_value_ = new_value;
221  }
222 
223 protected:
225  boost::function<void(T value)> callback_;
226 };
227 
228 
229 } // namespace ddynamic_reconfigure
230 
231 #endif // REGISTERED_PARAM_H
ddynamic_reconfigure::RegisteredParam::getCurrentValue
virtual T getCurrentValue() const =0
ddynamic_reconfigure::PointerRegisteredParam::updateValue
void updateValue(T new_value) override
Definition: registered_param.h:184
ddynamic_reconfigure::CallbackRegisteredParam::updateValue
void updateValue(T new_value) override
Definition: registered_param.h:217
ddynamic_reconfigure::RegisteredParam::name_
const std::string name_
Definition: registered_param.h:154
ddynamic_reconfigure::RegisteredParam::getEditMethod
std::string getEditMethod() const
Definition: registered_param.h:112
ddynamic_reconfigure::RegisteredParam::~RegisteredParam
virtual ~RegisteredParam()
Definition: registered_param.h:58
ddynamic_reconfigure::PointerRegisteredParam::variable_
T * variable_
Definition: registered_param.h:192
ddynamic_reconfigure
Definition: ddynamic_reconfigure.h:42
ddynamic_reconfigure::CallbackRegisteredParam::callback_
boost::function< void(T value)> callback_
Definition: registered_param.h:225
ddynamic_reconfigure::PointerRegisteredParam
Definition: registered_param.h:165
ddynamic_reconfigure::PointerRegisteredParam::callback_
boost::function< void(T value)> callback_
Definition: registered_param.h:193
ddynamic_reconfigure::CallbackRegisteredParam::current_value_
T current_value_
Definition: registered_param.h:224
ddynamic_reconfigure::RegisteredParam::enum_description_
const std::string enum_description_
Definition: registered_param.h:159
ddynamic_reconfigure::PointerRegisteredParam::getCurrentValue
T getCurrentValue() const override
Definition: registered_param.h:180
ddynamic_reconfigure::CallbackRegisteredParam::CallbackRegisteredParam
CallbackRegisteredParam(const std::string &name, const std::string &description, T min_value, T max_value, T current_value, boost::function< void(T value)> callback, std::map< std::string, T > enum_dictionary={}, const std::string &enum_description="", const std::string &group="")
Definition: registered_param.h:200
ddynamic_reconfigure::RegisteredParam::getParamDescription
virtual dynamic_reconfigure::ParamDescription getParamDescription() const
Definition: registered_param.h:98
ddynamic_reconfigure::RegisteredParam::makeConst
std::string makeConst(const std::string &name, T value, const std::string &desc) const
Definition: registered_param.h:134
ddynamic_reconfigure::RegisteredParam::getValueString
std::string getValueString(T value) const
Definition: registered_param.h:86
ddynamic_reconfigure::RegisteredParam::updateValue
virtual void updateValue(T new_value)=0
ddynamic_reconfigure::CallbackRegisteredParam::getCurrentValue
T getCurrentValue() const override
Definition: registered_param.h:212
ddynamic_reconfigure::RegisteredParam::RegisteredParam
RegisteredParam(const std::string &name, const std::string &description, T min_value, T max_value, std::map< std::string, T > enum_dictionary={}, const std::string &enum_description="", const std::string &group="")
Definition: registered_param.h:45
ddynamic_reconfigure::RegisteredParam::getTypeName
std::string getTypeName() const
Definition: registered_param.h:65
ddynamic_reconfigure::PointerRegisteredParam::PointerRegisteredParam
PointerRegisteredParam(const std::string &name, const std::string &description, T min_value, T max_value, T *variable, boost::function< void(T value)> callback={}, std::map< std::string, T > enum_dictionary={}, const std::string &enum_description="", const std::string &group="")
Definition: registered_param.h:168
ddynamic_reconfigure::RegisteredParam::description_
const std::string description_
Definition: registered_param.h:155
ddynamic_reconfigure::RegisteredParam
Definition: registered_param.h:42
ddynamic_reconfigure::RegisteredParam::min_value_
const T min_value_
Definition: registered_param.h:156
ddynamic_reconfigure::RegisteredParam::enum_dictionary_
const std::map< std::string, T > enum_dictionary_
Definition: registered_param.h:158
ddynamic_reconfigure::RegisteredParam::max_value_
const T max_value_
Definition: registered_param.h:157
ddynamic_reconfigure::RegisteredParam::group_
const std::string group_
Definition: registered_param.h:160
ddynamic_reconfigure::CallbackRegisteredParam
Definition: registered_param.h:197


ddynamic_reconfigure
Author(s): Hilario Tome
autogenerated on Wed Mar 2 2022 00:09:57