Go to the documentation of this file.00001
00002
00003
00004 #include <ros/ros.h>
00005 #include <gtest/gtest.h>
00006 #include <ddynamic_reconfigure/dd_value.h>
00007 #include <ddynamic_reconfigure/TutorialParams.h>
00008 #include <dynamic_reconfigure/Reconfigure.h>
00009
00010 using namespace ros;
00011 namespace ddynamic_reconfigure {
00012
00016 TEST(DDFullScaleTest, doTest) {
00017
00018 NodeHandle nh;
00019
00020 ServiceClient dynamics = nh.serviceClient<dynamic_reconfigure::Reconfigure>("set_parameters");
00021 int new_int = 2, new_enum = 2;
00022 double new_double = 0.2;
00023 string new_string = "2";
00024 bool new_bool = false;
00025
00026 dynamic_reconfigure::Reconfigure srv;
00027
00028 dynamic_reconfigure::IntParameter int_param;
00029 int_param.name = "int_param";
00030 int_param.value = new_int;
00031 srv.request.config.ints.push_back(int_param);
00032
00033 dynamic_reconfigure::DoubleParameter double_param;
00034 double_param.name = "double_param";
00035 double_param.value = new_double;
00036 srv.request.config.doubles.push_back(double_param);
00037
00038 dynamic_reconfigure::BoolParameter bool_param;
00039 bool_param.name = "bool_param";
00040 bool_param.value = (unsigned char)new_bool;
00041 srv.request.config.bools.push_back(bool_param);
00042
00043 dynamic_reconfigure::StrParameter str_param;
00044 str_param.name = "str_param";
00045 str_param.value = new_string;
00046 srv.request.config.strs.push_back(str_param);
00047
00048 dynamic_reconfigure::IntParameter enum_param;
00049 enum_param.name = "enum_param";
00050 enum_param.value = new_enum;
00051 srv.request.config.ints.push_back(enum_param);
00052
00053 ASSERT_TRUE(dynamics.call(srv));
00054
00055 ServiceClient client = nh.serviceClient<ddynamic_reconfigure::TutorialParams>("get_params");
00056 ddynamic_reconfigure::TutorialParams params;
00057 ASSERT_TRUE(client.call(params));
00058
00059 ASSERT_EQ(new_int,params.response.int_param);
00060 ASSERT_EQ(new_double,params.response.double_param);
00061 ASSERT_EQ(new_string,params.response.str_param);
00062 ASSERT_EQ(new_bool,params.response.bool_param);
00063 ASSERT_EQ(new_enum,params.response.enum_param);
00064 }
00065 }
00066
00067
00068 int main(int argc, char** argv) {
00069 init(argc, argv, "dd_client");
00070 testing::InitGoogleTest(&argc, argv);
00071
00072 srand((unsigned int)random());
00073
00074 return RUN_ALL_TESTS();
00075 }