tesseract_common_serialization_unit.cpp
Go to the documentation of this file.
1 
27 #include <gtest/gtest.h>
28 #include <boost/serialization/shared_ptr.hpp>
29 #include <boost/serialization/nvp.hpp>
31 
35 #include <tesseract_common/utils.h>
47 
48 namespace tesseract_common
49 {
50 bool operator==(const ProfileDictionary& lhs, const ProfileDictionary& rhs)
51 {
52  using DataContainer =
53  std::unordered_map<std::string,
54  std::unordered_map<std::size_t, std::unordered_map<std::string, Profile::ConstPtr>>>;
55 
56  DataContainer lhs_data = lhs.getAllProfileEntries();
57  DataContainer rhs_data = rhs.getAllProfileEntries();
58 
59  bool equal = true;
60  equal &= lhs_data.size() == rhs_data.size();
61  equal &= lhs_data.at("test_namespace_1").size() == rhs_data.at("test_namespace_1").size();
62  equal &= lhs_data.at("test_namespace_2").size() == rhs_data.at("test_namespace_2").size();
63  equal &= lhs_data.at("test_namespace_1").at(100).size() == rhs_data.at("test_namespace_1").at(100).size();
64  equal &= lhs_data.at("test_namespace_2").at(200).size() == rhs_data.at("test_namespace_2").at(200).size();
65  return equal;
66 }
67 
68 bool operator!=(const ProfileDictionary& lhs, const ProfileDictionary& rhs) { return !(lhs == rhs); }
69 } // namespace tesseract_common
70 
71 using namespace tesseract_common;
72 
73 class TestProfile : public Profile
74 {
75 public:
76  TestProfile() = default;
77  ~TestProfile() override = default;
78  TestProfile(std::size_t key) : Profile(key){};
79  TestProfile(const TestProfile&) = default;
80  TestProfile& operator=(const TestProfile&) = default;
81  TestProfile(TestProfile&&) = default;
82  TestProfile& operator=(TestProfile&&) = default;
83 
84  bool operator==(const TestProfile& rhs) const { return (key_ == rhs.key_); };
85  bool operator!=(const TestProfile& rhs) const { return !operator==(rhs); };
86 
87 protected:
88  friend class boost::serialization::access;
90  template <class Archive>
91  void serialize(Archive& ar, const unsigned int) // NOLINT
92  {
93  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Profile);
94  }
95 };
96 
97 BOOST_CLASS_EXPORT_KEY(TestProfile)
99 BOOST_CLASS_EXPORT_IMPLEMENT(TestProfile)
100 
101 TEST(TesseractCommonSerializeUnit, Profile) // NOLINT
102 {
103  TestProfile profile(100);
104  EXPECT_EQ(profile.getKey(), 100);
105  tesseract_common::testSerialization<TestProfile>(profile, "TestProfile");
106 }
107 
108 TEST(TesseractCommonSerializeUnit, ProfileDictionary) // NOLINT
109 {
110  auto profile_a = std::make_shared<TestProfile>(100);
111  auto profile_b = std::make_shared<TestProfile>(100);
112  auto profile_c = std::make_shared<TestProfile>(200);
113  auto profile_d = std::make_shared<TestProfile>(200);
114 
115  ProfileDictionary profile_dictionary;
116  profile_dictionary.addProfile("test_namespace_1", "profile_a", profile_a);
117  profile_dictionary.addProfile("test_namespace_1", "profile_b", profile_b);
118  profile_dictionary.addProfile("test_namespace_2", "profile_c", profile_c);
119  profile_dictionary.addProfile("test_namespace_2", "profile_c", profile_d);
120 
121  tesseract_common::testSerialization<ProfileDictionary>(profile_dictionary, "ProfileDictionary");
122 }
123 
124 TEST(TesseractCommonSerializeUnit, GeneralResourceLocator) // NOLINT
125 {
126  GeneralResourceLocator locator;
127  tesseract_common::testSerialization<GeneralResourceLocator>(locator, "GeneralResourceLocator");
128 }
129 
130 TEST(TesseractCommonSerializeUnit, KinematicLimits) // NOLINT
131 {
132  KinematicLimits limits;
133  limits.resize(3);
134  EXPECT_EQ(limits.joint_limits.rows(), 3);
135  EXPECT_EQ(limits.velocity_limits.rows(), 3);
136  EXPECT_EQ(limits.acceleration_limits.rows(), 3);
137 
138  limits.joint_limits << -5, 5, -5, 5, -5, 5;
139  limits.velocity_limits << -6, 6, -6, 6, -6, 6;
140  limits.acceleration_limits << -7, 7, -7, 7, -7, 7;
141 
142  tesseract_common::testSerialization<KinematicLimits>(limits, "KinematicLimits");
143 }
144 
145 TEST(TesseractCommonSerializeUnit, ManipulatorInfo) // NOLINT
146 {
147  ManipulatorInfo manip_info("manipulator", "world", "tool0");
148  tesseract_common::testSerialization<ManipulatorInfo>(manip_info, "ManipulatorInfo");
149 
150  ManipulatorInfo manip_info2("manipulator", "world", "tool0");
151  manip_info2.tcp_offset = "tool0";
152  tesseract_common::testSerialization<ManipulatorInfo>(manip_info2, "ManipulatorInfo2");
153 }
154 
155 TEST(TesseractCommonSerializeUnit, JointState) // NOLINT
156 {
157  JointState joint_state;
158  joint_state.joint_names = { "joint_1", "joint_2", "joint_3" };
159  joint_state.position = Eigen::VectorXd::Constant(3, 5);
160  joint_state.velocity = Eigen::VectorXd::Constant(3, 6);
161  joint_state.acceleration = Eigen::VectorXd::Constant(3, 7);
162  joint_state.effort = Eigen::VectorXd::Constant(3, 8);
163  joint_state.time = 100;
164 
165  tesseract_common::testSerialization<JointState>(joint_state, "JointState");
166 }
167 
168 TEST(TesseractCommonSerializeUnit, JointTrajectory) // NOLINT
169 {
170  JointState joint_state;
171  joint_state.joint_names = { "joint_1", "joint_2", "joint_3" };
172  joint_state.position = Eigen::VectorXd::Constant(3, 5);
173  joint_state.velocity = Eigen::VectorXd::Constant(3, 6);
174  joint_state.acceleration = Eigen::VectorXd::Constant(3, 7);
175  joint_state.effort = Eigen::VectorXd::Constant(3, 8);
176  joint_state.time = 100;
177 
178  JointTrajectory trajectory;
179  trajectory.states.push_back(joint_state);
180  trajectory.description = "this is a test";
181 
182  tesseract_common::testSerialization<JointTrajectory>(trajectory, "JointTrajectory");
183 }
184 
185 TEST(TesseractCommonSerializeUnit, AllowedCollisionMatrix) // NOLINT
186 {
187  auto object = std::make_shared<AllowedCollisionMatrix>();
188  tesseract_common::testSerialization<AllowedCollisionMatrix>(*object, "EmptyAllowedCollisionMatrix");
189  object->addAllowedCollision("link_1", "link2", "reason1");
190  object->addAllowedCollision("link_2", "link1", "reason2");
191  object->addAllowedCollision("link_4", "link3", "reason3");
192  object->addAllowedCollision("link_5", "link2", "reason4");
193  tesseract_common::testSerialization<AllowedCollisionMatrix>(*object, "AllowedCollisionMatrix");
194 }
195 
196 TEST(TesseractCommonSerializeUnit, CalibrationInfo) // NOLINT
197 {
198  auto object = std::make_shared<CalibrationInfo>();
199  tesseract_common::testSerialization<CalibrationInfo>(*object, "EmptyCalibrationInfo");
200  object->joints["test"].setIdentity();
201  object->joints["test"].translate(Eigen::Vector3d(2, 4, 8));
202  tesseract_common::testSerialization<CalibrationInfo>(*object, "CalibrationInfo");
203 }
204 
205 TEST(TesseractCommonSerializeUnit, CollisionMarginData) // NOLINT
206 {
207  auto object = std::make_shared<CollisionMarginData>();
208  tesseract_common::testSerialization<CollisionMarginData>(*object, "EmptyCollisionMarginData");
209  object->setCollisionMargin("link_1", "link2", 1.1);
210  object->setCollisionMargin("link_2", "link1", 2.2);
211  object->setCollisionMargin("link_4", "link3", 3.3);
212  object->setCollisionMargin("link_5", "link2", -4.4);
213  tesseract_common::testSerialization<CollisionMarginData>(*object, "CollisionMarginData");
214 }
215 
216 TEST(TesseractCommonSerializeUnit, ContactManagersPluginInfo) // NOLINT
217 {
218  auto object = std::make_shared<ContactManagersPluginInfo>();
219  object->search_paths.insert("path 1");
220  object->search_paths.insert("path 2");
221  object->search_libraries.insert("search_libraries 1");
222  object->search_libraries.insert("search_libraries 2");
223  object->search_libraries.insert("search_libraries 3");
224 
225  {
226  PluginInfoContainer container;
227  PluginInfo plugin;
228  plugin.class_name = "test_class_name";
229  plugin.config["test"] = "value";
230  object->discrete_plugin_infos.default_plugin = "test_string";
231  object->discrete_plugin_infos.plugins["plugin_key"] = plugin;
232  }
233  {
234  PluginInfoContainer container;
235  PluginInfo plugin;
236  plugin.class_name = "test_class_name 2";
237  plugin.config["test2"] = "value2";
238  object->continuous_plugin_infos.default_plugin = "test_string2";
239  object->continuous_plugin_infos.plugins["plugin_key2"] = plugin;
240  }
241 
242  tesseract_common::testSerialization<ContactManagersPluginInfo>(*object, "ContactManagersPluginInfo");
243 }
244 
245 TEST(TesseractCommonSerializeUnit, TaskComposerPluginInfo) // NOLINT
246 {
247  auto object = std::make_shared<TaskComposerPluginInfo>();
248  object->search_paths.insert("path 1");
249  object->search_paths.insert("path 2");
250  object->search_libraries.insert("search_libraries 1");
251  object->search_libraries.insert("search_libraries 2");
252  object->search_libraries.insert("search_libraries 3");
253 
254  {
255  PluginInfo plugin;
256  plugin.class_name = "test_class_name";
257  plugin.config["test"] = "value";
258  object->executor_plugin_infos.default_plugin = "test_string";
259  object->executor_plugin_infos.plugins["plugin_key"] = plugin;
260  }
261  {
262  PluginInfo plugin;
263  plugin.class_name = "test_class_name 2";
264  plugin.config["test2"] = "value2";
265  object->task_plugin_infos.default_plugin = "test_string2";
266  object->task_plugin_infos.plugins["plugin_key2"] = plugin;
267  }
268 
269  tesseract_common::testSerialization<TaskComposerPluginInfo>(*object, "TaskComposerPluginInfo");
270 }
271 
272 TEST(TesseractCommonSerializeUnit, KinematicsPluginInfo) // NOLINT
273 {
274  auto object = std::make_shared<KinematicsPluginInfo>();
275  object->search_paths.insert("path 1");
276  object->search_paths.insert("path 2");
277  object->search_libraries.insert("search_libraries 1");
278  object->search_libraries.insert("search_libraries 2");
279  object->search_libraries.insert("search_libraries 3");
280 
281  {
282  PluginInfo plugin;
283  plugin.class_name = "test_class_name";
284  plugin.config["test"] = "value";
285  object->fwd_plugin_infos["plugin 1"].default_plugin = "test_string";
286  object->fwd_plugin_infos["plugin 1"].plugins["plugin_key"] = plugin;
287  object->fwd_plugin_infos["plugin 2"].default_plugin = "test_string2";
288  object->fwd_plugin_infos["plugin 2"].plugins["plugin_key2"] = plugin;
289  }
290  {
291  PluginInfo plugin;
292  plugin.class_name = "test_class_name 2";
293  plugin.config["test2"] = "value2";
294  object->inv_plugin_infos["inv plugin 1"].default_plugin = "test_string3";
295  object->inv_plugin_infos["inv plugin 1"].plugins["plugin_key3"] = plugin;
296  object->inv_plugin_infos["inv plugin 2"].default_plugin = "test_string4";
297  object->inv_plugin_infos["inv plugin 2"].plugins["plugin_key4"] = plugin;
298  }
299 
300  tesseract_common::testSerialization<KinematicsPluginInfo>(*object, "KinematicsPluginInfo");
301 }
302 
303 TEST(TesseractCommonSerializeUnit, PluginInfo) // NOLINT
304 {
305  auto object = std::make_shared<PluginInfo>();
306  object->class_name = "test_class_name";
307  object->config["test"] = M_PI;
308  tesseract_common::testSerialization<PluginInfo>(*object, "PluginInfo");
309 }
310 
311 TEST(TesseractCommonSerializeUnit, PluginInfoContainer) // NOLINT
312 {
313  auto object = std::make_shared<PluginInfoContainer>();
314  auto plugin = std::make_shared<PluginInfo>();
315  plugin->class_name = "test_class_name";
316  plugin->config["test"] = "value";
317  object->default_plugin = "test_string";
318  object->plugins["plugin_key"] = *plugin;
319  tesseract_common::testSerialization<PluginInfoContainer>(*object, "PluginInfoContainer");
320 }
321 
322 TEST(TesseractCommonSerializeUnit, VectorXd) // NOLINT
323 {
324  { // Serialize empty object
325  Eigen::VectorXd ev;
326  {
327  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xd_boost.xml");
328  boost::archive::xml_oarchive oa(os);
329  oa << BOOST_SERIALIZATION_NVP(ev);
330  }
331 
332  Eigen::VectorXd nev;
333  {
334  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xd_boost.xml");
335  assert(ifs.good());
336  boost::archive::xml_iarchive ia(ifs);
337 
338  // restore the schedule from the archive
339  ia >> BOOST_SERIALIZATION_NVP(nev);
340  }
341  }
342 
343  // Serialize to object which already has data
344  for (int i = 0; i < 5; ++i)
345  {
346  Eigen::VectorXd ev = Eigen::VectorXd::Random(6);
347 
348  {
349  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xd_boost.xml");
350  boost::archive::xml_oarchive oa(os);
351  oa << BOOST_SERIALIZATION_NVP(ev);
352  }
353 
354  Eigen::VectorXd nev = Eigen::VectorXd::Random(6);
355  {
356  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xd_boost.xml");
357  assert(ifs.good());
358  boost::archive::xml_iarchive ia(ifs);
359 
360  // restore the schedule from the archive
361  ia >> BOOST_SERIALIZATION_NVP(nev);
362  }
363 
364  EXPECT_TRUE(ev.isApprox(nev, 1e-5));
365  }
366 
367  // Serialize to object which already has data and different size
368  for (int i = 0; i < 5; ++i)
369  {
370  Eigen::VectorXd ev = Eigen::VectorXd::Random(6);
371 
372  {
373  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xd_boost.xml");
374  boost::archive::xml_oarchive oa(os);
375  oa << BOOST_SERIALIZATION_NVP(ev);
376  }
377 
378  Eigen::VectorXd nev = Eigen::VectorXd::Random(3);
379  {
380  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xd_boost.xml");
381  assert(ifs.good());
382  boost::archive::xml_iarchive ia(ifs);
383 
384  // restore the schedule from the archive
385  ia >> BOOST_SERIALIZATION_NVP(nev);
386  }
387 
388  EXPECT_TRUE(ev.isApprox(nev, 1e-5));
389  }
390 
391  // Default use case
392  for (int i = 0; i < 5; ++i)
393  {
394  Eigen::VectorXd ev = Eigen::VectorXd::Random(6);
395 
396  {
397  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xd_boost.xml");
398  boost::archive::xml_oarchive oa(os);
399  oa << BOOST_SERIALIZATION_NVP(ev);
400  }
401 
402  Eigen::VectorXd nev;
403  {
404  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xd_boost.xml");
405  assert(ifs.good());
406  boost::archive::xml_iarchive ia(ifs);
407 
408  // restore the schedule from the archive
409  ia >> BOOST_SERIALIZATION_NVP(nev);
410  }
411 
412  EXPECT_TRUE(ev.isApprox(nev, 1e-5));
413  }
414 }
415 
416 TEST(TesseractCommonSerializeUnit, VectorXi) // NOLINT
417 {
418  { // Serialize empty object
419  Eigen::VectorXi ev;
420  {
421  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
422  boost::archive::xml_oarchive oa(os);
423  oa << BOOST_SERIALIZATION_NVP(ev);
424  }
425 
426  Eigen::VectorXi nev;
427  {
428  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
429  assert(ifs.good());
430  boost::archive::xml_iarchive ia(ifs);
431 
432  // restore the schedule from the archive
433  ia >> BOOST_SERIALIZATION_NVP(nev);
434  }
435  }
436 
437  // Serialize to object which already has data
438  for (int i = 0; i < 5; ++i)
439  {
440  Eigen::VectorXi ev = Eigen::VectorXi::Random(6);
441 
442  {
443  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
444  boost::archive::xml_oarchive oa(os);
445  oa << BOOST_SERIALIZATION_NVP(ev);
446  }
447 
448  Eigen::VectorXi nev = Eigen::VectorXi::Random(6);
449  {
450  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
451  assert(ifs.good());
452  boost::archive::xml_iarchive ia(ifs);
453 
454  // restore the schedule from the archive
455  ia >> BOOST_SERIALIZATION_NVP(nev);
456  }
457 
458  EXPECT_TRUE(ev == nev);
459  }
460 
461  // Serialize to object which already has data and different size
462  for (int i = 0; i < 5; ++i)
463  {
464  Eigen::VectorXi ev = Eigen::VectorXi::Random(6);
465 
466  {
467  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
468  boost::archive::xml_oarchive oa(os);
469  oa << BOOST_SERIALIZATION_NVP(ev);
470  }
471 
472  Eigen::VectorXi nev = Eigen::VectorXi::Random(3);
473  {
474  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
475  assert(ifs.good());
476  boost::archive::xml_iarchive ia(ifs);
477 
478  // restore the schedule from the archive
479  ia >> BOOST_SERIALIZATION_NVP(nev);
480  }
481 
482  EXPECT_TRUE(ev == nev);
483  }
484 
485  // Default use case
486  for (int i = 0; i < 5; ++i)
487  {
488  Eigen::VectorXi ev = Eigen::VectorXi::Random(6);
489 
490  {
491  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
492  boost::archive::xml_oarchive oa(os);
493  oa << BOOST_SERIALIZATION_NVP(ev);
494  }
495 
496  Eigen::VectorXi nev;
497  {
498  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
499  assert(ifs.good());
500  boost::archive::xml_iarchive ia(ifs);
501 
502  // restore the schedule from the archive
503  ia >> BOOST_SERIALIZATION_NVP(nev);
504  }
505 
506  EXPECT_TRUE(ev == nev);
507  }
508 }
509 
510 TEST(TesseractCommonSerializeUnit, Vector3d) // NOLINT
511 {
512  { // Serialize empty object
513  Eigen::Vector3d ev = Eigen::Vector3d::Zero();
514  {
515  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
516  boost::archive::xml_oarchive oa(os);
517  oa << BOOST_SERIALIZATION_NVP(ev);
518  }
519 
520  Eigen::Vector3d nev;
521  {
522  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
523  assert(ifs.good());
524  boost::archive::xml_iarchive ia(ifs);
525 
526  // restore the schedule from the archive
527  ia >> BOOST_SERIALIZATION_NVP(nev);
528  }
529  }
530 
531  // Serialize to object which already has data
532  for (int i = 0; i < 3; ++i)
533  {
534  Eigen::Vector3d ev = Eigen::Vector3d::Random();
535 
536  {
537  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
538  boost::archive::xml_oarchive oa(os);
539  oa << BOOST_SERIALIZATION_NVP(ev);
540  }
541 
542  Eigen::Vector3d nev = Eigen::Vector3d::Random();
543  {
544  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
545  assert(ifs.good());
546  boost::archive::xml_iarchive ia(ifs);
547 
548  // restore the schedule from the archive
549  ia >> BOOST_SERIALIZATION_NVP(nev);
550  }
551 
552  EXPECT_TRUE(ev.isApprox(nev, 1e-5));
553  }
554 
555  // Default use case
556  for (int i = 0; i < 3; ++i)
557  {
558  Eigen::Vector3d ev = Eigen::Vector3d::Random();
559 
560  {
561  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
562  boost::archive::xml_oarchive oa(os);
563  oa << BOOST_SERIALIZATION_NVP(ev);
564  }
565 
566  Eigen::Vector3d nev;
567  {
568  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
569  assert(ifs.good());
570  boost::archive::xml_iarchive ia(ifs);
571 
572  // restore the schedule from the archive
573  ia >> BOOST_SERIALIZATION_NVP(nev);
574  }
575 
576  EXPECT_TRUE(ev.isApprox(nev, 1e-5));
577  }
578 }
579 
580 TEST(TesseractCommonSerializeUnit, Vector4d) // NOLINT
581 {
582  { // Serialize empty object
583  Eigen::Vector4d ev = Eigen::Vector4d::Zero();
584  {
585  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
586  boost::archive::xml_oarchive oa(os);
587  oa << BOOST_SERIALIZATION_NVP(ev);
588  }
589 
590  Eigen::Vector4d nev;
591  {
592  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
593  assert(ifs.good());
594  boost::archive::xml_iarchive ia(ifs);
595 
596  // restore the schedule from the archive
597  ia >> BOOST_SERIALIZATION_NVP(nev);
598  }
599  }
600 
601  // Serialize to object which already has data
602  for (int i = 0; i < 4; ++i)
603  {
604  Eigen::Vector4d ev = Eigen::Vector4d::Random();
605 
606  {
607  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
608  boost::archive::xml_oarchive oa(os);
609  oa << BOOST_SERIALIZATION_NVP(ev);
610  }
611 
612  Eigen::Vector4d nev = Eigen::Vector4d::Random();
613  {
614  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
615  assert(ifs.good());
616  boost::archive::xml_iarchive ia(ifs);
617 
618  // restore the schedule from the archive
619  ia >> BOOST_SERIALIZATION_NVP(nev);
620  }
621 
622  EXPECT_TRUE(ev.isApprox(nev, 1e-5));
623  }
624 
625  // Default use case
626  for (int i = 0; i < 4; ++i)
627  {
628  Eigen::Vector4d ev = Eigen::Vector4d::Random();
629 
630  {
631  std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
632  boost::archive::xml_oarchive oa(os);
633  oa << BOOST_SERIALIZATION_NVP(ev);
634  }
635 
636  Eigen::Vector4d nev;
637  {
638  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
639  assert(ifs.good());
640  boost::archive::xml_iarchive ia(ifs);
641 
642  // restore the schedule from the archive
643  ia >> BOOST_SERIALIZATION_NVP(nev);
644  }
645 
646  EXPECT_TRUE(ev.isApprox(nev, 1e-5));
647  }
648 }
649 
650 TEST(TesseractCommonSerializeUnit, MatrixX2d) // NOLINT
651 {
652  { // Serialize empty
653  Eigen::MatrixX2d em;
654 
655  {
656  std::ofstream os(tesseract_common::getTempPath() + "eigen_matrix_x2d_boost.xml");
657  boost::archive::xml_oarchive oa(os);
658  oa << BOOST_SERIALIZATION_NVP(em);
659  }
660 
661  Eigen::MatrixX2d nem;
662  {
663  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_matrix_x2d_boost.xml");
664  assert(ifs.good());
665  boost::archive::xml_iarchive ia(ifs);
666 
667  // restore the schedule from the archive
668  ia >> BOOST_SERIALIZATION_NVP(nem);
669  }
670 
671  EXPECT_TRUE(em.isApprox(nem, 1e-5));
672  }
673 
674  // Serialize to object which already has data
675  for (int i = 0; i < 5; ++i)
676  {
677  Eigen::MatrixX2d em = Eigen::MatrixX2d::Random(4, 2);
678 
679  {
680  std::ofstream os(tesseract_common::getTempPath() + "eigen_matrix_x2d_boost.xml");
681  boost::archive::xml_oarchive oa(os);
682  oa << BOOST_SERIALIZATION_NVP(em);
683  }
684 
685  Eigen::MatrixX2d nem = Eigen::MatrixX2d::Random(4, 2);
686  {
687  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_matrix_x2d_boost.xml");
688  assert(ifs.good());
689  boost::archive::xml_iarchive ia(ifs);
690 
691  // restore the schedule from the archive
692  ia >> BOOST_SERIALIZATION_NVP(nem);
693  }
694 
695  EXPECT_TRUE(em.isApprox(nem, 1e-5));
696  }
697 
698  // Serialize to object which already has data and different size
699  for (int i = 0; i < 5; ++i)
700  {
701  Eigen::MatrixX2d em = Eigen::MatrixX2d::Random(4, 2);
702 
703  {
704  std::ofstream os(tesseract_common::getTempPath() + "eigen_matrix_x2d_boost.xml");
705  boost::archive::xml_oarchive oa(os);
706  oa << BOOST_SERIALIZATION_NVP(em);
707  }
708 
709  Eigen::MatrixX2d nem = Eigen::MatrixX2d::Random(2, 2);
710  {
711  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_matrix_x2d_boost.xml");
712  assert(ifs.good());
713  boost::archive::xml_iarchive ia(ifs);
714 
715  // restore the schedule from the archive
716  ia >> BOOST_SERIALIZATION_NVP(nem);
717  }
718 
719  EXPECT_TRUE(em.isApprox(nem, 1e-5));
720  }
721 
722  // Default
723  for (int i = 0; i < 5; ++i)
724  {
725  Eigen::MatrixX2d em = Eigen::MatrixX2d::Random(4, 2);
726 
727  {
728  std::ofstream os(tesseract_common::getTempPath() + "eigen_matrix_x2d_boost.xml");
729  boost::archive::xml_oarchive oa(os);
730  oa << BOOST_SERIALIZATION_NVP(em);
731  }
732 
733  Eigen::MatrixX2d nem;
734  {
735  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_matrix_x2d_boost.xml");
736  assert(ifs.good());
737  boost::archive::xml_iarchive ia(ifs);
738 
739  // restore the schedule from the archive
740  ia >> BOOST_SERIALIZATION_NVP(nem);
741  }
742 
743  EXPECT_TRUE(em.isApprox(nem, 1e-5));
744  }
745 }
746 
747 TEST(TesseractCommonSerializeUnit, Isometry3d) // NOLINT
748 {
749  for (int i = 0; i < 5; ++i)
750  {
751  Eigen::Isometry3d pose =
752  Eigen::Isometry3d::Identity() * Eigen::AngleAxisd(M_PI, Eigen::Vector3d::Random().normalized());
753  pose.translation() = Eigen::Vector3d::Random();
754 
755  {
756  std::ofstream os(tesseract_common::getTempPath() + "eigen_isometry3d_boost.xml");
757  boost::archive::xml_oarchive oa(os);
758  oa << BOOST_SERIALIZATION_NVP(pose);
759  }
760 
761  Eigen::Isometry3d npose;
762  {
763  std::ifstream ifs(tesseract_common::getTempPath() + "eigen_isometry3d_boost.xml");
764  assert(ifs.good());
765  boost::archive::xml_iarchive ia(ifs);
766 
767  // restore the schedule from the archive
768  ia >> BOOST_SERIALIZATION_NVP(npose);
769  }
770 
771  EXPECT_TRUE(pose.isApprox(npose, 1e-5));
772  }
773 }
774 
777 {
778  std::atomic<bool> value{ true };
779 
780  TestAtomic() = default;
781  ~TestAtomic() = default;
782  TestAtomic(const TestAtomic& other) { *this = other; }
784  {
785  value = other.value.load();
786  return *this;
787  }
788  TestAtomic(TestAtomic&& other) noexcept : value(other.value.load()) {}
789  TestAtomic& operator=(TestAtomic&& other) noexcept
790  {
791  value = other.value.load();
792  return *this;
793  }
794 
795  bool operator==(const TestAtomic& rhs) const { return rhs.value.load() == value.load(); }
796  bool operator!=(const TestAtomic& rhs) const { return rhs.value.load() != value.load(); }
797 
798  friend class boost::serialization::access;
800  template <class Archive>
801  void serialize(Archive& ar, const unsigned int /*version*/) // NOLINT
802  {
803  ar& BOOST_SERIALIZATION_NVP(value);
804  }
805 };
806 
808 BOOST_CLASS_EXPORT_IMPLEMENT(TestAtomic)
809 
810 TEST(TesseractCommonSerializeUnit, StdAtomic) // NOLINT
811 {
812  TestAtomic object;
813  object.value = true;
814  tesseract_common::testSerialization<TestAtomic>(object, "TestAtomic");
815 }
816 
818 {
819  double a{ 0 };
820 };
821 
823 
825 {
826  double b{ 0 };
827 };
828 
829 TEST(TesseractCommonSerializeUnit, ExtensionXmlMacro) // NOLINT
830 {
832  EXPECT_EQ(ext, ".etax");
833 
835  EXPECT_EQ(default_ext, ".trsx");
836 }
837 
838 TEST(TesseractCommonSerializeUnit, ExtensionBinaryMacro) // NOLINT
839 {
841  EXPECT_EQ(ext, ".etab");
842 
844  EXPECT_EQ(default_ext, ".trsb");
845 }
846 
847 int main(int argc, char** argv)
848 {
849  testing::InitGoogleTest(&argc, argv);
850 
851  return RUN_ALL_TESTS();
852 }
allowed_collision_matrix.h
profile.h
This is a profile base class.
tesseract_common::getTempPath
std::string getTempPath()
Get the host temp directory path.
Definition: utils.cpp:262
tesseract_common
Definition: allowed_collision_matrix.h:19
TestProfile::operator==
bool operator==(const TestProfile &rhs) const
Definition: tesseract_common_serialization_unit.cpp:84
TestAtomic
Atomic do not have a copy constructor so must have implement one for your class.
Definition: tesseract_common_serialization_unit.cpp:776
tesseract_common::KinematicLimits::resize
void resize(Eigen::Index size)
Definition: kinematic_limits.cpp:37
tesseract_common::KinematicLimits
Store kinematic limits.
Definition: kinematic_limits.h:41
TestAtomic::serialize
void serialize(Archive &ar, const unsigned int)
Definition: tesseract_common_serialization_unit.cpp:801
tesseract_common::JointState::effort
Eigen::VectorXd effort
The Effort at the waypoint (optional)
Definition: joint_state.h:68
collision_margin_data.h
This is used to store collision margin information.
tesseract_common::JointTrajectory::description
std::string description
Definition: joint_state.h:93
tesseract_common::serialization::xml::extension
Definition: serialization_extensions.h:42
unit_test_utils.h
Common Tesseract unit test utilities.
tesseract_common::ManipulatorInfo
Contains information about a robot manipulator.
Definition: manipulator_info.h:44
tesseract_common::JointState::velocity
Eigen::VectorXd velocity
The velocity at the waypoint (optional)
Definition: joint_state.h:62
TESSERACT_SERIALIZE_ARCHIVES_INSTANTIATE
#define TESSERACT_SERIALIZE_ARCHIVES_INSTANTIATE(Type)
Definition: serialization.h:49
tesseract_common::TaskComposerPluginInfo
The task composer plugin information structure.
Definition: plugin_info.h:172
macros.h
Common Tesseract Macros.
tesseract_common::PluginInfoContainer
Definition: plugin_info.h:81
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
TestAtomic::TestAtomic
TestAtomic(const TestAtomic &other)
Definition: tesseract_common_serialization_unit.cpp:782
atomic_serialization.h
Additional Boost serialization wrappers.
TestAtomic::value
std::atomic< bool > value
Definition: tesseract_common_serialization_unit.cpp:778
tesseract_common::Serialization
Definition: serialization.h:97
TestProfile::operator!=
bool operator!=(const TestProfile &rhs) const
Definition: tesseract_common_serialization_unit.cpp:85
tesseract_common::CollisionMarginData
Stores information about how the margins allowed between collision objects.
Definition: collision_margin_data.h:159
TESSERACT_CLASS_EXTENSION
#define TESSERACT_CLASS_EXTENSION(T, X, B)
A macro for defining serialization extension for classes.
Definition: serialization_extensions.h:85
tesseract_common::ProfileDictionary::getAllProfileEntries
std::unordered_map< std::string, std::unordered_map< std::size_t, std::unordered_map< std::string, Profile::ConstPtr > > > getAllProfileEntries() const
Get all profile entries.
Definition: profile_dictionary.cpp:118
ExtensionMacroTestA
Definition: tesseract_common_serialization_unit.cpp:817
TestProfile::TestProfile
TestProfile(std::size_t key)
Definition: tesseract_common_serialization_unit.cpp:78
tesseract_common::serialization::binary::extension
Definition: serialization_extensions.h:61
tesseract_common::JointState
Definition: joint_state.h:49
TEST
TEST(TesseractCommonSerializeUnit, Profile)
Definition: tesseract_common_serialization_unit.cpp:101
tesseract_common::ManipulatorInfo::tcp_offset
std::variant< std::string, Eigen::Isometry3d > tcp_offset
(Optional) Offset transform applied to the tcp_frame link to represent the manipulator TCP
Definition: manipulator_info.h:73
tesseract_common::PluginInfo::class_name
std::string class_name
The plugin class name.
Definition: plugin_info.h:54
manipulator_info.h
tesseract_common::JointState::joint_names
std::vector< std::string > joint_names
The joint corresponding to the position vector.
Definition: joint_state.h:56
utils.h
Common Tesseract Utility Functions.
plugin_info.h
Common Tesseract Plugin Infos.
tesseract_common::operator!=
bool operator!=(const ProfileDictionary &lhs, const ProfileDictionary &rhs)
Definition: tesseract_common_serialization_unit.cpp:68
main
int main(int argc, char **argv)
Definition: tesseract_common_serialization_unit.cpp:847
tesseract_common::CalibrationInfo
The CalibrationInfo struct.
Definition: calibration_info.h:41
tesseract_common::JointState::acceleration
Eigen::VectorXd acceleration
The Acceleration at the waypoint (optional)
Definition: joint_state.h:65
tesseract_common::JointTrajectory
Represents a joint trajectory.
Definition: joint_state.h:85
tesseract_common::ContactManagersPluginInfo
The contact managers plugin information structure.
Definition: plugin_info.h:135
tesseract_common::PluginInfo
The Plugin Information struct.
Definition: plugin_info.h:51
tesseract_common::operator==
bool operator==(const AllowedCollisionEntries &entries_1, const AllowedCollisionEntries &entries_2)
Definition: allowed_collision_matrix.cpp:42
joint_state.h
Tesseract Joint State.
TestAtomic::operator=
TestAtomic & operator=(const TestAtomic &other)
Definition: tesseract_common_serialization_unit.cpp:783
ExtensionMacroTestB
Definition: tesseract_common_serialization_unit.cpp:824
tesseract_common::KinematicsPluginInfo
The kinematics plugin information structure.
Definition: plugin_info.h:98
tesseract_common::Profile
The Profile class.
Definition: profile.h:39
eigen_serialization.h
tesseract_common::PluginInfo::config
YAML::Node config
The plugin config data.
Definition: plugin_info.h:57
tesseract_common::JointState::time
double time
The Time from start at the waypoint (optional)
Definition: joint_state.h:71
TestProfile::serialize
void serialize(Archive &ar, const unsigned int)
Definition: tesseract_common_serialization_unit.cpp:91
tesseract_common::ProfileDictionary
This class is used to store profiles used by various tasks.
Definition: profile_dictionary.h:46
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
Definition: macros.h:72
calibration_info.h
Calibration Information.
tesseract_common::AllowedCollisionMatrix
Definition: allowed_collision_matrix.h:28
resource_locator.h
Locate and retrieve resource data.
tesseract_common::KinematicLimits::acceleration_limits
Eigen::MatrixX2d acceleration_limits
The acceleration limits.
Definition: kinematic_limits.h:54
tesseract_common::KinematicLimits::velocity_limits
Eigen::MatrixX2d velocity_limits
The velocity limits.
Definition: kinematic_limits.h:51
kinematic_limits.h
Common Tesseract Kinematic Limits and Related Utility Functions.
serialization.h
Additional Boost serialization wrappers.
tesseract_common::GeneralResourceLocator
A general resource loaders using environment variable.
Definition: resource_locator.h:84
TestAtomic::TestAtomic
TestAtomic(TestAtomic &&other) noexcept
Definition: tesseract_common_serialization_unit.cpp:788
profile_dictionary.h
This is a profile dictionary for storing all profiles.
TestAtomic::operator!=
bool operator!=(const TestAtomic &rhs) const
Definition: tesseract_common_serialization_unit.cpp:796
tesseract_common::JointState::position
Eigen::VectorXd position
The joint position at the waypoint.
Definition: joint_state.h:59
tesseract_common::JointTrajectory::states
std::vector< JointState > states
Definition: joint_state.h:92
TestAtomic::operator=
TestAtomic & operator=(TestAtomic &&other) noexcept
Definition: tesseract_common_serialization_unit.cpp:789
TestAtomic::operator==
bool operator==(const TestAtomic &rhs) const
Definition: tesseract_common_serialization_unit.cpp:795
TestProfile
Definition: tesseract_common_serialization_unit.cpp:73
tesseract_common::KinematicLimits::joint_limits
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::MatrixX2d joint_limits
The position limits.
Definition: kinematic_limits.h:48
tesseract_common::ProfileDictionary::addProfile
void addProfile(const std::string &ns, const std::string &profile_name, const Profile::ConstPtr &profile)
Add a profile.
Definition: profile_dictionary.cpp:124


tesseract_common
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:40