00001 #include <gtest/gtest.h>
00002 #include <ros/ros.h>
00003 #include <rosparam_handler/DefaultsParameters.h>
00004
00005 typedef rosparam_handler::DefaultsParameters ParamType;
00006 typedef rosparam_handler::DefaultsConfig ConfigType;
00007
00008 TEST(RosparamHandler, Defaults) {
00009 ParamType testParams(ros::NodeHandle("~"));
00010 ASSERT_NO_THROW(testParams.fromParamServer());
00011
00012 ASSERT_EQ(1, testParams.int_param_w_default);
00013 ASSERT_DOUBLE_EQ(1.1, testParams.double_param_w_default);
00014 ASSERT_EQ("Hello World", testParams.str_param_w_default);
00015 ASSERT_EQ(true, testParams.bool_param_w_default);
00016
00017 ASSERT_EQ(std::vector<int>({1, 2, 3}), testParams.vector_int_param_w_default);
00018 ASSERT_EQ(std::vector<double>({1.1, 1.2, 1.3}), testParams.vector_double_param_w_default);
00019 ASSERT_EQ(std::vector<bool>({false, true}), testParams.vector_bool_param_w_default);
00020 ASSERT_EQ(std::vector<std::string>({"Hello", "World"}), testParams.vector_string_param_w_default);
00021
00022 std::map<std::string, std::string> tmp{{"Hello", "World"}};
00023 ASSERT_EQ(tmp, testParams.map_param_w_default);
00024
00025 ASSERT_EQ(1, testParams.enum_param_w_default);
00026 }
00027
00028 TEST(RosparamHandler, DefaultsOnParamServer) {
00029 ros::NodeHandle nh("~");
00030 ParamType testParams(nh);
00031 ASSERT_NO_THROW(testParams.fromParamServer());
00032
00033
00034 {
00035 int int_param;
00036 ASSERT_TRUE(nh.getParam("int_param_w_default", int_param));
00037 ASSERT_EQ(int_param, testParams.int_param_w_default);
00038 }
00039 {
00040 double double_param;
00041 ASSERT_TRUE(nh.getParam("double_param_w_default", double_param));
00042 EXPECT_EQ(double_param, testParams.double_param_w_default);
00043 }
00044 {
00045 bool bool_param;
00046 ASSERT_TRUE(nh.getParam("bool_param_w_default", bool_param));
00047 EXPECT_EQ(bool_param, testParams.bool_param_w_default);
00048 }
00049 {
00050 std::string string_param;
00051 ASSERT_TRUE(nh.getParam("str_param_w_default", string_param));
00052 EXPECT_EQ(string_param, testParams.str_param_w_default);
00053 }
00054 {
00055 std::vector<int> vector_int_param;
00056 ASSERT_TRUE(nh.getParam("vector_int_param_w_default", vector_int_param));
00057 EXPECT_EQ(vector_int_param, testParams.vector_int_param_w_default);
00058 }
00059 {
00060 std::vector<double> vector_double_param;
00061 ASSERT_TRUE(nh.getParam("vector_double_param_w_default", vector_double_param));
00062 EXPECT_EQ(vector_double_param, testParams.vector_double_param_w_default);
00063 }
00064 {
00065 std::vector<bool> vector_bool_param;
00066 ASSERT_TRUE(nh.getParam("vector_bool_param_w_default", vector_bool_param));
00067 EXPECT_EQ(vector_bool_param, testParams.vector_bool_param_w_default);
00068 }
00069 {
00070 std::vector<std::string> vector_string_param;
00071 ASSERT_TRUE(nh.getParam("vector_string_param_w_default", vector_string_param));
00072 EXPECT_EQ(vector_string_param, testParams.vector_string_param_w_default);
00073 }
00074 {
00075 std::map<std::string, std::string> map_param_w_default;
00076 ASSERT_TRUE(nh.getParam("map_param_w_default", map_param_w_default));
00077 EXPECT_EQ(map_param_w_default, testParams.map_param_w_default);
00078 }
00079 {
00080 int enum_param;
00081 ASSERT_TRUE(nh.getParam("enum_param_w_default", enum_param));
00082 EXPECT_EQ(enum_param, testParams.enum_param_w_default);
00083 }
00084 }
00085
00086 TEST(RosparamHandler, SetParamOnServer) {
00087 ros::NodeHandle nh("~");
00088 ParamType testParams(nh);
00089 ASSERT_NO_THROW(testParams.fromParamServer());
00090
00091 testParams.int_param_w_default = 2;
00092 testParams.double_param_w_default = 2.2;
00093 testParams.str_param_w_default = "World Hello";
00094 testParams.bool_param_w_default = false;
00095 testParams.vector_int_param_w_default = std::vector<int>{3, 2, 1};
00096 testParams.vector_double_param_w_default = std::vector<double>{1.3, 1.2, 1.2};
00097 testParams.vector_bool_param_w_default = std::vector<bool>{true, false};
00098 testParams.vector_string_param_w_default = std::vector<std::string>{"World", "Hello"};
00099 testParams.map_param_w_default = std::map<std::string, std::string>{{"World", "Hello"}};
00100 testParams.enum_param_w_default = 2;
00101
00102 testParams.toParamServer();
00103
00104
00105 {
00106 int int_param;
00107 ASSERT_TRUE(nh.getParam("int_param_w_default", int_param));
00108 ASSERT_EQ(int_param, testParams.int_param_w_default);
00109 }
00110 {
00111 double double_param;
00112 ASSERT_TRUE(nh.getParam("double_param_w_default", double_param));
00113 EXPECT_EQ(double_param, testParams.double_param_w_default);
00114 }
00115 {
00116 bool bool_param;
00117 ASSERT_TRUE(nh.getParam("bool_param_w_default", bool_param));
00118 EXPECT_EQ(bool_param, testParams.bool_param_w_default);
00119 }
00120 {
00121 std::string string_param;
00122 ASSERT_TRUE(nh.getParam("str_param_w_default", string_param));
00123 EXPECT_EQ(string_param, testParams.str_param_w_default);
00124 }
00125 {
00126 std::vector<int> vector_int_param;
00127 ASSERT_TRUE(nh.getParam("vector_int_param_w_default", vector_int_param));
00128 EXPECT_EQ(vector_int_param, testParams.vector_int_param_w_default);
00129 }
00130 {
00131 std::vector<double> vector_double_param;
00132 ASSERT_TRUE(nh.getParam("vector_double_param_w_default", vector_double_param));
00133 EXPECT_EQ(vector_double_param, testParams.vector_double_param_w_default);
00134 }
00135 {
00136 std::vector<bool> vector_bool_param;
00137 ASSERT_TRUE(nh.getParam("vector_bool_param_w_default", vector_bool_param));
00138 EXPECT_EQ(vector_bool_param, testParams.vector_bool_param_w_default);
00139 }
00140 {
00141 std::vector<std::string> vector_string_param;
00142 ASSERT_TRUE(nh.getParam("vector_string_param_w_default", vector_string_param));
00143 EXPECT_EQ(vector_string_param, testParams.vector_string_param_w_default);
00144 }
00145 {
00146 std::map<std::string, std::string> map_param_w_default;
00147 ASSERT_TRUE(nh.getParam("map_param_w_default", map_param_w_default));
00148 EXPECT_EQ(map_param_w_default, testParams.map_param_w_default);
00149 }
00150 {
00151 int enum_param;
00152 ASSERT_TRUE(nh.getParam("enum_param_w_default", enum_param));
00153 EXPECT_EQ(enum_param, testParams.enum_param_w_default);
00154 }
00155 }