params.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /* Author: Josh Faust */
00031 
00032 /*
00033  * Test parameters
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   XmlRpc::XmlRpcValue v;
00077   param::get("test_set_param", v);
00078   ASSERT_EQ(v.getType(), XmlRpc::XmlRpcValue::TypeString);
00079 }
00080 
00081 TEST(Params, setThenGetStringCached)
00082 {
00083   std::string param;
00084   ASSERT_FALSE( param::getCached( "test_set_param_setThenGetStringCached", param) );
00085 
00086   param::set( "test_set_param_setThenGetStringCached", std::string("asdf") );
00087 
00088   ASSERT_TRUE( param::getCached( "test_set_param_setThenGetStringCached", param) );
00089   ASSERT_STREQ( "asdf", param.c_str() );
00090 }
00091 
00092 TEST(Params, setThenGetStringCachedNodeHandle)
00093 {
00094         NodeHandle nh;
00095   std::string param;
00096   ASSERT_FALSE( nh.getParamCached( "test_set_param_setThenGetStringCachedNodeHandle", param) );
00097 
00098   nh.setParam( "test_set_param_setThenGetStringCachedNodeHandle", std::string("asdf") );
00099 
00100   ASSERT_TRUE( nh.getParamCached( "test_set_param_setThenGetStringCachedNodeHandle", param) );
00101   ASSERT_STREQ( "asdf", param.c_str() );
00102 }
00103 
00104 TEST(Params, setThenGetCString)
00105 {
00106   param::set( "test_set_param", "asdf" );
00107   std::string param;
00108   ASSERT_TRUE( param::get( "test_set_param", param ) );
00109   ASSERT_STREQ( "asdf", param.c_str() );
00110 }
00111 
00112 TEST(Params, setThenGetInt)
00113 {
00114   param::set( "test_set_param", 42);
00115   int param;
00116   ASSERT_TRUE( param::get( "test_set_param", param ) );
00117   ASSERT_EQ( 42, param );
00118   XmlRpc::XmlRpcValue v;
00119   param::get("test_set_param", v);
00120   ASSERT_EQ(v.getType(), XmlRpc::XmlRpcValue::TypeInt);
00121 }
00122 
00123 TEST(Params, unknownParam)
00124 {
00125   std::string param;
00126   ASSERT_FALSE( param::get( "this_param_really_should_not_exist", param ) );
00127 }
00128 
00129 TEST(Params, deleteParam)
00130 {
00131   param::set( "test_delete_param", "asdf" );
00132   param::del( "test_delete_param" );
00133   std::string param;
00134   ASSERT_FALSE( param::get( "test_delete_param", param ) );
00135 }
00136 
00137 TEST(Params, hasParam)
00138 {
00139   ASSERT_TRUE( param::has( "string" ) );
00140 }
00141 
00142 TEST(Params, setIntDoubleGetInt)
00143 {
00144   param::set("test_set_int_as_double", 1);
00145   param::set("test_set_int_as_double", 3.0f);
00146 
00147   int i = -1;
00148   ASSERT_TRUE(param::get("test_set_int_as_double", i));
00149   ASSERT_EQ(3, i);
00150   double d = 0.0f;
00151   ASSERT_TRUE(param::get("test_set_int_as_double", d));
00152   ASSERT_EQ(3.0, d);
00153 }
00154 
00155 TEST(Params, getIntAsDouble)
00156 {
00157   param::set("int_param", 1);
00158   double d = 0.0;
00159   ASSERT_TRUE(param::get("int_param", d));
00160   ASSERT_EQ(1.0, d);
00161 }
00162 
00163 TEST(Params, getDoubleAsInt)
00164 {
00165   param::set("double_param", 2.3);
00166   int i = -1;
00167   ASSERT_TRUE(param::get("double_param", i));
00168   ASSERT_EQ(2, i);
00169 
00170   param::set("double_param", 3.8);
00171   i = -1;
00172   ASSERT_TRUE(param::get("double_param", i));
00173   ASSERT_EQ(4, i);
00174 }
00175 
00176 TEST(Params, searchParam)
00177 {
00178   std::string ns = "/a/b/c/d/e/f";
00179   std::string result;
00180 
00181   param::set("/s_i", 1);
00182   ASSERT_TRUE(param::search(ns, "s_i", result));
00183   ASSERT_STREQ(result.c_str(), "/s_i");
00184   param::del("/s_i");
00185 
00186   param::set("/a/b/s_i", 1);
00187   ASSERT_TRUE(param::search(ns, "s_i", result));
00188   ASSERT_STREQ(result.c_str(), "/a/b/s_i");
00189   param::del("/a/b/s_i");
00190 
00191   param::set("/a/b/c/d/e/f/s_i", 1);
00192   ASSERT_TRUE(param::search(ns, "s_i", result));
00193   ASSERT_STREQ(result.c_str(), "/a/b/c/d/e/f/s_i");
00194   param::del("/a/b/c/d/e/f/s_i");
00195 
00196   bool cont = true;
00197   while (!cont)
00198   {
00199         ros::WallDuration(0.1).sleep();
00200   }
00201 
00202   ASSERT_FALSE(param::search(ns, "s_j", result));
00203 }
00204 
00205 TEST(Params, searchParamNodeHandle)
00206 {
00207   NodeHandle n("/a/b/c/d/e/f");
00208   std::string result;
00209 
00210   n.setParam("/s_i", 1);
00211   ASSERT_TRUE(n.searchParam("s_i", result));
00212   ASSERT_STREQ(result.c_str(), "/s_i");
00213   n.deleteParam("/s_i");
00214 
00215   n.setParam("/a/b/s_i", 1);
00216   ASSERT_TRUE(n.searchParam("s_i", result));
00217   ASSERT_STREQ(result.c_str(), "/a/b/s_i");
00218   n.deleteParam("/a/b/s_i");
00219 
00220   n.setParam("/a/b/c/d/e/f/s_i", 1);
00221   ASSERT_TRUE(n.searchParam("s_i", result));
00222   ASSERT_STREQ(result.c_str(), "/a/b/c/d/e/f/s_i");
00223   n.deleteParam("/a/b/c/d/e/f/s_i");
00224 
00225   ASSERT_FALSE(n.searchParam("s_j", result));
00226 }
00227 
00228 TEST(Params, searchParamNodeHandleWithRemapping)
00229 {
00230   M_string remappings;
00231   remappings["s_c"] = "s_b";
00232   NodeHandle n("/a/b/c/d/e/f", remappings);
00233   std::string result;
00234 
00235   n.setParam("/s_c", 1);
00236   ASSERT_FALSE(n.searchParam("s_c", result));
00237   n.setParam("/s_b", 1);
00238   ASSERT_TRUE(n.searchParam("s_c", result));
00239 }
00240 
00241 // See ROS ticket #2381
00242 TEST(Params, getMissingXmlRpcValueParameterCachedTwice)
00243 {
00244   XmlRpc::XmlRpcValue v;
00245   ASSERT_FALSE(ros::param::getCached("invalid_xmlrpcvalue_param", v));
00246   ASSERT_FALSE(ros::param::getCached("invalid_xmlrpcvalue_param", v));
00247 }
00248 
00249 // See ROS ticket #2353
00250 TEST(Params, doublePrecision)
00251 {
00252   ros::param::set("bar", 0.123456789123456789);
00253   double d;
00254   ASSERT_TRUE(ros::param::get("bar", d));
00255   EXPECT_DOUBLE_EQ(d, 0.12345678912345678);
00256 }
00257 
00258 std::vector<std::string> vec_s, vec_s2;
00259 std::vector<double> vec_d, vec_d2;
00260 std::vector<float> vec_f, vec_f2;
00261 std::vector<int> vec_i, vec_i2;
00262 std::vector<bool> vec_b, vec_b2;
00263 
00264 TEST(Params, vectorStringParam)
00265 {
00266   const std::string param_name = "vec_str_param";
00267 
00268   vec_s.clear();
00269   vec_s.push_back("foo");
00270   vec_s.push_back("bar");
00271   vec_s.push_back("baz");
00272 
00273   ros::param::set(param_name, vec_s);
00274 
00275   ASSERT_FALSE(ros::param::get(param_name, vec_d));
00276   ASSERT_FALSE(ros::param::get(param_name, vec_f));
00277   ASSERT_FALSE(ros::param::get(param_name, vec_i));
00278   ASSERT_FALSE(ros::param::get(param_name, vec_b));
00279 
00280   ASSERT_TRUE(ros::param::get(param_name, vec_s2));
00281 
00282   ASSERT_EQ(vec_s.size(), vec_s2.size());
00283   ASSERT_TRUE(std::equal(vec_s.begin(), vec_s.end(), vec_s2.begin()));
00284 
00285   // Test empty vector
00286   vec_s.clear();
00287   ros::param::set(param_name, vec_s);
00288   ASSERT_TRUE(ros::param::get(param_name, vec_s2));
00289   ASSERT_EQ(vec_s.size(), vec_s2.size());
00290 }
00291 
00292 TEST(Params, vectorDoubleParam)
00293 {
00294   const std::string param_name = "vec_double_param";
00295 
00296   vec_d.clear();
00297   vec_d.push_back(-0.123456789);
00298   vec_d.push_back(3);
00299   vec_d.push_back(3.01);
00300   vec_d.push_back(7.01);
00301 
00302   ros::param::set(param_name, vec_d);
00303 
00304   ASSERT_FALSE(ros::param::get(param_name, vec_s));
00305   ASSERT_TRUE(ros::param::get(param_name, vec_i));
00306   ASSERT_TRUE(ros::param::get(param_name, vec_b));
00307   ASSERT_TRUE(ros::param::get(param_name, vec_f));
00308 
00309   ASSERT_TRUE(ros::param::get(param_name, vec_d2));
00310 
00311   ASSERT_EQ(vec_d.size(), vec_d2.size());
00312   ASSERT_TRUE(std::equal(vec_d.begin(), vec_d.end(), vec_d2.begin()));
00313 }
00314 
00315 TEST(Params, vectorFloatParam)
00316 {
00317   const std::string param_name = "vec_float_param";
00318 
00319   vec_f.clear();
00320   vec_f.push_back(-0.123456789);
00321   vec_f.push_back(0.0);
00322   vec_f.push_back(3);
00323   vec_f.push_back(3.01);
00324 
00325   ros::param::set(param_name, vec_f);
00326 
00327   ASSERT_FALSE(ros::param::get(param_name, vec_s));
00328   ASSERT_TRUE(ros::param::get(param_name, vec_i));
00329   ASSERT_TRUE(ros::param::get(param_name, vec_b));
00330   ASSERT_TRUE(ros::param::get(param_name, vec_d));
00331 
00332   ASSERT_EQ(vec_b[0],true);
00333   ASSERT_EQ(vec_b[1],false);
00334 
00335   ASSERT_TRUE(ros::param::get(param_name, vec_f2));
00336 
00337   ASSERT_EQ(vec_f.size(), vec_f2.size());
00338   ASSERT_TRUE(std::equal(vec_f.begin(), vec_f.end(), vec_f2.begin()));
00339 }
00340 
00341 TEST(Params, vectorIntParam)
00342 {
00343   const std::string param_name = "vec_int_param";
00344 
00345   vec_i.clear();
00346   vec_i.push_back(-1);
00347   vec_i.push_back(0);
00348   vec_i.push_back(1337);
00349   vec_i.push_back(2);
00350 
00351   ros::param::set(param_name, vec_i);
00352 
00353   ASSERT_FALSE(ros::param::get(param_name, vec_s));
00354   ASSERT_TRUE(ros::param::get(param_name, vec_d));
00355   ASSERT_TRUE(ros::param::get(param_name, vec_f));
00356   ASSERT_TRUE(ros::param::get(param_name, vec_b));
00357 
00358   ASSERT_EQ(vec_b[0],true);
00359   ASSERT_EQ(vec_b[1],false);
00360 
00361   ASSERT_TRUE(ros::param::get(param_name, vec_i2));
00362 
00363   ASSERT_EQ(vec_i.size(), vec_i2.size());
00364   ASSERT_TRUE(std::equal(vec_i.begin(), vec_i.end(), vec_i2.begin()));
00365 }
00366 
00367 TEST(Params, vectorBoolParam)
00368 {
00369   const std::string param_name = "vec_bool_param";
00370 
00371   vec_b.clear();
00372   vec_b.push_back(true);
00373   vec_b.push_back(false);
00374   vec_b.push_back(true);
00375   vec_b.push_back(true);
00376 
00377   ros::param::set(param_name, vec_b);
00378 
00379   ASSERT_FALSE(ros::param::get(param_name, vec_s));
00380   ASSERT_TRUE(ros::param::get(param_name, vec_d));
00381   ASSERT_TRUE(ros::param::get(param_name, vec_f));
00382   ASSERT_TRUE(ros::param::get(param_name, vec_i));
00383 
00384   ASSERT_EQ(vec_i[0],1);
00385   ASSERT_EQ(vec_i[1],0);
00386 
00387   ASSERT_TRUE(ros::param::get(param_name, vec_b2));
00388 
00389   ASSERT_EQ(vec_b.size(), vec_b2.size());
00390   ASSERT_TRUE(std::equal(vec_b.begin(), vec_b.end(), vec_b2.begin()));
00391 }
00392 
00393 std::map<std::string,std::string> map_s, map_s2;
00394 std::map<std::string,double> map_d, map_d2;
00395 std::map<std::string,float> map_f, map_f2;
00396 std::map<std::string,int> map_i, map_i2;
00397 std::map<std::string,bool> map_b, map_b2;
00398 
00399 TEST(Params, mapStringParam)
00400 {
00401   const std::string param_name = "map_str_param";
00402 
00403   map_s.clear();
00404   map_s["a"] = "apple";
00405   map_s["b"] = "blueberry";
00406   map_s["c"] = "carrot";
00407 
00408   ros::param::set(param_name, map_s);
00409 
00410   ASSERT_FALSE(ros::param::get(param_name, map_d));
00411   ASSERT_FALSE(ros::param::get(param_name, map_f));
00412   ASSERT_FALSE(ros::param::get(param_name, map_i));
00413   ASSERT_FALSE(ros::param::get(param_name, map_b));
00414 
00415   ASSERT_TRUE(ros::param::get(param_name, map_s2));
00416 
00417   ASSERT_EQ(map_s.size(), map_s2.size());
00418   ASSERT_TRUE(std::equal(map_s.begin(), map_s.end(), map_s2.begin()));
00419 }
00420 
00421 TEST(Params, mapDoubleParam)
00422 {
00423   const std::string param_name = "map_double_param";
00424 
00425   map_d.clear();
00426   map_d["a"] = 0.0;
00427   map_d["b"] = -0.123456789;
00428   map_d["c"] = 123456789;
00429 
00430   ros::param::set(param_name, map_d);
00431 
00432   ASSERT_FALSE(ros::param::get(param_name, map_s));
00433   ASSERT_TRUE(ros::param::get(param_name, map_f));
00434   ASSERT_TRUE(ros::param::get(param_name, map_i));
00435   ASSERT_TRUE(ros::param::get(param_name, map_b));
00436 
00437   ASSERT_TRUE(ros::param::get(param_name, map_d2));
00438 
00439   ASSERT_EQ(map_d.size(), map_d2.size());
00440   ASSERT_TRUE(std::equal(map_d.begin(), map_d.end(), map_d2.begin()));
00441 }
00442 
00443 TEST(Params, mapFloatParam)
00444 {
00445   const std::string param_name = "map_float_param";
00446 
00447   map_f.clear();
00448   map_f["a"] = 0.0;
00449   map_f["b"] = -0.123456789;
00450   map_f["c"] = 123456789;
00451 
00452   ros::param::set(param_name, map_f);
00453 
00454   ASSERT_FALSE(ros::param::get(param_name, map_s));
00455   ASSERT_TRUE(ros::param::get(param_name, map_d));
00456   ASSERT_TRUE(ros::param::get(param_name, map_i));
00457   ASSERT_TRUE(ros::param::get(param_name, map_b));
00458 
00459   ASSERT_TRUE(ros::param::get(param_name, map_f2));
00460 
00461   ASSERT_EQ(map_f.size(), map_f2.size());
00462   ASSERT_TRUE(std::equal(map_f.begin(), map_f.end(), map_f2.begin()));
00463 }
00464 
00465 TEST(Params, mapIntParam)
00466 {
00467   const std::string param_name = "map_int_param";
00468 
00469   map_i.clear();
00470   map_i["a"] = 0;
00471   map_i["b"] = -1;
00472   map_i["c"] = 1337;
00473 
00474   ros::param::set(param_name, map_i);
00475 
00476   ASSERT_FALSE(ros::param::get(param_name, map_s));
00477   ASSERT_TRUE(ros::param::get(param_name, map_d));
00478   ASSERT_TRUE(ros::param::get(param_name, map_f));
00479   ASSERT_TRUE(ros::param::get(param_name, map_b));
00480 
00481   ASSERT_TRUE(ros::param::get(param_name, map_i2));
00482 
00483   ASSERT_EQ(map_i.size(), map_i2.size());
00484   ASSERT_TRUE(std::equal(map_i.begin(), map_i.end(), map_i2.begin()));
00485 }
00486 
00487 TEST(Params, mapBoolParam)
00488 {
00489   const std::string param_name = "map_bool_param";
00490 
00491   map_b.clear();
00492   map_b["a"] = true;
00493   map_b["b"] = false;
00494   map_b["c"] = true;
00495 
00496   ros::param::set(param_name, map_b);
00497 
00498   ASSERT_FALSE(ros::param::get(param_name, map_s));
00499   ASSERT_TRUE(ros::param::get(param_name, map_d));
00500   ASSERT_TRUE(ros::param::get(param_name, map_f));
00501   ASSERT_TRUE(ros::param::get(param_name, map_i));
00502 
00503   ASSERT_EQ(map_i["a"],1);
00504   ASSERT_EQ(map_i["b"],0);
00505 
00506   ASSERT_TRUE(ros::param::get(param_name, map_b2));
00507 
00508   ASSERT_EQ(map_b.size(), map_b2.size());
00509   ASSERT_TRUE(std::equal(map_b.begin(), map_b.end(), map_b2.begin()));
00510 }
00511 
00512 int
00513 main(int argc, char** argv)
00514 {
00515   testing::InitGoogleTest(&argc, argv);
00516   ros::init( argc, argv, "params" );
00517 //  ros::NodeHandle nh;
00518 
00519   return RUN_ALL_TESTS();
00520 }


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:47:21