40 #include <gtest/gtest.h> 50 TEST(Params, allParamTypes)
52 std::string string_param;
53 EXPECT_TRUE(
param::get(
"string", string_param ) );
54 EXPECT_TRUE( string_param ==
"test" );
58 EXPECT_TRUE( int_param == 10 );
60 double double_param = 0.0;
61 EXPECT_TRUE(
param::get(
"double", double_param ) );
62 EXPECT_DOUBLE_EQ( double_param, 10.5 );
64 bool bool_param =
true;
65 EXPECT_TRUE(
param::get(
"bool", bool_param ) );
66 EXPECT_FALSE( bool_param );
69 TEST(Params, setThenGetString)
71 param::set(
"test_set_param", std::string(
"asdf") );
73 ASSERT_TRUE(
param::get(
"test_set_param", param ) );
74 ASSERT_STREQ(
"asdf", param.c_str() );
81 TEST(Params, setThenGetStringCached)
84 ASSERT_FALSE(
param::getCached(
"test_set_param_setThenGetStringCached", param) );
86 param::set(
"test_set_param_setThenGetStringCached", std::string(
"asdf") );
88 ASSERT_TRUE(
param::getCached(
"test_set_param_setThenGetStringCached", param) );
89 ASSERT_STREQ(
"asdf", param.c_str() );
92 TEST(Params, setThenGetStringCachedNodeHandle)
96 ASSERT_FALSE( nh.
getParamCached(
"test_set_param_setThenGetStringCachedNodeHandle", param) );
98 nh.
setParam(
"test_set_param_setThenGetStringCachedNodeHandle", std::string(
"asdf") );
100 ASSERT_TRUE( nh.
getParamCached(
"test_set_param_setThenGetStringCachedNodeHandle", param) );
101 ASSERT_STREQ(
"asdf", param.c_str() );
104 TEST(Params, setThenGetNamespaceCached)
106 std::string stringParam;
108 const std::string ns =
"test_set_param_setThenGetStringCached2";
113 ASSERT_STREQ(
"a", stringParam.c_str());
117 ASSERT_STREQ(
"b", stringParam.c_str());
119 ASSERT_TRUE(structParam.
hasMember(
"foo"));
120 ASSERT_STREQ(
"b", static_cast<std::string>(structParam[
"foo"]).c_str());
123 TEST(Params, setThenGetCString)
127 ASSERT_TRUE(
param::get(
"test_set_param", param ) );
128 ASSERT_STREQ(
"asdf", param.c_str() );
135 ASSERT_TRUE(
param::get(
"test_set_param", param ) );
136 ASSERT_EQ( 42, param );
145 ASSERT_FALSE(
param::get(
"this_param_really_should_not_exist", param ) );
153 ASSERT_FALSE(
param::get(
"test_delete_param", param ) );
161 TEST(Params, setIntDoubleGetInt)
167 ASSERT_TRUE(
param::get(
"test_set_int_as_double", i));
170 ASSERT_TRUE(
param::get(
"test_set_int_as_double", d));
197 std::string ns =
"/a/b/c/d/e/f";
202 ASSERT_STREQ(result.c_str(),
"/s_i");
207 ASSERT_STREQ(result.c_str(),
"/a/b/s_i");
212 ASSERT_STREQ(result.c_str(),
"/a/b/c/d/e/f/s_i");
224 TEST(Params, searchParamNodeHandle)
231 ASSERT_STREQ(result.c_str(),
"/s_i");
236 ASSERT_STREQ(result.c_str(),
"/a/b/s_i");
241 ASSERT_STREQ(result.c_str(),
"/a/b/c/d/e/f/s_i");
247 TEST(Params, searchParamNodeHandleWithRemapping)
250 remappings[
"s_c"] =
"s_b";
261 TEST(Params, getMissingXmlRpcValueParameterCachedTwice)
274 EXPECT_DOUBLE_EQ(d, 0.12345678912345678);
283 TEST(Params, vectorStringParam)
285 const std::string param_name =
"vec_str_param";
288 vec_s.push_back(
"foo");
289 vec_s.push_back(
"bar");
290 vec_s.push_back(
"baz");
311 TEST(Params, vectorDoubleParam)
313 const std::string param_name =
"vec_double_param";
316 vec_d.push_back(-0.123456789);
318 vec_d.push_back(3.01);
319 vec_d.push_back(7.01);
336 const std::string param_name =
"vec_float_param";
339 vec_f.push_back(-0.123456789);
340 vec_f.push_back(0.0);
342 vec_f.push_back(3.01);
351 ASSERT_EQ(
vec_b[0],
true);
352 ASSERT_EQ(
vec_b[1],
false);
362 const std::string param_name =
"vec_int_param";
367 vec_i.push_back(1337);
377 ASSERT_EQ(
vec_b[0],
true);
378 ASSERT_EQ(
vec_b[1],
false);
388 const std::string param_name =
"vec_bool_param";
391 vec_b.push_back(
true);
392 vec_b.push_back(
false);
393 vec_b.push_back(
true);
394 vec_b.push_back(
true);
403 ASSERT_EQ(
vec_i[0],1);
404 ASSERT_EQ(
vec_i[1],0);
420 const std::string param_name =
"map_str_param";
423 map_s[
"a"] =
"apple";
424 map_s[
"b"] =
"blueberry";
425 map_s[
"c"] =
"carrot";
442 const std::string param_name =
"map_double_param";
446 map_d[
"b"] = -0.123456789;
447 map_d[
"c"] = 123456789;
464 const std::string param_name =
"map_float_param";
468 map_f[
"b"] = -0.123456789;
469 map_f[
"c"] = 123456789;
486 const std::string param_name =
"map_int_param";
508 const std::string param_name =
"map_bool_param";
522 ASSERT_EQ(
map_i[
"a"],1);
523 ASSERT_EQ(
map_i[
"b"],0);
531 TEST(Params, paramTemplateFunction)
533 EXPECT_EQ( param::param<std::string>(
"string",
"" ),
"test" );
534 EXPECT_EQ( param::param<std::string>(
"gnirts",
"test" ),
"test" );
536 EXPECT_EQ( param::param<int>(
"int", 0 ), 10 );
537 EXPECT_EQ( param::param<int>(
"tni", 10 ), 10 );
539 EXPECT_DOUBLE_EQ( param::param<double>(
"double", 0.0 ), 10.5 );
540 EXPECT_DOUBLE_EQ( param::param<double>(
"elbuod", 10.5 ), 10.5 );
542 EXPECT_EQ( param::param<bool>(
"bool",
true ),
false );
543 EXPECT_EQ( param::param<bool>(
"loob",
true ),
true );
546 TEST(Params, paramNodeHandleTemplateFunction)
550 EXPECT_EQ( nh.
param<std::string>(
"string",
"" ),
"test" );
551 EXPECT_EQ( nh.
param<std::string>(
"gnirts",
"test" ),
"test" );
553 EXPECT_EQ( nh.
param<
int>(
"int", 0 ), 10 );
554 EXPECT_EQ( nh.
param<
int>(
"tni", 10 ), 10 );
556 EXPECT_DOUBLE_EQ( nh.
param<
double>(
"double", 0.0 ), 10.5 );
557 EXPECT_DOUBLE_EQ( nh.
param<
double>(
"elbuod", 10.5 ), 10.5 );
559 EXPECT_EQ( nh.
param<
bool>(
"bool",
true ),
false );
560 EXPECT_EQ( nh.
param<
bool>(
"loob",
true ),
true );
564 std::vector<std::string> test_params;
566 EXPECT_LT(10, test_params.size());
569 TEST(Params, getParamCachedSetParamLoop) {
571 const std::string name =
"changeable_int";
572 for (
int i = 0; i < 100; i++) {
583 testing::InitGoogleTest(&argc, argv);
587 return RUN_ALL_TESTS();
TEST(Params, allParamTypes)
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
std::vector< std::string > vec_s
std::map< std::string, double > map_d2
std::vector< bool > vec_b2
std::map< std::string, bool > map_b2
bool getParamCached(const std::string &key, std::string &s) const
std::map< std::string, bool > map_b
bool deleteParam(const std::string &key) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< float > vec_f
std::vector< double > vec_d
Type const & getType() const
std::map< std::string, std::string > map_s
std::vector< float > vec_f2
std::map< std::string, std::string > M_string
std::map< std::string, std::string > map_s2
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::map< std::string, float > map_f
std::map< std::string, double > map_d
ROSCPP_DECL bool get(const std::string &key, std::string &s)
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::map< std::string, float > map_f2
ROSCPP_DECL bool has(const std::string &key)
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
std::map< std::string, int > map_i
ROSCPP_DECL bool del(const std::string &key)
bool hasMember(const std::string &name) const
std::vector< double > vec_d2
std::vector< bool > vec_b
std::vector< std::string > vec_s2
std::vector< int > vec_i2
std::map< std::string, int > map_i2
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
int main(int argc, char **argv)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const