params.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /* Author: Josh Faust */
31 
32 /*
33  * Test parameters
34  */
35 
36 #include <string>
37 #include <sstream>
38 #include <fstream>
39 
40 #include <gtest/gtest.h>
41 
42 #include <time.h>
43 #include <stdlib.h>
44 
45 #include "ros/ros.h"
46 #include <ros/param.h>
47 
48 using namespace ros;
49 
50 TEST(Params, allParamTypes)
51 {
52  std::string string_param;
53  EXPECT_TRUE( param::get( "string", string_param ) );
54  EXPECT_TRUE( string_param == "test" );
55 
56  int int_param = 0;
57  EXPECT_TRUE( param::get( "int", int_param ) );
58  EXPECT_TRUE( int_param == 10 );
59 
60  double double_param = 0.0;
61  EXPECT_TRUE( param::get( "double", double_param ) );
62  EXPECT_DOUBLE_EQ( double_param, 10.5 );
63 
64  bool bool_param = true;
65  EXPECT_TRUE( param::get( "bool", bool_param ) );
66  EXPECT_FALSE( bool_param );
67 }
68 
69 TEST(Params, setThenGetString)
70 {
71  param::set( "test_set_param", std::string("asdf") );
72  std::string param;
73  ASSERT_TRUE( param::get( "test_set_param", param ) );
74  ASSERT_STREQ( "asdf", param.c_str() );
75 
77  param::get("test_set_param", v);
78  ASSERT_EQ(v.getType(), XmlRpc::XmlRpcValue::TypeString);
79 }
80 
81 TEST(Params, setThenGetStringCached)
82 {
83  std::string param;
84  ASSERT_FALSE( param::getCached( "test_set_param_setThenGetStringCached", param) );
85 
86  param::set( "test_set_param_setThenGetStringCached", std::string("asdf") );
87 
88  ASSERT_TRUE( param::getCached( "test_set_param_setThenGetStringCached", param) );
89  ASSERT_STREQ( "asdf", param.c_str() );
90 }
91 
92 TEST(Params, setThenGetStringCachedNodeHandle)
93 {
94  NodeHandle nh;
95  std::string param;
96  ASSERT_FALSE( nh.getParamCached( "test_set_param_setThenGetStringCachedNodeHandle", param) );
97 
98  nh.setParam( "test_set_param_setThenGetStringCachedNodeHandle", std::string("asdf") );
99 
100  ASSERT_TRUE( nh.getParamCached( "test_set_param_setThenGetStringCachedNodeHandle", param) );
101  ASSERT_STREQ( "asdf", param.c_str() );
102 }
103 
104 TEST(Params, setThenGetNamespaceCached)
105 {
106  std::string stringParam;
107  XmlRpc::XmlRpcValue structParam;
108  const std::string ns = "test_set_param_setThenGetStringCached2";
109  ASSERT_FALSE(param::getCached(ns, stringParam));
110 
111  param::set(ns, std::string("a"));
112  ASSERT_TRUE(param::getCached(ns, stringParam));
113  ASSERT_STREQ("a", stringParam.c_str());
114 
115  param::set(ns + "/foo", std::string("b"));
116  ASSERT_TRUE(param::getCached(ns + "/foo", stringParam));
117  ASSERT_STREQ("b", stringParam.c_str());
118  ASSERT_TRUE(param::getCached(ns, structParam));
119  ASSERT_TRUE(structParam.hasMember("foo"));
120  ASSERT_STREQ("b", static_cast<std::string>(structParam["foo"]).c_str());
121 }
122 
123 TEST(Params, setThenGetCString)
124 {
125  param::set( "test_set_param", "asdf" );
126  std::string param;
127  ASSERT_TRUE( param::get( "test_set_param", param ) );
128  ASSERT_STREQ( "asdf", param.c_str() );
129 }
130 
131 TEST(Params, setThenGetInt)
132 {
133  param::set( "test_set_param", 42);
134  int param;
135  ASSERT_TRUE( param::get( "test_set_param", param ) );
136  ASSERT_EQ( 42, param );
138  param::get("test_set_param", v);
139  ASSERT_EQ(v.getType(), XmlRpc::XmlRpcValue::TypeInt);
140 }
141 
142 TEST(Params, unknownParam)
143 {
144  std::string param;
145  ASSERT_FALSE( param::get( "this_param_really_should_not_exist", param ) );
146 }
147 
148 TEST(Params, deleteParam)
149 {
150  param::set( "test_delete_param", "asdf" );
151  param::del( "test_delete_param" );
152  std::string param;
153  ASSERT_FALSE( param::get( "test_delete_param", param ) );
154 }
155 
156 TEST(Params, hasParam)
157 {
158  ASSERT_TRUE( param::has( "string" ) );
159 }
160 
161 TEST(Params, setIntDoubleGetInt)
162 {
163  param::set("test_set_int_as_double", 1);
164  param::set("test_set_int_as_double", 3.0f);
165 
166  int i = -1;
167  ASSERT_TRUE(param::get("test_set_int_as_double", i));
168  ASSERT_EQ(3, i);
169  double d = 0.0f;
170  ASSERT_TRUE(param::get("test_set_int_as_double", d));
171  ASSERT_EQ(3.0, d);
172 }
173 
174 TEST(Params, getIntAsDouble)
175 {
176  param::set("int_param", 1);
177  double d = 0.0;
178  ASSERT_TRUE(param::get("int_param", d));
179  ASSERT_EQ(1.0, d);
180 }
181 
182 TEST(Params, getDoubleAsInt)
183 {
184  param::set("double_param", 2.3);
185  int i = -1;
186  ASSERT_TRUE(param::get("double_param", i));
187  ASSERT_EQ(2, i);
188 
189  param::set("double_param", 3.8);
190  i = -1;
191  ASSERT_TRUE(param::get("double_param", i));
192  ASSERT_EQ(4, i);
193 }
194 
195 TEST(Params, searchParam)
196 {
197  std::string ns = "/a/b/c/d/e/f";
198  std::string result;
199 
200  param::set("/s_i", 1);
201  ASSERT_TRUE(param::search(ns, "s_i", result));
202  ASSERT_STREQ(result.c_str(), "/s_i");
203  param::del("/s_i");
204 
205  param::set("/a/b/s_i", 1);
206  ASSERT_TRUE(param::search(ns, "s_i", result));
207  ASSERT_STREQ(result.c_str(), "/a/b/s_i");
208  param::del("/a/b/s_i");
209 
210  param::set("/a/b/c/d/e/f/s_i", 1);
211  ASSERT_TRUE(param::search(ns, "s_i", result));
212  ASSERT_STREQ(result.c_str(), "/a/b/c/d/e/f/s_i");
213  param::del("/a/b/c/d/e/f/s_i");
214 
215  bool cont = true;
216  while (!cont)
217  {
218  ros::WallDuration(0.1).sleep();
219  }
220 
221  ASSERT_FALSE(param::search(ns, "s_j", result));
222 }
223 
224 TEST(Params, searchParamNodeHandle)
225 {
226  NodeHandle n("/a/b/c/d/e/f");
227  std::string result;
228 
229  n.setParam("/s_i", 1);
230  ASSERT_TRUE(n.searchParam("s_i", result));
231  ASSERT_STREQ(result.c_str(), "/s_i");
232  n.deleteParam("/s_i");
233 
234  n.setParam("/a/b/s_i", 1);
235  ASSERT_TRUE(n.searchParam("s_i", result));
236  ASSERT_STREQ(result.c_str(), "/a/b/s_i");
237  n.deleteParam("/a/b/s_i");
238 
239  n.setParam("/a/b/c/d/e/f/s_i", 1);
240  ASSERT_TRUE(n.searchParam("s_i", result));
241  ASSERT_STREQ(result.c_str(), "/a/b/c/d/e/f/s_i");
242  n.deleteParam("/a/b/c/d/e/f/s_i");
243 
244  ASSERT_FALSE(n.searchParam("s_j", result));
245 }
246 
247 TEST(Params, searchParamNodeHandleWithRemapping)
248 {
249  M_string remappings;
250  remappings["s_c"] = "s_b";
251  NodeHandle n("/a/b/c/d/e/f", remappings);
252  std::string result;
253 
254  n.setParam("/s_c", 1);
255  ASSERT_FALSE(n.searchParam("s_c", result));
256  n.setParam("/s_b", 1);
257  ASSERT_TRUE(n.searchParam("s_c", result));
258 }
259 
260 // See ROS ticket #2381
261 TEST(Params, getMissingXmlRpcValueParameterCachedTwice)
262 {
264  ASSERT_FALSE(ros::param::getCached("invalid_xmlrpcvalue_param", v));
265  ASSERT_FALSE(ros::param::getCached("invalid_xmlrpcvalue_param", v));
266 }
267 
268 // See ROS ticket #2353
269 TEST(Params, doublePrecision)
270 {
271  ros::param::set("bar", 0.123456789123456789);
272  double d;
273  ASSERT_TRUE(ros::param::get("bar", d));
274  EXPECT_DOUBLE_EQ(d, 0.12345678912345678);
275 }
276 
277 std::vector<std::string> vec_s, vec_s2;
278 std::vector<double> vec_d, vec_d2;
279 std::vector<float> vec_f, vec_f2;
280 std::vector<int> vec_i, vec_i2;
281 std::vector<bool> vec_b, vec_b2;
282 
283 TEST(Params, vectorStringParam)
284 {
285  const std::string param_name = "vec_str_param";
286 
287  vec_s.clear();
288  vec_s.push_back("foo");
289  vec_s.push_back("bar");
290  vec_s.push_back("baz");
291 
292  ros::param::set(param_name, vec_s);
293 
294  ASSERT_FALSE(ros::param::get(param_name, vec_d));
295  ASSERT_FALSE(ros::param::get(param_name, vec_f));
296  ASSERT_FALSE(ros::param::get(param_name, vec_i));
297  ASSERT_FALSE(ros::param::get(param_name, vec_b));
298 
299  ASSERT_TRUE(ros::param::get(param_name, vec_s2));
300 
301  ASSERT_EQ(vec_s.size(), vec_s2.size());
302  ASSERT_TRUE(std::equal(vec_s.begin(), vec_s.end(), vec_s2.begin()));
303 
304  // Test empty vector
305  vec_s.clear();
306  ros::param::set(param_name, vec_s);
307  ASSERT_TRUE(ros::param::get(param_name, vec_s2));
308  ASSERT_EQ(vec_s.size(), vec_s2.size());
309 }
310 
311 TEST(Params, vectorDoubleParam)
312 {
313  const std::string param_name = "vec_double_param";
314 
315  vec_d.clear();
316  vec_d.push_back(-0.123456789);
317  vec_d.push_back(3);
318  vec_d.push_back(3.01);
319  vec_d.push_back(7.01);
320 
321  ros::param::set(param_name, vec_d);
322 
323  ASSERT_FALSE(ros::param::get(param_name, vec_s));
324  ASSERT_TRUE(ros::param::get(param_name, vec_i));
325  ASSERT_TRUE(ros::param::get(param_name, vec_b));
326  ASSERT_TRUE(ros::param::get(param_name, vec_f));
327 
328  ASSERT_TRUE(ros::param::get(param_name, vec_d2));
329 
330  ASSERT_EQ(vec_d.size(), vec_d2.size());
331  ASSERT_TRUE(std::equal(vec_d.begin(), vec_d.end(), vec_d2.begin()));
332 }
333 
334 TEST(Params, vectorFloatParam)
335 {
336  const std::string param_name = "vec_float_param";
337 
338  vec_f.clear();
339  vec_f.push_back(-0.123456789);
340  vec_f.push_back(0.0);
341  vec_f.push_back(3);
342  vec_f.push_back(3.01);
343 
344  ros::param::set(param_name, vec_f);
345 
346  ASSERT_FALSE(ros::param::get(param_name, vec_s));
347  ASSERT_TRUE(ros::param::get(param_name, vec_i));
348  ASSERT_TRUE(ros::param::get(param_name, vec_b));
349  ASSERT_TRUE(ros::param::get(param_name, vec_d));
350 
351  ASSERT_EQ(vec_b[0],true);
352  ASSERT_EQ(vec_b[1],false);
353 
354  ASSERT_TRUE(ros::param::get(param_name, vec_f2));
355 
356  ASSERT_EQ(vec_f.size(), vec_f2.size());
357  ASSERT_TRUE(std::equal(vec_f.begin(), vec_f.end(), vec_f2.begin()));
358 }
359 
360 TEST(Params, vectorIntParam)
361 {
362  const std::string param_name = "vec_int_param";
363 
364  vec_i.clear();
365  vec_i.push_back(-1);
366  vec_i.push_back(0);
367  vec_i.push_back(1337);
368  vec_i.push_back(2);
369 
370  ros::param::set(param_name, vec_i);
371 
372  ASSERT_FALSE(ros::param::get(param_name, vec_s));
373  ASSERT_TRUE(ros::param::get(param_name, vec_d));
374  ASSERT_TRUE(ros::param::get(param_name, vec_f));
375  ASSERT_TRUE(ros::param::get(param_name, vec_b));
376 
377  ASSERT_EQ(vec_b[0],true);
378  ASSERT_EQ(vec_b[1],false);
379 
380  ASSERT_TRUE(ros::param::get(param_name, vec_i2));
381 
382  ASSERT_EQ(vec_i.size(), vec_i2.size());
383  ASSERT_TRUE(std::equal(vec_i.begin(), vec_i.end(), vec_i2.begin()));
384 }
385 
386 TEST(Params, vectorBoolParam)
387 {
388  const std::string param_name = "vec_bool_param";
389 
390  vec_b.clear();
391  vec_b.push_back(true);
392  vec_b.push_back(false);
393  vec_b.push_back(true);
394  vec_b.push_back(true);
395 
396  ros::param::set(param_name, vec_b);
397 
398  ASSERT_FALSE(ros::param::get(param_name, vec_s));
399  ASSERT_TRUE(ros::param::get(param_name, vec_d));
400  ASSERT_TRUE(ros::param::get(param_name, vec_f));
401  ASSERT_TRUE(ros::param::get(param_name, vec_i));
402 
403  ASSERT_EQ(vec_i[0],1);
404  ASSERT_EQ(vec_i[1],0);
405 
406  ASSERT_TRUE(ros::param::get(param_name, vec_b2));
407 
408  ASSERT_EQ(vec_b.size(), vec_b2.size());
409  ASSERT_TRUE(std::equal(vec_b.begin(), vec_b.end(), vec_b2.begin()));
410 }
411 
412 std::map<std::string,std::string> map_s, map_s2;
413 std::map<std::string,double> map_d, map_d2;
414 std::map<std::string,float> map_f, map_f2;
415 std::map<std::string,int> map_i, map_i2;
416 std::map<std::string,bool> map_b, map_b2;
417 
418 TEST(Params, mapStringParam)
419 {
420  const std::string param_name = "map_str_param";
421 
422  map_s.clear();
423  map_s["a"] = "apple";
424  map_s["b"] = "blueberry";
425  map_s["c"] = "carrot";
426 
427  ros::param::set(param_name, map_s);
428 
429  ASSERT_FALSE(ros::param::get(param_name, map_d));
430  ASSERT_FALSE(ros::param::get(param_name, map_f));
431  ASSERT_FALSE(ros::param::get(param_name, map_i));
432  ASSERT_FALSE(ros::param::get(param_name, map_b));
433 
434  ASSERT_TRUE(ros::param::get(param_name, map_s2));
435 
436  ASSERT_EQ(map_s.size(), map_s2.size());
437  ASSERT_TRUE(std::equal(map_s.begin(), map_s.end(), map_s2.begin()));
438 }
439 
440 TEST(Params, mapDoubleParam)
441 {
442  const std::string param_name = "map_double_param";
443 
444  map_d.clear();
445  map_d["a"] = 0.0;
446  map_d["b"] = -0.123456789;
447  map_d["c"] = 123456789;
448 
449  ros::param::set(param_name, map_d);
450 
451  ASSERT_FALSE(ros::param::get(param_name, map_s));
452  ASSERT_TRUE(ros::param::get(param_name, map_f));
453  ASSERT_TRUE(ros::param::get(param_name, map_i));
454  ASSERT_TRUE(ros::param::get(param_name, map_b));
455 
456  ASSERT_TRUE(ros::param::get(param_name, map_d2));
457 
458  ASSERT_EQ(map_d.size(), map_d2.size());
459  ASSERT_TRUE(std::equal(map_d.begin(), map_d.end(), map_d2.begin()));
460 }
461 
462 TEST(Params, mapFloatParam)
463 {
464  const std::string param_name = "map_float_param";
465 
466  map_f.clear();
467  map_f["a"] = 0.0;
468  map_f["b"] = -0.123456789;
469  map_f["c"] = 123456789;
470 
471  ros::param::set(param_name, map_f);
472 
473  ASSERT_FALSE(ros::param::get(param_name, map_s));
474  ASSERT_TRUE(ros::param::get(param_name, map_d));
475  ASSERT_TRUE(ros::param::get(param_name, map_i));
476  ASSERT_TRUE(ros::param::get(param_name, map_b));
477 
478  ASSERT_TRUE(ros::param::get(param_name, map_f2));
479 
480  ASSERT_EQ(map_f.size(), map_f2.size());
481  ASSERT_TRUE(std::equal(map_f.begin(), map_f.end(), map_f2.begin()));
482 }
483 
484 TEST(Params, mapIntParam)
485 {
486  const std::string param_name = "map_int_param";
487 
488  map_i.clear();
489  map_i["a"] = 0;
490  map_i["b"] = -1;
491  map_i["c"] = 1337;
492 
493  ros::param::set(param_name, map_i);
494 
495  ASSERT_FALSE(ros::param::get(param_name, map_s));
496  ASSERT_TRUE(ros::param::get(param_name, map_d));
497  ASSERT_TRUE(ros::param::get(param_name, map_f));
498  ASSERT_TRUE(ros::param::get(param_name, map_b));
499 
500  ASSERT_TRUE(ros::param::get(param_name, map_i2));
501 
502  ASSERT_EQ(map_i.size(), map_i2.size());
503  ASSERT_TRUE(std::equal(map_i.begin(), map_i.end(), map_i2.begin()));
504 }
505 
506 TEST(Params, mapBoolParam)
507 {
508  const std::string param_name = "map_bool_param";
509 
510  map_b.clear();
511  map_b["a"] = true;
512  map_b["b"] = false;
513  map_b["c"] = true;
514 
515  ros::param::set(param_name, map_b);
516 
517  ASSERT_FALSE(ros::param::get(param_name, map_s));
518  ASSERT_TRUE(ros::param::get(param_name, map_d));
519  ASSERT_TRUE(ros::param::get(param_name, map_f));
520  ASSERT_TRUE(ros::param::get(param_name, map_i));
521 
522  ASSERT_EQ(map_i["a"],1);
523  ASSERT_EQ(map_i["b"],0);
524 
525  ASSERT_TRUE(ros::param::get(param_name, map_b2));
526 
527  ASSERT_EQ(map_b.size(), map_b2.size());
528  ASSERT_TRUE(std::equal(map_b.begin(), map_b.end(), map_b2.begin()));
529 }
530 
531 TEST(Params, paramTemplateFunction)
532 {
533  EXPECT_EQ( param::param<std::string>( "string", "" ), "test" );
534  EXPECT_EQ( param::param<std::string>( "gnirts", "test" ), "test" );
535 
536  EXPECT_EQ( param::param<int>( "int", 0 ), 10 );
537  EXPECT_EQ( param::param<int>( "tni", 10 ), 10 );
538 
539  EXPECT_DOUBLE_EQ( param::param<double>( "double", 0.0 ), 10.5 );
540  EXPECT_DOUBLE_EQ( param::param<double>( "elbuod", 10.5 ), 10.5 );
541 
542  EXPECT_EQ( param::param<bool>( "bool", true ), false );
543  EXPECT_EQ( param::param<bool>( "loob", true ), true );
544 }
545 
546 TEST(Params, paramNodeHandleTemplateFunction)
547 {
548  NodeHandle nh;
549 
550  EXPECT_EQ( nh.param<std::string>( "string", "" ), "test" );
551  EXPECT_EQ( nh.param<std::string>( "gnirts", "test" ), "test" );
552 
553  EXPECT_EQ( nh.param<int>( "int", 0 ), 10 );
554  EXPECT_EQ( nh.param<int>( "tni", 10 ), 10 );
555 
556  EXPECT_DOUBLE_EQ( nh.param<double>( "double", 0.0 ), 10.5 );
557  EXPECT_DOUBLE_EQ( nh.param<double>( "elbuod", 10.5 ), 10.5 );
558 
559  EXPECT_EQ( nh.param<bool>( "bool", true ), false );
560  EXPECT_EQ( nh.param<bool>( "loob", true ), true );
561 }
562 
563 TEST(Params, getParamNames) {
564  std::vector<std::string> test_params;
565  EXPECT_TRUE(ros::param::getParamNames(test_params));
566  EXPECT_LT(10, test_params.size());
567 }
568 
569 TEST(Params, getParamCachedSetParamLoop) {
570  NodeHandle nh;
571  const std::string name = "changeable_int";
572  for (int i = 0; i < 100; i++) {
573  nh.setParam(name, i);
574  int v = 0;
575  ASSERT_TRUE(nh.getParamCached(name, v));
576  ASSERT_EQ(i, v);
577  }
578 }
579 
580 int
581 main(int argc, char** argv)
582 {
583  testing::InitGoogleTest(&argc, argv);
584  ros::init(argc, argv, "params");
585  ros::NodeHandle nh;
586 
587  return RUN_ALL_TESTS();
588 }
TEST(Params, allParamTypes)
Definition: params.cpp:50
d
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
bool param(const std::string &param_name, T &param_val, const T &default_val)
std::vector< std::string > vec_s
Definition: params.cpp:277
std::map< std::string, double > map_d2
Definition: params.cpp:413
f
std::vector< bool > vec_b2
Definition: params.cpp:281
std::map< std::string, bool > map_b2
Definition: params.cpp:416
bool getParamCached(const std::string &key, std::string &s) const
std::map< std::string, bool > map_b
Definition: params.cpp:416
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
Definition: params.cpp:279
std::vector< double > vec_d
Definition: params.cpp:278
Type const & getType() const
std::map< std::string, std::string > map_s
Definition: params.cpp:412
std::vector< float > vec_f2
Definition: params.cpp:279
std::map< std::string, std::string > M_string
std::map< std::string, std::string > map_s2
Definition: params.cpp:412
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
bool sleep() const
std::vector< int > vec_i
Definition: params.cpp:280
std::map< std::string, float > map_f
Definition: params.cpp:414
std::map< std::string, double > map_d
Definition: params.cpp:413
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 &param_name, T &param_val, const T &default_val) const
std::map< std::string, float > map_f2
Definition: params.cpp:414
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
Definition: params.cpp:415
ROSCPP_DECL bool del(const std::string &key)
bool hasMember(const std::string &name) const
std::vector< double > vec_d2
Definition: params.cpp:278
std::vector< bool > vec_b
Definition: params.cpp:281
std::vector< std::string > vec_s2
Definition: params.cpp:277
std::vector< int > vec_i2
Definition: params.cpp:280
std::map< std::string, int > map_i2
Definition: params.cpp:415
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
int main(int argc, char **argv)
Definition: params.cpp:581
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46