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> 12 TEST(DDynamicReconfigureTest, mapTest) {
20 ASSERT_NE(
DDPtr(),dd.
at(
"exists"));
23 ASSERT_EQ(
DDPtr(),dd.
at(
"exists"));
26 ASSERT_EQ(
DDPtr(),dd.
at(
"exists"));
36 TEST(DDynamicReconfigureTest, basicCallbackTest) {
47 dynamic_reconfigure::Reconfigure srv;
54 ASSERT_EQ(
"int",
at(map,
"int_param")->getValue().getType());
55 *flag =
at(map,
"int_param")->getValue().toInt();
61 TEST(DDynamicReconfigureTest, intTest) {
67 dd.
add(
new DDInt(
"int_param", 0,
"int_param", 0));
73 dynamic_reconfigure::Reconfigure srv;
74 dynamic_reconfigure::IntParameter int_param;
75 int_param.name =
"int_param";
77 int_param.value = (int)random();
78 srv.request.config.ints.push_back(int_param);
80 ASSERT_EQ(int_param.value, flag);
82 int_param.value = INT32_MAX;
83 srv.request.config.ints.push_back(int_param);
85 ASSERT_EQ(int_param.value, flag);
87 int_param.value = INT32_MIN;
88 srv.request.config.ints.push_back(int_param);
90 ASSERT_EQ(int_param.value, flag);
94 ASSERT_EQ(
"double",
at(map,
"double_param")->getValue().getType());
95 *flag =
at(map,
"double_param")->getValue().toDouble();
101 TEST(DDynamicReconfigureTest, doubleTest) {
107 dd.
add(
new DDDouble(
"double_param", 0,
"double_param", 0));
113 dynamic_reconfigure::Reconfigure srv;
114 dynamic_reconfigure::DoubleParameter double_param;
115 double_param.name =
"double_param";
117 double_param.value = (double)random();
118 srv.request.config.doubles.push_back(double_param);
120 ASSERT_EQ(double_param.value, flag);
122 double_param.value = DBL_MAX;
123 srv.request.config.doubles.push_back(double_param);
125 ASSERT_EQ(double_param.value, flag);
127 double_param.value = DBL_MIN;
128 srv.request.config.doubles.push_back(double_param);
130 ASSERT_EQ(double_param.value, flag);
132 double_param.value = -DBL_MAX;
133 srv.request.config.doubles.push_back(double_param);
135 ASSERT_EQ(double_param.value, flag);
137 double_param.value = -DBL_MIN;
138 srv.request.config.doubles.push_back(double_param);
140 ASSERT_EQ(double_param.value, flag);
144 ASSERT_EQ(
"bool",
at(map,
"bool_param")->getValue().getType());
145 *flag =
at(map,
"bool_param")->getValue().toBool();
151 TEST(DDynamicReconfigureTest, boolTest) {
157 dd.
add(
new DDBool(
"bool_param", 0,
"bool_param",
false));
163 dynamic_reconfigure::Reconfigure srv;
164 dynamic_reconfigure::BoolParameter bool_param;
165 bool_param.name =
"bool_param";
167 bool_param.value = (
unsigned char)
false;
168 srv.request.config.bools.push_back(bool_param);
170 ASSERT_EQ((
bool)bool_param.value, flag);
174 bool_param.value = (
unsigned char)
true;
175 srv.request.config.bools.push_back(bool_param);
177 ASSERT_EQ((
bool)bool_param.value, flag);
181 ASSERT_EQ(
"string",
at(map,
"string_param")->getValue().getType());
182 *flag =
at(map,
"string_param")->getValue().toString();
188 TEST(DDynamicReconfigureTest, stringTest) {
190 string flag =
"YOU SHOULDN'T RECEIVE THIS";
194 dd.
add(
new DDString(
"string_param", 0,
"string_param",
""));
200 dynamic_reconfigure::Reconfigure srv;
201 dynamic_reconfigure::StrParameter string_param;
202 string_param.name =
"string_param";
204 string_param.value = string(
"\000");
205 srv.request.config.strs.push_back(string_param);
207 ASSERT_EQ(string_param.value, flag);
209 string_param.value =
"";
210 srv.request.config.strs.push_back(string_param);
212 ASSERT_EQ(string_param.value, flag);
214 string_param.value =
"Hello World";
215 srv.request.config.strs.push_back(string_param);
217 ASSERT_EQ(string_param.value, flag);
221 ASSERT_EQ(
"int",
at(map,
"enum_param")->getValue().getType());
222 *flag =
at(map,
"enum_param")->getValue().toInt();
228 TEST(DDynamicReconfigureTest, enumTest) {
233 map<string,int> dict;
235 dict[
"NEG-ONE"] = -1;
239 dd.
add(
new DDEnum(
"enum_param", 0,
"enum_param",
"ONE", dict));
245 dynamic_reconfigure::Reconfigure srv;
247 dynamic_reconfigure::IntParameter int_enum;
248 int_enum.name =
"enum_param";
251 srv.request.config.ints.push_back(int_enum);
253 ASSERT_EQ(int_enum.value, flag);
256 srv.request.config.ints.push_back(int_enum);
258 ASSERT_EQ(int_enum.value, flag);
261 srv.request.config.ints.push_back(int_enum);
263 ASSERT_EQ(int_enum.value, flag);
265 srv.request.config.ints.clear();
266 dynamic_reconfigure::StrParameter str_enum;
267 str_enum.name =
"enum_param";
269 str_enum.value =
"ONE";
270 srv.request.config.strs.push_back(str_enum);
272 ASSERT_EQ(dict[str_enum.value], flag);
274 str_enum.value =
"TEN";
275 srv.request.config.strs.push_back(str_enum);
277 ASSERT_EQ(dict[str_enum.value], flag);
279 str_enum.value =
"NEG-ONE";
280 srv.request.config.strs.push_back(str_enum);
282 ASSERT_EQ(dict[str_enum.value], flag);
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());
297 TEST(DDynamicReconfigureTest, callbackTest) {
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; {
308 dict[
"ExtraLarge"] = 3;
310 dd.
add(
new DDEnum(
"enum_param", 0,
"A size parameter which is edited via an enum", 0, dict));
316 dynamic_reconfigure::Reconfigure srv;
318 dynamic_reconfigure::IntParameter int_param;
319 int_param.name =
"int_param";
321 srv.request.config.ints.push_back(int_param);
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);
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);
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);
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);
365 TEST(DDynamicReconfigureTest, memberCallbackTest) {
374 dynamic_reconfigure::Reconfigure srv;
386 TEST(DDynamicReconfigureTest, levelTest) {
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();
397 dd.
add(
new DDInt((format(
"param_%d") % i).str(), next,
"level_param", 0));
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();
409 srv.request.config.ints.push_back(int_param);
413 ASSERT_EQ(or_sum, flag);
415 dd.
add(
new DDInt(
"unchanged_param", 1,
"unchanged_param", 0));
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);
436 TEST(DDynamicReconfigureTest, badCallbackTest) {
444 dynamic_reconfigure::Reconfigure srv;
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"));
461 TEST(DDynamicReconfigureTest, unknownParamTest) {
469 dynamic_reconfigure::Reconfigure srv;
471 dynamic_reconfigure::IntParameter int_param;
472 int_param.name =
"int_param";
474 srv.request.config.ints.push_back(int_param);
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);
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);
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);
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);
502 TEST(DDynamicReconfigureTest, streamTest) {
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);
513 map<string, int> dict; {
517 dict[
"ExtraLarge"] = 3;
519 DDEnum dd_enum(
"enum_param", 0,
"A size parameter which is edited via an enum", 0, dict);
522 stringstream stream, explicit_stream;
525 explicit_stream <<
"{" << dd_bool <<
"," << dd_double <<
"," << dd_enum <<
"," << dd_int <<
"," << dd_string <<
"}";
526 ASSERT_EQ(explicit_stream.str(),stream.str());
531 int main(
int argc,
char** argv) {
532 testing::InitGoogleTest(&argc, argv);
533 ros::init(argc, argv,
"ddynamic_reconfigure_test");
535 srand((
unsigned int)random());
537 return RUN_ALL_TESTS();
539 #pragma clang diagnostic pop
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void callback(const DDMap &map, int)
const std::string & getNamespace() const