00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <string>
00037 #include <sstream>
00038 #include <fstream>
00039
00040 #include <gtest/gtest.h>
00041
00042 #include <time.h>
00043 #include <stdlib.h>
00044
00045 #include "ros/ros.h"
00046 #include <ros/param.h>
00047
00048 using namespace ros;
00049
00050 TEST(Params, allParamTypes)
00051 {
00052 std::string string_param;
00053 EXPECT_TRUE( param::get( "string", string_param ) );
00054 EXPECT_TRUE( string_param == "test" );
00055
00056 int int_param = 0;
00057 EXPECT_TRUE( param::get( "int", int_param ) );
00058 EXPECT_TRUE( int_param == 10 );
00059
00060 double double_param = 0.0;
00061 EXPECT_TRUE( param::get( "double", double_param ) );
00062 EXPECT_DOUBLE_EQ( double_param, 10.5 );
00063
00064 bool bool_param = true;
00065 EXPECT_TRUE( param::get( "bool", bool_param ) );
00066 EXPECT_FALSE( bool_param );
00067 }
00068
00069 TEST(Params, setThenGetString)
00070 {
00071 param::set( "test_set_param", std::string("asdf") );
00072 std::string param;
00073 ASSERT_TRUE( param::get( "test_set_param", param ) );
00074 ASSERT_STREQ( "asdf", param.c_str() );
00075 }
00076
00077 TEST(Params, setThenGetStringCached)
00078 {
00079 std::string param;
00080 ASSERT_FALSE( param::getCached( "test_set_param_setThenGetStringCached", param) );
00081
00082 param::set( "test_set_param_setThenGetStringCached", std::string("asdf") );
00083
00084 ASSERT_TRUE( param::getCached( "test_set_param_setThenGetStringCached", param) );
00085 ASSERT_STREQ( "asdf", param.c_str() );
00086 }
00087
00088 TEST(Params, setThenGetStringCachedNodeHandle)
00089 {
00090 NodeHandle nh;
00091 std::string param;
00092 ASSERT_FALSE( nh.getParamCached( "test_set_param_setThenGetStringCachedNodeHandle", param) );
00093
00094 nh.setParam( "test_set_param_setThenGetStringCachedNodeHandle", std::string("asdf") );
00095
00096 ASSERT_TRUE( nh.getParamCached( "test_set_param_setThenGetStringCachedNodeHandle", param) );
00097 ASSERT_STREQ( "asdf", param.c_str() );
00098 }
00099
00100 TEST(Params, setThenGetCString)
00101 {
00102 param::set( "test_set_param", "asdf" );
00103 std::string param;
00104 ASSERT_TRUE( param::get( "test_set_param", param ) );
00105 ASSERT_STREQ( "asdf", param.c_str() );
00106 }
00107
00108 TEST(Params, setThenGetInt)
00109 {
00110 param::set( "test_set_param", 42);
00111 int param;
00112 ASSERT_TRUE( param::get( "test_set_param", param ) );
00113 ASSERT_EQ( 42, param );
00114 }
00115
00116 TEST(Params, unknownParam)
00117 {
00118 std::string param;
00119 ASSERT_FALSE( param::get( "this_param_really_should_not_exist", param ) );
00120 }
00121
00122 TEST(Params, deleteParam)
00123 {
00124 param::set( "test_delete_param", "asdf" );
00125 param::del( "test_delete_param" );
00126 std::string param;
00127 ASSERT_FALSE( param::get( "test_delete_param", param ) );
00128 }
00129
00130 TEST(Params, hasParam)
00131 {
00132 ASSERT_TRUE( param::has( "string" ) );
00133 }
00134
00135 TEST(Params, setIntDoubleGetInt)
00136 {
00137 param::set("test_set_int_as_double", 1);
00138 param::set("test_set_int_as_double", 3.0f);
00139
00140 int i = -1;
00141 ASSERT_TRUE(param::get("test_set_int_as_double", i));
00142 ASSERT_EQ(3, i);
00143 double d = 0.0f;
00144 ASSERT_TRUE(param::get("test_set_int_as_double", d));
00145 ASSERT_EQ(3.0, d);
00146 }
00147
00148 TEST(Params, getIntAsDouble)
00149 {
00150 param::set("int_param", 1);
00151 double d = 0.0;
00152 ASSERT_TRUE(param::get("int_param", d));
00153 ASSERT_EQ(1.0, d);
00154 }
00155
00156 TEST(Params, getDoubleAsInt)
00157 {
00158 param::set("double_param", 2.3);
00159 int i = -1;
00160 ASSERT_TRUE(param::get("double_param", i));
00161 ASSERT_EQ(2, i);
00162
00163 param::set("double_param", 3.8);
00164 i = -1;
00165 ASSERT_TRUE(param::get("double_param", i));
00166 ASSERT_EQ(4, i);
00167 }
00168
00169 TEST(Params, searchParam)
00170 {
00171 std::string ns = "/a/b/c/d/e/f";
00172 std::string result;
00173
00174 param::set("/s_i", 1);
00175 ASSERT_TRUE(param::search(ns, "s_i", result));
00176 ASSERT_STREQ(result.c_str(), "/s_i");
00177 param::del("/s_i");
00178
00179 param::set("/a/b/s_i", 1);
00180 ASSERT_TRUE(param::search(ns, "s_i", result));
00181 ASSERT_STREQ(result.c_str(), "/a/b/s_i");
00182 param::del("/a/b/s_i");
00183
00184 param::set("/a/b/c/d/e/f/s_i", 1);
00185 ASSERT_TRUE(param::search(ns, "s_i", result));
00186 ASSERT_STREQ(result.c_str(), "/a/b/c/d/e/f/s_i");
00187 param::del("/a/b/c/d/e/f/s_i");
00188
00189 bool cont = true;
00190 while (!cont)
00191 {
00192 ros::WallDuration(0.1).sleep();
00193 }
00194
00195 ASSERT_FALSE(param::search(ns, "s_j", result));
00196 }
00197
00198 TEST(Params, searchParamNodeHandle)
00199 {
00200 NodeHandle n("/a/b/c/d/e/f");
00201 std::string result;
00202
00203 n.setParam("/s_i", 1);
00204 ASSERT_TRUE(n.searchParam("s_i", result));
00205 ASSERT_STREQ(result.c_str(), "/s_i");
00206 n.deleteParam("/s_i");
00207
00208 n.setParam("/a/b/s_i", 1);
00209 ASSERT_TRUE(n.searchParam("s_i", result));
00210 ASSERT_STREQ(result.c_str(), "/a/b/s_i");
00211 n.deleteParam("/a/b/s_i");
00212
00213 n.setParam("/a/b/c/d/e/f/s_i", 1);
00214 ASSERT_TRUE(n.searchParam("s_i", result));
00215 ASSERT_STREQ(result.c_str(), "/a/b/c/d/e/f/s_i");
00216 n.deleteParam("/a/b/c/d/e/f/s_i");
00217
00218 ASSERT_FALSE(n.searchParam("s_j", result));
00219 }
00220
00221 TEST(Params, searchParamNodeHandleWithRemapping)
00222 {
00223 M_string remappings;
00224 remappings["s_c"] = "s_b";
00225 NodeHandle n("/a/b/c/d/e/f", remappings);
00226 std::string result;
00227
00228 n.setParam("/s_c", 1);
00229 ASSERT_FALSE(n.searchParam("s_c", result));
00230 n.setParam("/s_b", 1);
00231 ASSERT_TRUE(n.searchParam("s_c", result));
00232 }
00233
00234
00235 TEST(Params, getMissingXmlRpcValueParameterCachedTwice)
00236 {
00237 XmlRpc::XmlRpcValue v;
00238 ASSERT_FALSE(ros::param::getCached("invalid_xmlrpcvalue_param", v));
00239 ASSERT_FALSE(ros::param::getCached("invalid_xmlrpcvalue_param", v));
00240 }
00241
00242
00243 TEST(Params, doublePrecision)
00244 {
00245 ros::param::set("bar", 0.123456789123456789);
00246 double d;
00247 ASSERT_TRUE(ros::param::get("bar", d));
00248 EXPECT_DOUBLE_EQ(d, 0.12345678912345678);
00249 }
00250
00251 int
00252 main(int argc, char** argv)
00253 {
00254 testing::InitGoogleTest(&argc, argv);
00255 ros::init( argc, argv, "params" );
00256
00257
00258 return RUN_ALL_TESTS();
00259 }