test_ddynamic_reconfigure.cpp
Go to the documentation of this file.
1 #pragma clang diagnostic push
2 #pragma clang diagnostic ignored "-Wunknown-pragmas"
3 #pragma ide diagnostic ignored "OCDFAInspection"
5 #include <gtest/gtest.h>
6 #include <dynamic_reconfigure/Reconfigure.h>
8 #include <exception>
9 using namespace std;
10 namespace ddynamic_reconfigure {
11 
12  TEST(DDynamicReconfigureTest, mapTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
13  ros::NodeHandle nh("~");
14  DDynamicReconfigure dd(nh); // gets our main class running
15 
16  DDParam* ptr = new DDBool("exists",0,"",true);
17  DDPtr dd_ptr = DDPtr(ptr);
18 
19  dd.add(dd_ptr);
20  ASSERT_NE(DDPtr(),dd.at("exists"));
21 
22  dd.remove(ptr);
23  ASSERT_EQ(DDPtr(),dd.at("exists"));
24 
25  dd.remove(dd_ptr);
26  ASSERT_EQ(DDPtr(),dd.at("exists"));
27  }
28 
29  void basicCallback(const DDMap& map, int, bool *flag) {
30  *flag = true;
31  }
32 
36  TEST(DDynamicReconfigureTest, basicCallbackTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
37  ros::NodeHandle nh("~");
38  DDynamicReconfigure dd(nh); // gets our main class running
39 
40  bool flag = false;
41  DDFunc callback = bind(&basicCallback,_1,_2,&flag);
42  dd.start(callback);
43 
44  ros::AsyncSpinner spinner(1);
45  spinner.start();
46 
47  dynamic_reconfigure::Reconfigure srv;
48 
49  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
50  ASSERT_TRUE(flag);
51  }
52 
53  void intCallback(const DDMap& map, int, int *flag) {
54  ASSERT_EQ("int",at(map,"int_param")->getValue().getType());
55  *flag = at(map,"int_param")->getValue().toInt();
56  }
57 
61  TEST(DDynamicReconfigureTest, intTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
62  ros::NodeHandle nh("~");
63  int flag = 0;
64  DDFunc callback = bind(&intCallback,_1,_2,&flag);
65 
66  DDynamicReconfigure dd(nh);
67  dd.add(new DDInt("int_param", 0,"int_param", 0));
68  dd.start(callback);
69 
70  ros::AsyncSpinner spinner(1);
71  spinner.start();
72 
73  dynamic_reconfigure::Reconfigure srv;
74  dynamic_reconfigure::IntParameter int_param;
75  int_param.name = "int_param";
76 
77  int_param.value = (int)random();
78  srv.request.config.ints.push_back(int_param);
79  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
80  ASSERT_EQ(int_param.value, flag);
81 
82  int_param.value = INT32_MAX;
83  srv.request.config.ints.push_back(int_param);
84  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
85  ASSERT_EQ(int_param.value, flag);
86 
87  int_param.value = INT32_MIN;
88  srv.request.config.ints.push_back(int_param);
89  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
90  ASSERT_EQ(int_param.value, flag);
91  }
92 
93  void doubleCallback(const DDMap& map, int, double *flag) {
94  ASSERT_EQ("double",at(map,"double_param")->getValue().getType());
95  *flag = at(map,"double_param")->getValue().toDouble();
96  }
97 
101  TEST(DDynamicReconfigureTest, doubleTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
102  ros::NodeHandle nh("~");
103  double flag = 0;
104  DDFunc callback = bind(&doubleCallback,_1,_2,&flag);
105 
106  DDynamicReconfigure dd(nh);
107  dd.add(new DDDouble("double_param", 0,"double_param", 0));
108  dd.start(callback);
109 
110  ros::AsyncSpinner spinner(1);
111  spinner.start();
112 
113  dynamic_reconfigure::Reconfigure srv;
114  dynamic_reconfigure::DoubleParameter double_param;
115  double_param.name = "double_param";
116 
117  double_param.value = (double)random();
118  srv.request.config.doubles.push_back(double_param);
119  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
120  ASSERT_EQ(double_param.value, flag);
121 
122  double_param.value = DBL_MAX;
123  srv.request.config.doubles.push_back(double_param);
124  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
125  ASSERT_EQ(double_param.value, flag);
126 
127  double_param.value = DBL_MIN;
128  srv.request.config.doubles.push_back(double_param);
129  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
130  ASSERT_EQ(double_param.value, flag);
131 
132  double_param.value = -DBL_MAX;
133  srv.request.config.doubles.push_back(double_param);
134  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
135  ASSERT_EQ(double_param.value, flag);
136 
137  double_param.value = -DBL_MIN;
138  srv.request.config.doubles.push_back(double_param);
139  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
140  ASSERT_EQ(double_param.value, flag);
141  }
142 
143  void boolCallback(const DDMap& map, int, bool *flag) {
144  ASSERT_EQ("bool",at(map,"bool_param")->getValue().getType());
145  *flag = at(map,"bool_param")->getValue().toBool();
146  }
147 
151  TEST(DDynamicReconfigureTest, boolTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
152  ros::NodeHandle nh("~");
153  bool flag = true;
154  DDFunc callback = bind(&boolCallback,_1,_2,&flag);
155 
156  DDynamicReconfigure dd(nh);
157  dd.add(new DDBool("bool_param", 0,"bool_param", false));
158  dd.start(callback);
159 
160  ros::AsyncSpinner spinner(1);
161  spinner.start();
162 
163  dynamic_reconfigure::Reconfigure srv;
164  dynamic_reconfigure::BoolParameter bool_param;
165  bool_param.name = "bool_param";
166 
167  bool_param.value = (unsigned char)false;
168  srv.request.config.bools.push_back(bool_param);
169  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
170  ASSERT_EQ((bool)bool_param.value, flag);
171 
172  flag = false;
173 
174  bool_param.value = (unsigned char)true;
175  srv.request.config.bools.push_back(bool_param);
176  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
177  ASSERT_EQ((bool)bool_param.value, flag);
178  }
179 
180  void strCallback(const DDMap& map, int, string *flag) {
181  ASSERT_EQ("string",at(map,"string_param")->getValue().getType());
182  *flag = at(map,"string_param")->getValue().toString();
183  }
184 
188  TEST(DDynamicReconfigureTest, stringTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
189  ros::NodeHandle nh("~");
190  string flag = "YOU SHOULDN'T RECEIVE THIS";
191  DDFunc callback = bind(&strCallback,_1,_2,&flag);
192 
193  DDynamicReconfigure dd(nh);
194  dd.add(new DDString("string_param", 0,"string_param", ""));
195  dd.start(callback);
196 
197  ros::AsyncSpinner spinner(1);
198  spinner.start();
199 
200  dynamic_reconfigure::Reconfigure srv;
201  dynamic_reconfigure::StrParameter string_param;
202  string_param.name = "string_param";
203 
204  string_param.value = string("\000"); // NOLINT(bugprone-string-literal-with-embedded-nul)
205  srv.request.config.strs.push_back(string_param);
206  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
207  ASSERT_EQ(string_param.value, flag);
208 
209  string_param.value = "";
210  srv.request.config.strs.push_back(string_param);
211  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
212  ASSERT_EQ(string_param.value, flag);
213 
214  string_param.value = "Hello World";
215  srv.request.config.strs.push_back(string_param);
216  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
217  ASSERT_EQ(string_param.value, flag);
218  }
219 
220  void enumCallback(const DDMap& map, int, int *flag) {
221  ASSERT_EQ("int",at(map,"enum_param")->getValue().getType());
222  *flag = at(map,"enum_param")->getValue().toInt();
223  }
224 
228  TEST(DDynamicReconfigureTest, enumTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
229  ros::NodeHandle nh("~");
230  int flag = 0;
231  DDFunc callback = bind(&enumCallback,_1,_2,&flag);
232 
233  map<string,int> dict;
234  dict["ONE"] = 1;
235  dict["NEG-ONE"] = -1;
236  dict["TEN"] = 10;
237 
238  DDynamicReconfigure dd(nh);
239  dd.add(new DDEnum("enum_param", 0,"enum_param", "ONE", dict));
240  dd.start(callback);
241 
242  ros::AsyncSpinner spinner(1);
243  spinner.start();
244 
245  dynamic_reconfigure::Reconfigure srv;
246 
247  dynamic_reconfigure::IntParameter int_enum;
248  int_enum.name = "enum_param";
249 
250  int_enum.value = 1;
251  srv.request.config.ints.push_back(int_enum);
252  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
253  ASSERT_EQ(int_enum.value, flag);
254 
255  int_enum.value = 10;
256  srv.request.config.ints.push_back(int_enum);
257  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
258  ASSERT_EQ(int_enum.value, flag);
259 
260  int_enum.value = -1;
261  srv.request.config.ints.push_back(int_enum);
262  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
263  ASSERT_EQ(int_enum.value, flag);
264 
265  srv.request.config.ints.clear();
266  dynamic_reconfigure::StrParameter str_enum;
267  str_enum.name = "enum_param";
268 
269  str_enum.value = "ONE";
270  srv.request.config.strs.push_back(str_enum);
271  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
272  ASSERT_EQ(dict[str_enum.value], flag);
273 
274  str_enum.value = "TEN";
275  srv.request.config.strs.push_back(str_enum);
276  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
277  ASSERT_EQ(dict[str_enum.value], flag);
278 
279  str_enum.value = "NEG-ONE";
280  srv.request.config.strs.push_back(str_enum);
281  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
282  ASSERT_EQ(dict[str_enum.value], flag);
283  }
284 
285  void complexCallback(const DDMap& map, int level) {
286  ASSERT_EQ(0, level);
287  ASSERT_EQ(1, at(map,"int_param")->getValue().toInt());
288  ASSERT_EQ(0.6, at(map,"double_param")->getValue().toDouble());
289  ASSERT_EQ("Goodbye Home", at(map,"str_param")->getValue().toString());
290  ASSERT_EQ(false, at(map,"bool_param")->getValue().toBool());
291  ASSERT_EQ(3, at(map,"enum_param")->getValue().toInt());
292  }
293 
297  TEST(DDynamicReconfigureTest, callbackTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
298  ros::NodeHandle nh("~");
299  DDynamicReconfigure dd(nh); // gets our main class running
300  dd.add(new DDInt("int_param", 0, "An Integer parameter", 0, 50, 100));
301  dd.add(new DDDouble("double_param", 0, "A double parameter", .5, 0, 1));
302  dd.add(new DDString("str_param", 0, "A string parameter", "Hello World"));
303  dd.add(new DDBool("bool_param", 0, "A Boolean parameter", true));
304  map<string, int> dict; {
305  dict["Small"] = 0;
306  dict["Medium"] = 1;
307  dict["Large"] = 2;
308  dict["ExtraLarge"] = 3;
309  }
310  dd.add(new DDEnum("enum_param", 0, "A size parameter which is edited via an enum", 0, dict));
312 
313  ros::AsyncSpinner spinner(1);
314  spinner.start();
315 
316  dynamic_reconfigure::Reconfigure srv;
317 
318  dynamic_reconfigure::IntParameter int_param;
319  int_param.name = "int_param";
320  int_param.value = 1;
321  srv.request.config.ints.push_back(int_param);
322 
323  dynamic_reconfigure::DoubleParameter double_param;
324  double_param.name = "double_param";
325  double_param.value = 0.6;
326  srv.request.config.doubles.push_back(double_param);
327 
328  dynamic_reconfigure::BoolParameter bool_param;
329  bool_param.name = "bool_param";
330  bool_param.value = (unsigned char) false;
331  srv.request.config.bools.push_back(bool_param);
332 
333  dynamic_reconfigure::StrParameter string_param;
334  string_param.name = "str_param";
335  string_param.value = "Goodbye Home";
336  srv.request.config.strs.push_back(string_param);
337 
338  dynamic_reconfigure::StrParameter enum_param;
339  enum_param.name = "enum_param";
340  enum_param.value = "ExtraLarge";
341  srv.request.config.strs.push_back(enum_param);
342 
343  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
344 
345  bool flag = false;
346  DDFunc callback = bind(&basicCallback,_1,_2,&flag);
347  dd.setCallback(callback);
348  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
349  ASSERT_TRUE(flag);
350 
351  flag = false;
352  dd.clearCallback();
353  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
354  ASSERT_FALSE(flag);
355  }
356 
358  public:
359  inline void internalCallback(const DDMap& map, int level) {}
360  };
361 
365  TEST(DDynamicReconfigureTest, memberCallbackTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
366  ros::NodeHandle nh("~");
367  DDynamicReconfigure dd(nh); // gets our main class running
368 
369  dd.start(&InternalClass::internalCallback,new InternalClass);
370 
371  ros::AsyncSpinner spinner(1);
372  spinner.start();
373 
374  dynamic_reconfigure::Reconfigure srv;
375 
376  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
377  }
378 
379  void levelCallback(const DDMap&, int level, int *flag) {
380  *flag = level;
381  }
382 
386  TEST(DDynamicReconfigureTest, levelTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
387  ros::NodeHandle nh("~");
388  int flag = 0;
389  DDFunc callback = bind(&levelCallback, _1, _2, &flag);
390 
391  DDynamicReconfigure dd(nh);
392  int top = (int) random() % 5 + 5;
393  unsigned int or_sum = 0, next;
394  for (int i = 1; i < top; i++) {
395  next = (unsigned int) random();
396  or_sum |= next;
397  dd.add(new DDInt((format("param_%d") % i).str(), next,"level_param", 0));
398  }
399  dd.start(callback);
400 
401  ros::AsyncSpinner spinner(1);
402  spinner.start();
403 
404  dynamic_reconfigure::Reconfigure srv;
405  dynamic_reconfigure::IntParameter int_param;
406  for (int i = 1; i < top; i++) {
407  int_param.name = (format("param_%d") % i).str();
408  int_param.value = 1;
409  srv.request.config.ints.push_back(int_param);
410  }
411 
412  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
413  ASSERT_EQ(or_sum, flag);
414 
415  dd.add(new DDInt("unchanged_param", 1,"unchanged_param", 0)); //u-int max means everything is 1, so the result must also be that.
416  dynamic_reconfigure::IntParameter unchanged_param;
417  unchanged_param.name = "unchanged_param";
418  unchanged_param.value = 1;
419  srv.request.config.ints.push_back(unchanged_param);
420 
421  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
422  ASSERT_EQ(1, flag);
423 
424  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
425  ASSERT_EQ(0, flag);
426  }
427 
428  void badCallback(const DDMap&, int) {
429  std::exception e;
430  throw e; // NOLINT(cert-err09-cpp,cert-err61-cpp,misc-throw-by-value-catch-by-reference)
431  }
432 
436  TEST(DDynamicReconfigureTest, badCallbackTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
437  ros::NodeHandle nh("~");
438  DDynamicReconfigure dd(nh); // gets our main class running
439  dd.start(badCallback);
440 
441  ros::AsyncSpinner spinner(1);
442  spinner.start();
443 
444  dynamic_reconfigure::Reconfigure srv;
445 
446  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
447  // this is the best way to see exceptions doesn't make the whole thing tumble
448  }
449 
450  void missingCallback(const DDMap& map, int) {
451  ASSERT_EQ(map.end(),map.find("int_param"));
452  ASSERT_EQ(map.end(),map.find("double_param"));
453  ASSERT_EQ(map.end(),map.find("bool_param"));
454  ASSERT_EQ(map.end(),map.find("str_param"));
455  ASSERT_EQ(map.end(),map.find("enum_param"));
456  }
457 
461  TEST(DDynamicReconfigureTest, unknownParamTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
462  ros::NodeHandle nh("~");
463  DDynamicReconfigure dd(nh); // gets our main class running
465 
466  ros::AsyncSpinner spinner(1);
467  spinner.start();
468 
469  dynamic_reconfigure::Reconfigure srv;
470 
471  dynamic_reconfigure::IntParameter int_param;
472  int_param.name = "int_param";
473  int_param.value = 1;
474  srv.request.config.ints.push_back(int_param);
475 
476  dynamic_reconfigure::DoubleParameter double_param;
477  double_param.name = "double_param";
478  double_param.value = 0.6;
479  srv.request.config.doubles.push_back(double_param);
480 
481  dynamic_reconfigure::BoolParameter bool_param;
482  bool_param.name = "bool_param";
483  bool_param.value = (unsigned char) false;
484  srv.request.config.bools.push_back(bool_param);
485 
486  dynamic_reconfigure::StrParameter string_param;
487  string_param.name = "str_param";
488  string_param.value = "Goodbye Home";
489  srv.request.config.strs.push_back(string_param);
490 
491  dynamic_reconfigure::StrParameter enum_param;
492  enum_param.name = "enum_param";
493  enum_param.value = "ExtraLarge";
494  srv.request.config.strs.push_back(enum_param);
495 
496  ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
497  }
498 
502  TEST(DDynamicReconfigureTest, streamTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
503  ros::NodeHandle nh("~");
504  DDynamicReconfigure dd(nh); // gets our main class running
505  DDInt dd_int("int_param", 0, "An Integer parameter", 0, 50, 100);
506  DDDouble dd_double("double_param", 0, "A double parameter", .5, 0, 1);
507  DDString dd_string("str_param", 0, "A string parameter", "Hello World");
508  DDBool dd_bool("bool_param", 0, "A Boolean parameter", true);
509  dd.add(new DDInt(dd_int));
510  dd.add(new DDDouble(dd_double));
511  dd.add(new DDString(dd_string));
512  dd.add(new DDBool(dd_bool));
513  map<string, int> dict; {
514  dict["Small"] = 0;
515  dict["Medium"] = 1;
516  dict["Large"] = 2;
517  dict["ExtraLarge"] = 3;
518  }
519  DDEnum dd_enum("enum_param", 0, "A size parameter which is edited via an enum", 0, dict);
520  dd.add(new DDEnum(dd_enum));
521 
522  stringstream stream, explicit_stream;
523  stream << dd;
524 
525  explicit_stream << "{" << dd_bool << "," << dd_double << "," << dd_enum << "," << dd_int << "," << dd_string << "}";
526  ASSERT_EQ(explicit_stream.str(),stream.str());
527  }
528 }
529 
530 
531 int main(int argc, char** argv) {
532  testing::InitGoogleTest(&argc, argv);
533  ros::init(argc, argv, "ddynamic_reconfigure_test");
534 
535  srand((unsigned int)random());
536 
537  return RUN_ALL_TESTS();
538 }
539 #pragma clang diagnostic pop
void boolCallback(const DDMap &map, int, bool *flag)
void levelCallback(const DDMap &, int level, int *flag)
void clearCallback()
sets the callback to be empty.
void intCallback(const DDMap &map, int, int *flag)
boost::function< void(const DDMap &, int)> DDFunc
a boolean implementation of the parameter. These are used to handle true/false values, or bit quantities if needed. In ROS, booleans are handled as u-bytes (u-int8), so be careful with these!
Definition: dd_bool_param.h:16
bool call(const std::string &service_name, MReq &req, MRes &res)
void internalCallback(const DDMap &map, int level)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void callback(const DDMap &map, int)
Definition: dd_server.cpp:26
map< string, DDPtr > DDMap
The DDynamicReconfigure class is the main class responsible for keeping track of parameters basic pro...
void basicCallback(const DDMap &map, int, bool *flag)
DDPtr at(const DDMap &map, const char *name)
a tool people who use this API can use to find the param given within the param map.
an integer enum implementation of the parameter. This is an extension to the int parameter, which allows creating string aliases for certain (if not all) numbers available.
Definition: dd_enum_param.h:19
void doubleCallback(const DDMap &map, int, double *flag)
void strCallback(const DDMap &map, int, string *flag)
void missingCallback(const DDMap &map, int)
The DDParam class is the abstraction of all parameter types, and is the template for creating them...
Definition: dd_param.h:48
TEST(DDynamicReconfigureTest, streamTest)
tests that ddynamic&#39;s stream operator properly works
void setCallback(DDFunc callback)
sets the callback to this.
const std::string & getNamespace() const
a double implementation of the parameter. This is used to handle double-precision floating point numb...
DDPtr at(const char *name)
a tool people who use this API can use to find the param given within the param map.
virtual void start()
starts the server and config, without having any callback.
void complexCallback(const DDMap &map, int level)
virtual void add(DDPtr param)
adds a parameter to the list, allowing it to be generated.
a string implementation of the parameter. This is used to handle strings of characters of variable le...
int main(int argc, char **argv)
void enumCallback(const DDMap &map, int, int *flag)
an integer implementation of the parameter. This is used to 32 bit signed integral numbers...
Definition: dd_int_param.h:17
boost::shared_ptr< DDParam > DDPtr
Definition: dd_param.h:17
void badCallback(const DDMap &, int)


ddynamic_reconfigure
Author(s): Noam Dori
autogenerated on Thu May 16 2019 02:46:37