params.cpp
Go to the documentation of this file.
00001 #include <swri_roscpp/parameters.h>
00002 
00003 #include <string>
00004 #include <vector>
00005 #include <gtest/gtest.h>
00006 
00007 TEST(ParamTests, getUnusedParamKeys)
00008 {
00009   ros::NodeHandle pnh("~");
00010   std::string ns = pnh.getNamespace();
00011   
00012   int int_var;
00013   swri::getParam(pnh, "used_int_var_1", int_var);
00014   swri::param(pnh, "used_int_var_2", int_var, 2);
00015   swri::param(pnh, "unset_int_var", int_var, 2);
00016   
00017   std::string str_var;
00018   swri::getParam(pnh, "used_str_var_1", str_var);
00019   swri::param(pnh, "used_str_var_2", str_var, "foo");
00020   swri::param(pnh, "unset_str_var", str_var, "foo");
00021   
00022   double dbl_var;
00023   swri::getParam(pnh, "used_dbl_var_1", dbl_var);
00024   swri::param(pnh, "used_dbl_var_2", dbl_var, 2.0);
00025   swri::param(pnh, "unset_dbl_var", dbl_var, 2.0);
00026   
00027   bool bool_var;
00028   swri::getParam(pnh, "used_bool_var_1", bool_var);
00029   swri::param(pnh, "used_bool_var_2", bool_var, true);
00030   swri::param(pnh, "unset_bool_var", bool_var, true);
00031   
00032   std::vector<std::string> unused = swri::getUnusedParamKeys(pnh);
00033   ASSERT_EQ(4, unused.size());
00034   ASSERT_EQ(ns + "/unused_bool_var", unused[0]);
00035   ASSERT_EQ(ns + "/unused_dbl_var", unused[1]);
00036   ASSERT_EQ(ns + "/unused_int_var", unused[2]);
00037   ASSERT_EQ(ns + "/unused_str_var", unused[3]);
00038 }
00039 
00040 int main(int argc, char **argv)
00041 {
00042   ros::init(argc, argv, "param_test");
00043   testing::InitGoogleTest(&argc, argv);
00044   return RUN_ALL_TESTS();
00045 }
00046 


swri_roscpp
Author(s):
autogenerated on Thu Jun 6 2019 20:34:47