param_tests.cpp
Go to the documentation of this file.
1 #include <utility>
2 #include <vector>
3 
4 #include <rtt/os/startstop.h>
5 #include <rtt/Logger.hpp>
6 #include <rtt/TaskContext.hpp>
11 
12 #include <boost/serialization/serialization.hpp>
13 
14 #include <rtt_rosparam/rosparam.h>
15 
16 #include <geometry_msgs/typekit/Vector3.h>
17 
18 #include <ros/init.h>
19 #include <ros/names.h>
20 #include <ros/param.h>
21 #include <ros/this_node.h>
22 
23 #include <gtest/gtest.h>
24 
25 using namespace RTT;
26 using namespace rtt_rosparam;
27 
28 // helper function to compare PropertyBags
29 namespace RTT {
30  bool operator==(const PropertyBag &left, const PropertyBag &right) {
31  std::set<base::PropertyBase *> right_seen;
32 
33  for(PropertyBag::const_iterator left_it = left.begin(); left_it != left.end(); ++left_it) {
34  base::PropertyBase *left_prop = *left_it;
35  base::PropertyBase *right_prop = right.getProperty(left_prop->getName());
36  if (right_prop) {
37  right_seen.insert(right_prop);
38  if (left_prop->getType() != right_prop->getType()) return false;
39 
40  // Recurse if both properties are PropertyBags
41  Property<PropertyBag> left_bag;
42  left_bag = left_prop;
43  Property<PropertyBag> right_bag;
44  right_bag = right_prop;
45  if (left_bag.ready() && right_bag.ready()) {
46  if (!(left_bag == right_bag)) return false;
47  continue;
48  }
49 
50  // Otherwise,...
51  // ... we believe that the values are the same for now (TODO)
52  }
53  }
54 
55  // check that all values of the right bag have been visited
56  if (right_seen.size() != right.size()) return false;
57 
58  return true;
59  }
60 }
61 
62 namespace boost {
63 namespace serialization {
64 template<class Archive>
65 void serialize(Archive & a, std::pair<std::string, int> &pair, unsigned int) {
66  using boost::serialization::make_nvp;
67  a & make_nvp("first", pair.first);
68  a & make_nvp("second", pair.second);
69 }
70 }
71 }
72 
73 // Typekit for the custom types.
74 namespace {
75 
76 typedef std::pair<std::string, int> StringIntPair;
77 
78 class StringIntPairTypeInfo : public RTT::types::StructTypeInfo<StringIntPair> {
79 public:
80  StringIntPairTypeInfo()
82  {}
83 };
84 
85 class StringIntPairVecTypeInfo : public RTT::types::SequenceTypeInfo<std::vector<StringIntPair> > {
86 public:
87  StringIntPairVecTypeInfo()
89  {}
90 };
91 
92 }
93 
94 class ParamTest : public ::testing::Test {
95 public:
96  static void SetUpTestCase()
97  {
98  RTT::types::Types()->addType(new StringIntPairTypeInfo);
99  RTT::types::Types()->addType(new StringIntPairVecTypeInfo);
100  }
101 
102 protected:
103  virtual void SetUp() {
104  // Import packages
105  ASSERT_TRUE(RTT::ComponentLoader::Instance()->import("rtt_rosparam", "" ));
106  ASSERT_TRUE(RTT::ComponentLoader::Instance()->import("rtt_geometry_msgs", "" ));
107 
108  tc = new TaskContext("rtt_rosparam_component");
109 
110  // Primitive parameters
111  tc->addProperty("string", props.string_);
112  tc->addProperty("double", props.double_);
113  tc->addProperty("float", props.float_);
114  tc->addProperty("int", props.int_);
115  tc->addProperty("uint", props.uint_);
116  tc->addProperty("char", props.char_);
117  tc->addProperty("uchar", props.uchar_);
118  tc->addProperty("bool", props.bool_);
119 
120  // Vector parameters
121  tc->addProperty("vstring", props.v_string_);
122  tc->addProperty("vdouble", props.v_double_);
123  tc->addProperty("vfloat", props.v_float_);
124  tc->addProperty("vint", props.v_int_);
125  tc->addProperty("vuint", props.v_uint_);
126  tc->addProperty("vchar", props.v_char_);
127  tc->addProperty("vuchar", props.v_uchar_);
128  tc->addProperty("vbool", props.v_bool_);
129 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
130  tc->addProperty("eigenvectordouble", props.eigenvector_double_);
131  tc->addProperty("eigenvectorfloat", props.eigenvector_float_);
132 #endif
133  // Struct parameters
134  tc->addProperty("bag", props.bag_);
135  tc->addProperty("vector3", props.vector3_);
136  tc->addProperty("pair", props.pair_);
137  tc->addProperty("pair_vector", props.pair_vector_);
138 
139  // Delete parameters that might be left from previous executions
140  deleteParameters();
141 
142  // Load rosparam service and get pointers
143  ASSERT_TRUE(tc->loadService("rosparam"));
144  ASSERT_TRUE((rosparam = tc->getProvider<ROSParam>("rosparam")).get());
145  ASSERT_TRUE((service = tc->provides()->getService("rosparam")).get());
146  }
147 
148  virtual void TearDown() {
149  deleteParameters();
150  delete tc;
151  }
152 
153  struct Values {
154  // Primitive parameters
155  std::string string_;
156  double double_;
157  float float_;
158  int int_;
159  unsigned int uint_;
160  char char_;
161  unsigned char uchar_;
162  bool bool_;
163 
164  // Vector parameters_
165  std::vector<std::string> v_string_;
166  std::vector<double> v_double_;
167  std::vector<float> v_float_;
168  std::vector<int> v_int_;
169  std::vector<unsigned int> v_uint_;
170  std::vector<char> v_char_;
171  std::vector<unsigned char> v_uchar_;
172  std::vector<bool> v_bool_;
173 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
174  Eigen::VectorXd eigenvector_double_;
175  Eigen::VectorXf eigenvector_float_;
176 #endif
177 
178  // Struct parameters
180  geometry_msgs::Vector3 vector3_;
181  StringIntPair pair_;
182  std::vector<StringIntPair> pair_vector_;
183 
184  Values() {
185  reset();
186  }
187 
188  void initialize() {
189  // Primitive parameters
190  string_ = "foobar";
191  double_ = 5.5;
192  float_ = 6.5f;
193  int_ = -7;
194  uint_ = 8u;
195  char_ = 'c';
196  uchar_ = 255u;
197  bool_ = true;
198 
199  // Vector parameters
200  v_string_.push_back(string_);
201  v_double_.push_back(double_);
202  v_float_.push_back(float_);
203  v_int_.push_back(int_);
204  v_uint_.push_back(uint_);
205  v_char_.push_back(char_);
206  v_uchar_.push_back(uchar_);
207  v_bool_.push_back(bool_);
208 
209 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
210  eigenvector_double_ = Eigen::Vector3d(5.0, 6.0, 7.0);
211  eigenvector_float_ = Eigen::Vector3f(8.0f, 9.0f, 10.0f);
212 #endif
213 
214  // Struct parameters
215  bag_.clear();
216  bag_.ownProperty(new RTT::Property<std::string>("string", "", "yet another value"));
217  bag_.ownProperty(new RTT::Property<int>("int", "", 20));
218 
219  vector3_.x = 20.0;
220  vector3_.y = 21.0;
221  vector3_.z = 22.0;
222 
223  pair_ = std::make_pair("abc", 6);
224 
225  pair_vector_.clear();
226  pair_vector_.push_back(std::make_pair("one", 1));
227  pair_vector_.push_back(std::make_pair("two", 2));
228  }
229 
231  // Primitive parameters
232  string_ = "barfoo";
233  double_ = 6.8;
234  float_ = 8.4f;
235  int_ = -42;
236  uint_ = 17u;
237  char_ = 'p';
238  uchar_ = 58u;
239  bool_ = false;
240 
241  // Vector parameters
242  v_string_.push_back(string_);
243  v_double_.push_back(double_);
244  v_float_.push_back(float_);
245  v_int_.push_back(int_);
246  v_uint_.push_back(uint_);
247  v_char_.push_back(char_);
248  v_uchar_.push_back(uchar_);
249  v_bool_.push_back(bool_);
250 
251 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
252  eigenvector_double_ = Eigen::Vector3d(9.6, 3.4, 2.5);
253  eigenvector_float_ = Eigen::Vector3f(2.3f, 7.6f, 5.2f);
254 #endif
255 
256  // Struct parameters
257  bag_.clear();
258  bag_.ownProperty(new RTT::Property<std::string>("string", "", "yet another alternative value"));
259  bag_.ownProperty(new RTT::Property<int>("int", "", 30));
260 
261  vector3_.x = 24.4;
262  vector3_.y = 25.5;
263  vector3_.z = 26.6;
264  }
265 
266  void reset() {
267  string_.clear();
268  double_ = 0.0;
269  float_ = 0.0f;
270  int_ = 0;
271  uint_ = 0u;
272  char_ = 0;
273  uchar_ = 0u;
274  bool_ = false;
275 
276  v_string_.clear();
277  v_double_.clear();
278  v_float_.clear();
279  v_int_.clear();
280  v_uint_.clear();
281  v_char_.clear();
282  v_uchar_.clear();
283  v_bool_.clear();
284 
285 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
286  eigenvector_double_.setZero(0);
287  eigenvector_float_.setZero(0);
288 #endif
289 
290  bag_.clear();
291  bag_.ownProperty(new RTT::Property<std::string>("string", "", std::string()));
292  bag_.ownProperty(new RTT::Property<int>("int", "", 0));
293 
294  vector3_= geometry_msgs::Vector3();
295 
296  pair_ = std::make_pair("", 0);
297  pair_vector_.clear();
298  }
299  } props, params;
300 
301 
302  void getParameters(const std::string &prefix, Values &data, bool only_ros_types = false) {
303  EXPECT_TRUE(ros::param::get(prefix + "string", data.string_));
304  EXPECT_TRUE(ros::param::get(prefix + "double", data.double_));
305  EXPECT_TRUE(ros::param::get(prefix + "float", data.float_));
306  EXPECT_TRUE(ros::param::get(prefix + "int", data.int_));
307  if (!only_ros_types) {
308  int temp;
309  EXPECT_TRUE(ros::param::get(prefix + "uint", temp));
310  data.uint_ = static_cast<unsigned int>(temp);
311  EXPECT_TRUE(ros::param::get(prefix + "char", temp));
312  data.char_ = static_cast<char>(temp);
313  EXPECT_TRUE(ros::param::get(prefix + "uchar", temp));
314  data.uchar_ = static_cast<unsigned char>(temp);
315  }
316  EXPECT_TRUE(ros::param::get(prefix + "bool", data.bool_));
317 
318  EXPECT_TRUE(ros::param::get(prefix + "vstring", data.v_string_));
319  EXPECT_TRUE(ros::param::get(prefix + "vdouble", data.v_double_));
320  EXPECT_TRUE(ros::param::get(prefix + "vfloat", data.v_float_));
321  EXPECT_TRUE(ros::param::get(prefix + "vint", data.v_int_));
322  if (!only_ros_types) {
323  std::vector<int> vtemp;
324  EXPECT_TRUE(ros::param::get(prefix + "vuint", vtemp));
325  data.v_uint_.assign(vtemp.begin(), vtemp.end());
326  EXPECT_TRUE(ros::param::get(prefix + "vchar", vtemp));
327  data.v_char_.assign(vtemp.begin(), vtemp.end());
328  EXPECT_TRUE(ros::param::get(prefix + "vuchar", vtemp));
329  data.v_uchar_.assign(vtemp.begin(), vtemp.end());
330  }
331  EXPECT_TRUE(ros::param::get(prefix + "vbool", data.v_bool_));
332 
333 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
334  std::vector<double> v_temp_double;
335  EXPECT_TRUE(ros::param::get(prefix + "eigenvectordouble", v_temp_double));
336  data.eigenvector_double_ = Eigen::Map<Eigen::VectorXd>(v_temp_double.data(), v_temp_double.size());
337  std::vector<float> v_temp_float;
338  EXPECT_TRUE(ros::param::get(prefix + "eigenvectorfloat", v_temp_float));
339  data.eigenvector_float_ = Eigen::Map<Eigen::VectorXf>(v_temp_float.data(), v_temp_float.size());
340 #endif
341 
342  if (!only_ros_types) {
343  data.bag_.clear();
344  XmlRpc::XmlRpcValue bag_xmlrpc;
345  ros::param::get(prefix + "bag", bag_xmlrpc);
346  if (bag_xmlrpc.valid() && bag_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeStruct) {
347  for(XmlRpc::XmlRpcValue::iterator it = bag_xmlrpc.begin(); it != bag_xmlrpc.end(); ++it) {
348  switch(it->second.getType()) {
350  data.bag_.ownProperty(new RTT::Property<std::string>(it->first, "", it->second));
351  break;
353  data.bag_.ownProperty(new RTT::Property<int>(it->first, "", it->second));
354  break;
355  default:
356  break;
357  }
358  }
359  }
360 
361  EXPECT_TRUE(ros::param::get(prefix + "vector3/x", data.vector3_.x));
362  EXPECT_TRUE(ros::param::get(prefix + "vector3/y", data.vector3_.y));
363  EXPECT_TRUE(ros::param::get(prefix + "vector3/z", data.vector3_.z));
364 
365  EXPECT_TRUE(ros::param::get(prefix + "pair/first", data.pair_.first));
366  EXPECT_TRUE(ros::param::get(prefix + "pair/second", data.pair_.second));
367 
368  XmlRpc::XmlRpcValue vec_xmlrpc;
369  EXPECT_TRUE(ros::param::get(prefix + "pair_vector", vec_xmlrpc));
370  EXPECT_EQ(vec_xmlrpc.getType(), XmlRpc::XmlRpcValue::TypeArray);
371  if (vec_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeArray)
372  {
373  data.pair_vector_.clear();
374 
375  for (int i = 0; i < vec_xmlrpc.size(); ++i)
376  {
377  XmlRpc::XmlRpcValue const &pair_xml = vec_xmlrpc[i];
378 
379  EXPECT_EQ(pair_xml.getType(), XmlRpc::XmlRpcValue::TypeStruct);
381  {
382  bool hasFirst = pair_xml.hasMember("first"),
383  hasSecond = pair_xml.hasMember("second");
384  EXPECT_TRUE(hasFirst);
385  EXPECT_TRUE(hasSecond);
386 
387  if (hasFirst && hasSecond)
388  {
389  StringIntPair pair;
390  pair.first = static_cast<std::string>(pair_xml["first"]);
391  pair.second = pair_xml["second"];
392 
393  data.pair_vector_.push_back(pair);
394  }
395  }
396  }
397  }
398  }
399  }
400 
401  void setParameters(const std::string &prefix, const Values &data) {
402  ros::param::set(prefix + "string", data.string_);
403  ros::param::set(prefix + "double", data.double_);
404  ros::param::set(prefix + "float", data.float_);
405  ros::param::set(prefix + "int", data.int_);
406  int temp;
407  ros::param::set(prefix + "uint", temp = data.uint_);
408  ros::param::set(prefix + "char", temp = data.char_);
409  ros::param::set(prefix + "uchar", temp = data.uchar_);
410  ros::param::set(prefix + "bool", data.bool_);
411 
412  ros::param::set(prefix + "vstring", data.v_string_);
413  ros::param::set(prefix + "vdouble", data.v_double_);
414  ros::param::set(prefix + "vfloat", data.v_float_);
415  ros::param::set(prefix + "vint", data.v_int_);
416  std::vector<int> vtemp;
417  vtemp.assign(data.v_uint_.begin(), data.v_uint_.end());
418  ros::param::set(prefix + "vuint", vtemp);
419  vtemp.assign(data.v_char_.begin(), data.v_char_.end());
420  ros::param::set(prefix + "vchar", vtemp);
421  vtemp.assign(data.v_uchar_.begin(), data.v_uchar_.end());
422  ros::param::set(prefix + "vuchar", vtemp);
423  ros::param::set(prefix + "vbool", data.v_bool_);
424 
425 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
426  std::vector<double> v_temp_double(data.eigenvector_double_.data(), data.eigenvector_double_.data() + data.eigenvector_double_.size());
427  ros::param::set(prefix + "eigenvectordouble", v_temp_double);
428  std::vector<float> v_temp_float(data.eigenvector_float_.data(), data.eigenvector_float_.data() + data.eigenvector_float_.size());
429  ros::param::set(prefix + "eigenvectorfloat", v_temp_float);
430 #endif
431 
432  XmlRpc::XmlRpcValue bag_xmlrpc;
433  (void) bag_xmlrpc.begin(); // force struct type
434  RTT::Property<std::string> bag_string = data.bag_.getProperty("string");
435  if (bag_string.ready()) bag_xmlrpc["string"] = bag_string.rvalue();
436  RTT::Property<int> bag_int = data.bag_.getProperty("int");
437  if (bag_string.ready()) bag_xmlrpc["int"] = bag_int.rvalue();
438  ros::param::set(prefix + "bag", bag_xmlrpc);
439 
440  ros::param::set(prefix + "vector3/x", data.vector3_.x);
441  ros::param::set(prefix + "vector3/y", data.vector3_.y);
442  ros::param::set(prefix + "vector3/z", data.vector3_.z);
443 
444  ros::param::set(prefix + "pair/first", data.pair_.first);
445  ros::param::set(prefix + "pair/second", data.pair_.second);
446 
447  {
448  XmlRpc::XmlRpcValue vec_xmlrpc;
449 
450  int idx = 0;
451  for (std::vector<StringIntPair>::const_iterator pairIt = data.pair_vector_.begin(); pairIt != data.pair_vector_.end(); ++pairIt)
452  {
453  XmlRpc::XmlRpcValue pair_xmlrpc;
454  pair_xmlrpc["first"] = XmlRpc::XmlRpcValue(pairIt->first);
455  pair_xmlrpc["second"] = XmlRpc::XmlRpcValue(pairIt->second);
456  vec_xmlrpc[idx++] = pair_xmlrpc;
457  }
458 
459  ros::param::set(prefix + "pair_vector", vec_xmlrpc);
460  }
461  }
462 
464  for(RTT::PropertyBag::const_iterator prop_it = tc->properties()->begin();
465  prop_it != tc->properties()->end(); ++prop_it)
466  {
467  RTT::base::PropertyBase *prop = *prop_it;
468  ros::param::del(prop->getName()); // RELATIVE
469  ros::param::del(std::string("/") + prop->getName()); // ABSOLUTE
470 // ros::param::del(std::string("~") + prop->getName()); // PRIVATE
471  ros::param::del(tc->getName() + "/" + prop->getName()); // COMPONENT_RELATIVE
472  ros::param::del(std::string("/") + tc->getName() + "/" + prop->getName()); // COMPONENT_ABSOLUTE
473 // ros::param::del(std::string("~") + tc->getName() + "/" + prop->getName()); // COMPONENT_PRIVATE
474  }
475  ros::param::del("~");
476  }
477 
478  void compareValues(const Values &expected, const Values &actual, const std::string &test_name, bool only_ros_types = false) {
479  EXPECT_EQ(expected.string_, actual.string_) << "string values do not match in " << test_name;
480  EXPECT_EQ(expected.double_, actual.double_) << "double values do not match in " << test_name;
481  EXPECT_EQ(expected.float_, actual.float_) << "float values do not match in " << test_name;
482  EXPECT_EQ(expected.int_, actual.int_) << "int values do not match in " << test_name;
483  if (!only_ros_types) {
484  EXPECT_EQ(expected.uint_, actual.uint_) << "unsigned int values do not match in " << test_name;
485  EXPECT_EQ(expected.char_, actual.char_) << "char values do not match in " << test_name;
486  EXPECT_EQ(expected.uchar_, actual.uchar_) << "unsigned char values do not match in " << test_name;
487  }
488  EXPECT_EQ(expected.bool_, actual.bool_) << "bool values do not match in " << test_name;
489  EXPECT_EQ(expected.v_string_, actual.v_string_) << "string vectors do not match in " << test_name;
490  EXPECT_EQ(expected.v_double_, actual.v_double_) << "double vectors do not match in " << test_name;
491  EXPECT_EQ(expected.v_float_, actual.v_float_) << "float vectors do not match in " << test_name;
492  EXPECT_EQ(expected.v_int_, actual.v_int_) << "int vectors does do match in " << test_name;
493  if (!only_ros_types) {
494  EXPECT_EQ(expected.v_uint_, actual.v_uint_) << "unsigned int vectors do not match in " << test_name;
495  EXPECT_EQ(expected.v_char_, actual.v_char_) << "char vectors do not match in " << test_name;
496  EXPECT_EQ(expected.v_uchar_, actual.v_uchar_) << "unsigned char vectors do not match in " << test_name;
497  }
498  EXPECT_EQ(expected.v_bool_, actual.v_bool_) << "bool vectors do not match in " << test_name;
499 
500 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
501  EXPECT_EQ(expected.eigenvector_double_, actual.eigenvector_double_) << "Eigen::VectorXd values do not match in " << test_name;
502  EXPECT_EQ(expected.eigenvector_float_, actual.eigenvector_float_) << "Eigen::VectorXf values do not match in " << test_name;
503 #endif
504  if (!only_ros_types) {
505  EXPECT_EQ(expected.bag_, actual.bag_) << "PropertyBag contents do not match in " << test_name;
506  EXPECT_EQ(expected.vector3_.x, actual.vector3_.x) << "geometry_msgs/Vector3 values do not match in " << test_name;
507  EXPECT_EQ(expected.vector3_.y, actual.vector3_.y) << "geometry_msgs/Vector3 values do not match in " << test_name;
508  EXPECT_EQ(expected.vector3_.z, actual.vector3_.z) << "geometry_msgs/Vector3 values do not match in " << test_name;
509 
510  EXPECT_EQ(expected.pair_, actual.pair_) << "std::pair<std::string, int> values does not match in " << test_name;
511  EXPECT_EQ(expected.pair_vector_, actual.pair_vector_) << "std::vector<std::pair<std::string, int>> values does not match in " << test_name;
512  }
513  }
514 
518 };
519 
520 TEST_F(ParamTest, Constants)
521 {
522  EXPECT_EQ(RELATIVE, Constant<int>(service->getValue("RELATIVE")).get());
523  EXPECT_EQ(ABSOLUTE, Constant<int>(service->getValue("ABSOLUTE")).get());
524  EXPECT_EQ(PRIVATE, Constant<int>(service->getValue("PRIVATE")).get());
525  EXPECT_EQ(COMPONENT_PRIVATE, Constant<int>(service->getValue("COMPONENT_PRIVATE")).get());
526  EXPECT_EQ(COMPONENT_RELATIVE, Constant<int>(service->getValue("COMPONENT_RELATIVE")).get());
527  EXPECT_EQ(COMPONENT_ABSOLUTE, Constant<int>(service->getValue("COMPONENT_ABSOLUTE")).get());
528  EXPECT_EQ(COMPONENT, Constant<int>(service->getValue("COMPONENT")).get());
529 }
530 
531 TEST_F(ParamTest, SetAllPropertiesOnParameterServer)
532 {
533  // initialize properties to some values
534  props.initialize();
535 
536  // setAllRelative()
537  EXPECT_TRUE(rosparam->setAllRelative());
538  getParameters("", params);
539  compareValues(props, params, "setAllRelative()");
540  params.reset();
541 
542 // // setAllAbsolute()
543 // EXPECT_TRUE(rosparam->setAllAbsolute());
544 // getParameters("/", params);
545 // compareValues(props, params, "setAllAbsolute()");
546 // params.reset();
547 
548  // setAllPrivate()
549  EXPECT_TRUE(rosparam->setAllPrivate());
550  getParameters("~", params);
551  compareValues(props, params, "setAllPrivate()");
552  params.reset();
553 
554  // setAllComponentRelative()
555  EXPECT_TRUE(rosparam->setAllComponentRelative());
556  getParameters(tc->getName() + "/", params);
557  compareValues(props, params, "setAllComponentRelative()");
558  params.reset();
559 
560  // setAllComponentAbsolute()
561  EXPECT_TRUE(rosparam->setAllComponentAbsolute());
562  getParameters("/" + tc->getName() + "/", params);
563  compareValues(props, params, "setAllComponentAbsolute()");
564  params.reset();
565 
566  // setAllComponentPrivate()
567  EXPECT_TRUE(rosparam->setAllComponentPrivate());
568  getParameters("~" + tc->getName() + "/", params);
569  compareValues(props, params, "setAllComponentPrivate()");
570  params.reset();
571 }
572 
573 TEST_F(ParamTest, GetAllPropertiesFromParameterServer)
574 {
575  // initialize parameters to some values
576  params.initialize();
577 
578  // getAllRelative()
579  setParameters("", params);
580  props.reset();
581  EXPECT_TRUE(rosparam->getAllRelative());
582  compareValues(params, props, "getAllRelative()");
583 
584  // getAllAbsolute()
585  setParameters("/", params);
586  props.reset();
587  EXPECT_TRUE(rosparam->getAllAbsolute());
588  compareValues(params, props, "getAllAbsolute()");
589 
590  // getAllPrivate()
591  setParameters("~", params);
592  props.reset();
593  EXPECT_TRUE(rosparam->getAllPrivate());
594  compareValues(params, props, "getAllPrivate()");
595 
596  // getAllComponentRelative()
597  setParameters("" + tc->getName() + "/", params);
598  props.reset();
599  EXPECT_TRUE(rosparam->getAllComponentRelative());
600  compareValues(params, props, "getAllComponentRelative()");
601 
602  // getAllComponentAbsolute()
603  setParameters("/" + tc->getName() + "/", params);
604  props.reset();
605  EXPECT_TRUE(rosparam->getAllComponentAbsolute());
606  compareValues(params, props, "getAllComponentAbsolute()");
607 
608  // getAllComponentPrivate()
609  setParameters("~" + tc->getName() + "/", params);
610  props.reset();
611  EXPECT_TRUE(rosparam->getAllComponentPrivate());
612  compareValues(params, props, "getAllComponentPrivate()");
613 }
614 
615 TEST_F(ParamTest, SetSinglePropertyOnParameterServer)
616 {
617  // initialize properties to some values
618  props.initialize();
619 
620  // setRelative()
621  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
622  prop_it != tc->properties()->end(); ++prop_it) {
623  EXPECT_TRUE(rosparam->setRelative((*prop_it)->getName()));
624  }
625  getParameters("", params);
626  compareValues(props, params, "setRelative()");
627  params.reset();
628 
629 // // setAbsolute()
630 // for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
631 // prop_it != tc->properties()->end(); ++prop_it) {
632 // EXPECT_TRUE(rosparam->setAbsolute((*prop_it)->getName()));
633 // }
634 // getParameters("/", params);
635 // compareValues(props, params, "setAbsolute()");
636 // params.reset();
637 
638  // setPrivate()
639  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
640  prop_it != tc->properties()->end(); ++prop_it) {
641  EXPECT_TRUE(rosparam->setPrivate((*prop_it)->getName()));
642  }
643  getParameters("~", params);
644  compareValues(props, params, "setPrivate()");
645  params.reset();
646 
647  // setComponentRelative()
648  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
649  prop_it != tc->properties()->end(); ++prop_it) {
650  EXPECT_TRUE(rosparam->setComponentRelative((*prop_it)->getName()));
651  }
652  getParameters(tc->getName() + "/", params);
653  compareValues(props, params, "setComponentRelative()");
654  params.reset();
655 
656  // setComponentAbsolute()
657  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
658  prop_it != tc->properties()->end(); ++prop_it) {
659  EXPECT_TRUE(rosparam->setComponentAbsolute((*prop_it)->getName()));
660  }
661  getParameters("/" + tc->getName() + "/", params);
662  compareValues(props, params, "setComponentAbsolute()");
663  params.reset();
664 
665  // setComponentPrivate()
666  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
667  prop_it != tc->properties()->end(); ++prop_it) {
668  EXPECT_TRUE(rosparam->setComponentPrivate((*prop_it)->getName()));
669  }
670  getParameters("~" + tc->getName() + "/", params);
671  compareValues(props, params, "setComponentPrivate()");
672  params.reset();
673 }
674 
675 TEST_F(ParamTest, GetSinglePropertyFromParameterServer)
676 {
677  // initialize parameters to some values
678  params.initialize();
679 
680  // getRelative()
681  setParameters("", params);
682  props.reset();
683  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
684  prop_it != tc->properties()->end(); ++prop_it) {
685  EXPECT_TRUE(rosparam->getRelative((*prop_it)->getName()));
686  }
687  compareValues(params, props, "getRelative()");
688 
689  // getAbsolute()
690  setParameters("/", params);
691  props.reset();
692  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
693  prop_it != tc->properties()->end(); ++prop_it) {
694  EXPECT_TRUE(rosparam->getAbsolute((*prop_it)->getName()));
695  }
696  compareValues(params, props, "getAbsolute()");
697 
698  // getPrivate()
699  setParameters("~", params);
700  props.reset();
701  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
702  prop_it != tc->properties()->end(); ++prop_it) {
703  EXPECT_TRUE(rosparam->getPrivate((*prop_it)->getName()));
704  }
705  compareValues(params, props, "getPrivate()");
706 
707  // getComponentRelative()
708  setParameters("" + tc->getName() + "/", params);
709  props.reset();
710  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
711  prop_it != tc->properties()->end(); ++prop_it) {
712  EXPECT_TRUE(rosparam->getComponentRelative((*prop_it)->getName()));
713  }
714  compareValues(params, props, "getComponentRelative()");
715 
716  // getComponentAbsolute()
717  setParameters("/" + tc->getName() + "/", params);
718  props.reset();
719  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
720  prop_it != tc->properties()->end(); ++prop_it) {
721  EXPECT_TRUE(rosparam->getComponentAbsolute((*prop_it)->getName()));
722  }
723  compareValues(params, props, "getComponentAbsolute()");
724 
725  // getComponentPrivate()
726  setParameters("~" + tc->getName() + "/", params);
727  props.reset();
728  for (PropertyBag::const_iterator prop_it = tc->properties()->begin();
729  prop_it != tc->properties()->end(); ++prop_it) {
730  EXPECT_TRUE(rosparam->getComponentPrivate((*prop_it)->getName()));
731  }
732  compareValues(params, props, "getComponentPrivate()");
733 }
734 
735 TEST_F(ParamTest, SetValueOnParameterServer)
736 {
737  // initialize properties to some values
738  props.initialize();
739 
740  // fetch parameters one by one
741  rosparam->setStringComponentPrivate("string", props.string_);
742  rosparam->setDoubleComponentPrivate("double", props.double_);
743  rosparam->setFloatComponentPrivate("float", props.float_);
744  rosparam->setIntComponentPrivate("int", props.int_);
745  rosparam->setBoolComponentPrivate("bool", props.bool_);
746  rosparam->setVectorOfStringComponentPrivate("vstring", props.v_string_);
747  rosparam->setVectorOfDoubleComponentPrivate("vdouble", props.v_double_);
748  rosparam->setVectorOfFloatComponentPrivate("vfloat", props.v_float_);
749  rosparam->setVectorOfIntComponentPrivate("vint", props.v_int_);
750  rosparam->setVectorOfBoolComponentPrivate("vbool", props.v_bool_);
751 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
752  rosparam->setEigenVectorXdComponentPrivate("eigenvectordouble", props.eigenvector_double_);
753  rosparam->setEigenVectorXfComponentPrivate("eigenvectorfloat", props.eigenvector_float_);
754 #endif
755  getParameters("~" + tc->getName() + "/", params, /* only_ros_types = */ true);
756  compareValues(props, params, "set[Type]ComponentPrivate()", /* only_ros_types = */ true);
757 }
758 
759 TEST_F(ParamTest, AddRosParamDataSources)
760 {
761  // initialize properties to some values
762  props.initialize();
763 
764  // Read in parameters through data source
765  ros::param::set("bool_parameter", props.bool_);
766  EXPECT_EQ(rosparam->addRosParamPropertyBool("bool_parameter").value(), props.bool_);
767  ros::param::set("double_parameter", props.double_);
768  EXPECT_EQ(rosparam->addRosParamPropertyDouble("double_parameter").value(), props.double_);
769  ros::param::set("float_parameter", props.float_);
770  EXPECT_EQ(rosparam->addRosParamPropertyFloat("float_parameter").value(), props.float_);
771  ros::param::set("int_parameter", props.int_);
772  EXPECT_EQ(rosparam->addRosParamPropertyInt("int_parameter").value(), props.int_);
773  ros::param::set("string_parameter", props.string_);
774  EXPECT_EQ(rosparam->addRosParamPropertyString("string_parameter").value(), props.string_);
775 
776  // change the props values to an alternative configuration
777  props.initialize_alternative();
778 
779  // Write out paramters through data source
780  bool in_bool;
781  double in_double;
782  float in_float;
783  int in_int;
784  std::string in_string;
785  tc->properties()->getPropertyType<bool>("bool_parameter")->set(props.bool_);
786  ros::param::get("bool_parameter", in_bool);
787  EXPECT_EQ(in_bool, props.bool_);
788  tc->properties()->getPropertyType<double>("double_parameter")->set(props.double_);
789  ros::param::get("double_parameter", in_double);
790  EXPECT_EQ(in_double, props.double_);
791  tc->properties()->getPropertyType<float>("float_parameter")->set(props.float_);
792  ros::param::get("float_parameter", in_float);
793  EXPECT_EQ(in_float, props.float_);
794  tc->properties()->getPropertyType<int>("int_parameter")->set(props.int_);
795  ros::param::get("int_parameter", in_int);
796  EXPECT_EQ(in_int, props.int_);
797  tc->properties()->getPropertyType<std::string>("string_parameter")->set(props.string_);
798  ros::param::get("string_parameter", in_string);
799  EXPECT_EQ(in_string, props.string_);
800 }
801 
802 TEST_F(ParamTest, GetValueFromParameterServer)
803 {
804  // initialize parameters to some values
805  params.initialize();
806  setParameters("~" + tc->getName() + "/", params);
807 
808  // fetch parameters one by one
809  props.reset();
810  EXPECT_TRUE(rosparam->getStringComponentPrivate("string", props.string_));
811  EXPECT_TRUE(rosparam->getDoubleComponentPrivate("double", props.double_));
812  EXPECT_TRUE(rosparam->getFloatComponentPrivate("float", props.float_));
813  EXPECT_TRUE(rosparam->getIntComponentPrivate("int", props.int_));
814  EXPECT_TRUE(rosparam->getBoolComponentPrivate("bool", props.bool_));
815  EXPECT_TRUE(rosparam->getVectorOfStringComponentPrivate("vstring", props.v_string_));
816  EXPECT_TRUE(rosparam->getVectorOfDoubleComponentPrivate("vdouble", props.v_double_));
817  EXPECT_TRUE(rosparam->getVectorOfFloatComponentPrivate("vfloat", props.v_float_));
818  EXPECT_TRUE(rosparam->getVectorOfIntComponentPrivate("vint", props.v_int_));
819  EXPECT_TRUE(rosparam->getVectorOfBoolComponentPrivate("vbool", props.v_bool_));
820 #ifdef RTT_ROSPARAM_EIGEN_SUPPORT
821  EXPECT_TRUE(rosparam->getEigenVectorXdComponentPrivate("eigenvectordouble", props.eigenvector_double_));
822  EXPECT_TRUE(rosparam->getEigenVectorXfComponentPrivate("eigenvectorfloat", props.eigenvector_float_));
823 #endif
824  compareValues(params, props, "get[Type]ComponentPrivate()", /* only_ros_types = */ true);
825 }
826 
827 int main(int argc, char** argv) {
828  testing::InitGoogleTest(&argc, argv);
829 
830  // Start ROS node
831  ros::M_string remappings;
832  remappings["__ns"] = "rtt_rosparam_namespace";
833  ros::init(remappings, "rtt_rosparam_tests_node", ros::init_options::AnonymousName);
834 
835  // Initialize Orocos
836  __os_init(argc, argv);
837 
838  RTT::Logger::log().setStdStream(std::cerr);
840 // RTT::Logger::log().setLogLevel(RTT::Logger::Debug);
841 
842  return RUN_ALL_TESTS();
843 }
844 
void serialize(Archive &a, std::pair< std::string, int > &pair, unsigned int)
Definition: param_tests.cpp:65
static void SetUpTestCase()
Definition: param_tests.cpp:96
iterator end()
ValueStruct::iterator iterator
std::vector< StringIntPair > pair_vector_
f
unsigned char uchar_
int __os_init(int argc, char **argv)
boost::shared_ptr< Service > service
int size() const
bool valid() const
COMPONENT_ABSOLUTE
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< unsigned char > v_uchar_
const_reference_t rvalue() const
Type const & getType() const
static boost::shared_ptr< ComponentLoader > Instance()
PRIVATE
RTT::PropertyBag bag_
geometry_msgs::Vector3 vector3_
std::string string_
std::map< std::string, std::string > M_string
bool ownProperty(base::PropertyBase *p)
std::vector< char > v_char_
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
int main(int argc, char **argv)
virtual void TearDown()
void getParameters(const std::string &prefix, Values &data, bool only_ros_types=false)
std::vector< unsigned int > v_uint_
TaskContext * tc
virtual void SetUp()
ROSCPP_DECL bool get(const std::string &key, std::string &s)
void mayLogStdOut(bool tf)
void initialize_alternative()
std::vector< bool > v_bool_
virtual std::string getType() const =0
std::vector< float > v_float_
TypeInfoRepository::shared_ptr Types()
Properties::const_iterator const_iterator
TEST_F(ParamTest, Constants)
static bool operator==(const ConnPolicy &, const ConnPolicy &)
void compareValues(const Values &expected, const Values &actual, const std::string &test_name, bool only_ros_types=false)
std::vector< double > v_double_
ROSCPP_DECL bool del(const std::string &key)
base::PropertyBase * getProperty(const std::string &name) const
bool hasMember(const std::string &name) const
ABSOLUTE
static Logger & log()
COMPONENT_PRIVATE
boost::shared_ptr< ROSParam > rosparam
const std::string & getName() const
void setParameters(const std::string &prefix, const Values &data)
std::vector< std::string > v_string_
StringIntPair pair_
std::vector< int > v_int_
void deleteParameters()
void setStdStream(std::ostream &stdos)
size_t size() const
unsigned int uint_
COMPONENT_RELATIVE
iterator begin()
COMPONENT
RELATIVE


rtt_rosparam_tests
Author(s): Johannes Meyer
autogenerated on Mon May 10 2021 02:45:40