00001 #pragma clang diagnostic push
00002 #pragma clang diagnostic ignored "-Wunknown-pragmas"
00003 #pragma ide diagnostic ignored "OCDFAInspection"
00004 #include <ddynamic_reconfigure/ddynamic_reconfigure.h>
00005 #include <gtest/gtest.h>
00006 #include <dynamic_reconfigure/Reconfigure.h>
00007 #include <ddynamic_reconfigure/param/dd_all_params.h>
00008 #include <exception>
00009 using namespace std;
00010 namespace ddynamic_reconfigure {
00011
00012 TEST(DDynamicReconfigureTest, mapTest) {
00013 ros::NodeHandle nh("~");
00014 DDynamicReconfigure dd(nh);
00015
00016 DDParam* ptr = new DDBool("exists",0,"",true);
00017 DDPtr dd_ptr = DDPtr(ptr);
00018
00019 dd.add(dd_ptr);
00020 ASSERT_NE(DDPtr(),dd.at("exists"));
00021
00022 dd.remove(ptr);
00023 ASSERT_EQ(DDPtr(),dd.at("exists"));
00024
00025 dd.remove(dd_ptr);
00026 ASSERT_EQ(DDPtr(),dd.at("exists"));
00027 }
00028
00029 void basicCallback(const DDMap& map, int, bool *flag) {
00030 *flag = true;
00031 }
00032
00036 TEST(DDynamicReconfigureTest, basicCallbackTest) {
00037 ros::NodeHandle nh("~");
00038 DDynamicReconfigure dd(nh);
00039
00040 bool flag = false;
00041 DDFunc callback = bind(&basicCallback,_1,_2,&flag);
00042 dd.start(callback);
00043
00044 ros::AsyncSpinner spinner(1);
00045 spinner.start();
00046
00047 dynamic_reconfigure::Reconfigure srv;
00048
00049 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00050 ASSERT_TRUE(flag);
00051 }
00052
00053 void intCallback(const DDMap& map, int, int *flag) {
00054 ASSERT_EQ("int",at(map,"int_param")->getValue().getType());
00055 *flag = at(map,"int_param")->getValue().toInt();
00056 }
00057
00061 TEST(DDynamicReconfigureTest, intTest) {
00062 ros::NodeHandle nh("~");
00063 int flag = 0;
00064 DDFunc callback = bind(&intCallback,_1,_2,&flag);
00065
00066 DDynamicReconfigure dd(nh);
00067 dd.add(new DDInt("int_param", 0,"int_param", 0));
00068 dd.start(callback);
00069
00070 ros::AsyncSpinner spinner(1);
00071 spinner.start();
00072
00073 dynamic_reconfigure::Reconfigure srv;
00074 dynamic_reconfigure::IntParameter int_param;
00075 int_param.name = "int_param";
00076
00077 int_param.value = (int)random();
00078 srv.request.config.ints.push_back(int_param);
00079 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00080 ASSERT_EQ(int_param.value, flag);
00081
00082 int_param.value = INT32_MAX;
00083 srv.request.config.ints.push_back(int_param);
00084 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00085 ASSERT_EQ(int_param.value, flag);
00086
00087 int_param.value = INT32_MIN;
00088 srv.request.config.ints.push_back(int_param);
00089 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00090 ASSERT_EQ(int_param.value, flag);
00091 }
00092
00093 void doubleCallback(const DDMap& map, int, double *flag) {
00094 ASSERT_EQ("double",at(map,"double_param")->getValue().getType());
00095 *flag = at(map,"double_param")->getValue().toDouble();
00096 }
00097
00101 TEST(DDynamicReconfigureTest, doubleTest) {
00102 ros::NodeHandle nh("~");
00103 double flag = 0;
00104 DDFunc callback = bind(&doubleCallback,_1,_2,&flag);
00105
00106 DDynamicReconfigure dd(nh);
00107 dd.add(new DDDouble("double_param", 0,"double_param", 0));
00108 dd.start(callback);
00109
00110 ros::AsyncSpinner spinner(1);
00111 spinner.start();
00112
00113 dynamic_reconfigure::Reconfigure srv;
00114 dynamic_reconfigure::DoubleParameter double_param;
00115 double_param.name = "double_param";
00116
00117 double_param.value = (double)random();
00118 srv.request.config.doubles.push_back(double_param);
00119 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00120 ASSERT_EQ(double_param.value, flag);
00121
00122 double_param.value = DBL_MAX;
00123 srv.request.config.doubles.push_back(double_param);
00124 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00125 ASSERT_EQ(double_param.value, flag);
00126
00127 double_param.value = DBL_MIN;
00128 srv.request.config.doubles.push_back(double_param);
00129 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00130 ASSERT_EQ(double_param.value, flag);
00131
00132 double_param.value = -DBL_MAX;
00133 srv.request.config.doubles.push_back(double_param);
00134 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00135 ASSERT_EQ(double_param.value, flag);
00136
00137 double_param.value = -DBL_MIN;
00138 srv.request.config.doubles.push_back(double_param);
00139 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00140 ASSERT_EQ(double_param.value, flag);
00141 }
00142
00143 void boolCallback(const DDMap& map, int, bool *flag) {
00144 ASSERT_EQ("bool",at(map,"bool_param")->getValue().getType());
00145 *flag = at(map,"bool_param")->getValue().toBool();
00146 }
00147
00151 TEST(DDynamicReconfigureTest, boolTest) {
00152 ros::NodeHandle nh("~");
00153 bool flag = true;
00154 DDFunc callback = bind(&boolCallback,_1,_2,&flag);
00155
00156 DDynamicReconfigure dd(nh);
00157 dd.add(new DDBool("bool_param", 0,"bool_param", false));
00158 dd.start(callback);
00159
00160 ros::AsyncSpinner spinner(1);
00161 spinner.start();
00162
00163 dynamic_reconfigure::Reconfigure srv;
00164 dynamic_reconfigure::BoolParameter bool_param;
00165 bool_param.name = "bool_param";
00166
00167 bool_param.value = (unsigned char)false;
00168 srv.request.config.bools.push_back(bool_param);
00169 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00170 ASSERT_EQ((bool)bool_param.value, flag);
00171
00172 flag = false;
00173
00174 bool_param.value = (unsigned char)true;
00175 srv.request.config.bools.push_back(bool_param);
00176 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00177 ASSERT_EQ((bool)bool_param.value, flag);
00178 }
00179
00180 void strCallback(const DDMap& map, int, string *flag) {
00181 ASSERT_EQ("string",at(map,"string_param")->getValue().getType());
00182 *flag = at(map,"string_param")->getValue().toString();
00183 }
00184
00188 TEST(DDynamicReconfigureTest, stringTest) {
00189 ros::NodeHandle nh("~");
00190 string flag = "YOU SHOULDN'T RECEIVE THIS";
00191 DDFunc callback = bind(&strCallback,_1,_2,&flag);
00192
00193 DDynamicReconfigure dd(nh);
00194 dd.add(new DDString("string_param", 0,"string_param", ""));
00195 dd.start(callback);
00196
00197 ros::AsyncSpinner spinner(1);
00198 spinner.start();
00199
00200 dynamic_reconfigure::Reconfigure srv;
00201 dynamic_reconfigure::StrParameter string_param;
00202 string_param.name = "string_param";
00203
00204 string_param.value = string("\000");
00205 srv.request.config.strs.push_back(string_param);
00206 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00207 ASSERT_EQ(string_param.value, flag);
00208
00209 string_param.value = "";
00210 srv.request.config.strs.push_back(string_param);
00211 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00212 ASSERT_EQ(string_param.value, flag);
00213
00214 string_param.value = "Hello World";
00215 srv.request.config.strs.push_back(string_param);
00216 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00217 ASSERT_EQ(string_param.value, flag);
00218 }
00219
00220 void enumCallback(const DDMap& map, int, int *flag) {
00221 ASSERT_EQ("int",at(map,"enum_param")->getValue().getType());
00222 *flag = at(map,"enum_param")->getValue().toInt();
00223 }
00224
00228 TEST(DDynamicReconfigureTest, enumTest) {
00229 ros::NodeHandle nh("~");
00230 int flag = 0;
00231 DDFunc callback = bind(&enumCallback,_1,_2,&flag);
00232
00233 map<string,int> dict;
00234 dict["ONE"] = 1;
00235 dict["NEG-ONE"] = -1;
00236 dict["TEN"] = 10;
00237
00238 DDynamicReconfigure dd(nh);
00239 dd.add(new DDEnum("enum_param", 0,"enum_param", "ONE", dict));
00240 dd.start(callback);
00241
00242 ros::AsyncSpinner spinner(1);
00243 spinner.start();
00244
00245 dynamic_reconfigure::Reconfigure srv;
00246
00247 dynamic_reconfigure::IntParameter int_enum;
00248 int_enum.name = "enum_param";
00249
00250 int_enum.value = 1;
00251 srv.request.config.ints.push_back(int_enum);
00252 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00253 ASSERT_EQ(int_enum.value, flag);
00254
00255 int_enum.value = 10;
00256 srv.request.config.ints.push_back(int_enum);
00257 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00258 ASSERT_EQ(int_enum.value, flag);
00259
00260 int_enum.value = -1;
00261 srv.request.config.ints.push_back(int_enum);
00262 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00263 ASSERT_EQ(int_enum.value, flag);
00264
00265 srv.request.config.ints.clear();
00266 dynamic_reconfigure::StrParameter str_enum;
00267 str_enum.name = "enum_param";
00268
00269 str_enum.value = "ONE";
00270 srv.request.config.strs.push_back(str_enum);
00271 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00272 ASSERT_EQ(dict[str_enum.value], flag);
00273
00274 str_enum.value = "TEN";
00275 srv.request.config.strs.push_back(str_enum);
00276 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00277 ASSERT_EQ(dict[str_enum.value], flag);
00278
00279 str_enum.value = "NEG-ONE";
00280 srv.request.config.strs.push_back(str_enum);
00281 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00282 ASSERT_EQ(dict[str_enum.value], flag);
00283 }
00284
00285 void complexCallback(const DDMap& map, int level) {
00286 ASSERT_EQ(0, level);
00287 ASSERT_EQ(1, at(map,"int_param")->getValue().toInt());
00288 ASSERT_EQ(0.6, at(map,"double_param")->getValue().toDouble());
00289 ASSERT_EQ("Goodbye Home", at(map,"str_param")->getValue().toString());
00290 ASSERT_EQ(false, at(map,"bool_param")->getValue().toBool());
00291 ASSERT_EQ(3, at(map,"enum_param")->getValue().toInt());
00292 }
00293
00297 TEST(DDynamicReconfigureTest, callbackTest) {
00298 ros::NodeHandle nh("~");
00299 DDynamicReconfigure dd(nh);
00300 dd.add(new DDInt("int_param", 0, "An Integer parameter", 0, 50, 100));
00301 dd.add(new DDDouble("double_param", 0, "A double parameter", .5, 0, 1));
00302 dd.add(new DDString("str_param", 0, "A string parameter", "Hello World"));
00303 dd.add(new DDBool("bool_param", 0, "A Boolean parameter", true));
00304 map<string, int> dict; {
00305 dict["Small"] = 0;
00306 dict["Medium"] = 1;
00307 dict["Large"] = 2;
00308 dict["ExtraLarge"] = 3;
00309 }
00310 dd.add(new DDEnum("enum_param", 0, "A size parameter which is edited via an enum", 0, dict));
00311 dd.start(complexCallback);
00312
00313 ros::AsyncSpinner spinner(1);
00314 spinner.start();
00315
00316 dynamic_reconfigure::Reconfigure srv;
00317
00318 dynamic_reconfigure::IntParameter int_param;
00319 int_param.name = "int_param";
00320 int_param.value = 1;
00321 srv.request.config.ints.push_back(int_param);
00322
00323 dynamic_reconfigure::DoubleParameter double_param;
00324 double_param.name = "double_param";
00325 double_param.value = 0.6;
00326 srv.request.config.doubles.push_back(double_param);
00327
00328 dynamic_reconfigure::BoolParameter bool_param;
00329 bool_param.name = "bool_param";
00330 bool_param.value = (unsigned char) false;
00331 srv.request.config.bools.push_back(bool_param);
00332
00333 dynamic_reconfigure::StrParameter string_param;
00334 string_param.name = "str_param";
00335 string_param.value = "Goodbye Home";
00336 srv.request.config.strs.push_back(string_param);
00337
00338 dynamic_reconfigure::StrParameter enum_param;
00339 enum_param.name = "enum_param";
00340 enum_param.value = "ExtraLarge";
00341 srv.request.config.strs.push_back(enum_param);
00342
00343 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00344
00345 bool flag = false;
00346 DDFunc callback = bind(&basicCallback,_1,_2,&flag);
00347 dd.setCallback(callback);
00348 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00349 ASSERT_TRUE(flag);
00350
00351 flag = false;
00352 dd.clearCallback();
00353 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00354 ASSERT_FALSE(flag);
00355 }
00356
00357 class InternalClass {
00358 public:
00359 inline void internalCallback(const DDMap& map, int level) {}
00360 };
00361
00365 TEST(DDynamicReconfigureTest, memberCallbackTest) {
00366 ros::NodeHandle nh("~");
00367 DDynamicReconfigure dd(nh);
00368
00369 dd.start(&InternalClass::internalCallback,new InternalClass);
00370
00371 ros::AsyncSpinner spinner(1);
00372 spinner.start();
00373
00374 dynamic_reconfigure::Reconfigure srv;
00375
00376 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00377 }
00378
00379 void levelCallback(const DDMap&, int level, int *flag) {
00380 *flag = level;
00381 }
00382
00386 TEST(DDynamicReconfigureTest, levelTest) {
00387 ros::NodeHandle nh("~");
00388 int flag = 0;
00389 DDFunc callback = bind(&levelCallback, _1, _2, &flag);
00390
00391 DDynamicReconfigure dd(nh);
00392 int top = (int) random() % 5 + 5;
00393 unsigned int or_sum = 0, next;
00394 for (int i = 1; i < top; i++) {
00395 next = (unsigned int) random();
00396 or_sum |= next;
00397 dd.add(new DDInt((format("param_%d") % i).str(), next,"level_param", 0));
00398 }
00399 dd.start(callback);
00400
00401 ros::AsyncSpinner spinner(1);
00402 spinner.start();
00403
00404 dynamic_reconfigure::Reconfigure srv;
00405 dynamic_reconfigure::IntParameter int_param;
00406 for (int i = 1; i < top; i++) {
00407 int_param.name = (format("param_%d") % i).str();
00408 int_param.value = 1;
00409 srv.request.config.ints.push_back(int_param);
00410 }
00411
00412 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00413 ASSERT_EQ(or_sum, flag);
00414
00415 dd.add(new DDInt("unchanged_param", 1,"unchanged_param", 0));
00416 dynamic_reconfigure::IntParameter unchanged_param;
00417 unchanged_param.name = "unchanged_param";
00418 unchanged_param.value = 1;
00419 srv.request.config.ints.push_back(unchanged_param);
00420
00421 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00422 ASSERT_EQ(1, flag);
00423
00424 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00425 ASSERT_EQ(0, flag);
00426 }
00427
00428 void badCallback(const DDMap&, int) {
00429 std::exception e;
00430 throw e;
00431 }
00432
00436 TEST(DDynamicReconfigureTest, badCallbackTest) {
00437 ros::NodeHandle nh("~");
00438 DDynamicReconfigure dd(nh);
00439 dd.start(badCallback);
00440
00441 ros::AsyncSpinner spinner(1);
00442 spinner.start();
00443
00444 dynamic_reconfigure::Reconfigure srv;
00445
00446 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00447
00448 }
00449
00450 void missingCallback(const DDMap& map, int) {
00451 ASSERT_EQ(map.end(),map.find("int_param"));
00452 ASSERT_EQ(map.end(),map.find("double_param"));
00453 ASSERT_EQ(map.end(),map.find("bool_param"));
00454 ASSERT_EQ(map.end(),map.find("str_param"));
00455 ASSERT_EQ(map.end(),map.find("enum_param"));
00456 }
00457
00461 TEST(DDynamicReconfigureTest, unknownParamTest) {
00462 ros::NodeHandle nh("~");
00463 DDynamicReconfigure dd(nh);
00464 dd.start(missingCallback);
00465
00466 ros::AsyncSpinner spinner(1);
00467 spinner.start();
00468
00469 dynamic_reconfigure::Reconfigure srv;
00470
00471 dynamic_reconfigure::IntParameter int_param;
00472 int_param.name = "int_param";
00473 int_param.value = 1;
00474 srv.request.config.ints.push_back(int_param);
00475
00476 dynamic_reconfigure::DoubleParameter double_param;
00477 double_param.name = "double_param";
00478 double_param.value = 0.6;
00479 srv.request.config.doubles.push_back(double_param);
00480
00481 dynamic_reconfigure::BoolParameter bool_param;
00482 bool_param.name = "bool_param";
00483 bool_param.value = (unsigned char) false;
00484 srv.request.config.bools.push_back(bool_param);
00485
00486 dynamic_reconfigure::StrParameter string_param;
00487 string_param.name = "str_param";
00488 string_param.value = "Goodbye Home";
00489 srv.request.config.strs.push_back(string_param);
00490
00491 dynamic_reconfigure::StrParameter enum_param;
00492 enum_param.name = "enum_param";
00493 enum_param.value = "ExtraLarge";
00494 srv.request.config.strs.push_back(enum_param);
00495
00496 ASSERT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
00497 }
00498
00502 TEST(DDynamicReconfigureTest, streamTest) {
00503 ros::NodeHandle nh("~");
00504 DDynamicReconfigure dd(nh);
00505 DDInt dd_int("int_param", 0, "An Integer parameter", 0, 50, 100);
00506 DDDouble dd_double("double_param", 0, "A double parameter", .5, 0, 1);
00507 DDString dd_string("str_param", 0, "A string parameter", "Hello World");
00508 DDBool dd_bool("bool_param", 0, "A Boolean parameter", true);
00509 dd.add(new DDInt(dd_int));
00510 dd.add(new DDDouble(dd_double));
00511 dd.add(new DDString(dd_string));
00512 dd.add(new DDBool(dd_bool));
00513 map<string, int> dict; {
00514 dict["Small"] = 0;
00515 dict["Medium"] = 1;
00516 dict["Large"] = 2;
00517 dict["ExtraLarge"] = 3;
00518 }
00519 DDEnum dd_enum("enum_param", 0, "A size parameter which is edited via an enum", 0, dict);
00520 dd.add(new DDEnum(dd_enum));
00521
00522 stringstream stream, explicit_stream;
00523 stream << dd;
00524
00525 explicit_stream << "{" << dd_bool << "," << dd_double << "," << dd_enum << "," << dd_int << "," << dd_string << "}";
00526 ASSERT_EQ(explicit_stream.str(),stream.str());
00527 }
00528 }
00529
00530
00531 int main(int argc, char** argv) {
00532 testing::InitGoogleTest(&argc, argv);
00533 ros::init(argc, argv, "ddynamic_reconfigure_test");
00534
00535 srand((unsigned int)random());
00536
00537 return RUN_ALL_TESTS();
00538 }
00539 #pragma clang diagnostic pop