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 int
00259 main(int argc, char** argv)
00260 {
00261   testing::InitGoogleTest(&argc, argv);
00262   ros::init( argc, argv, "params" );
00263 //  ros::NodeHandle nh;
00264 
00265   return RUN_ALL_TESTS();
00266 }


test_roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Ken Conley kwc@willowgarage.com
autogenerated on Sat Dec 28 2013 17:36:21