27 #include <gtest/gtest.h>
28 #include <boost/serialization/shared_ptr.hpp>
29 #include <boost/serialization/nvp.hpp>
53 std::unordered_map<std::string,
54 std::unordered_map<std::size_t, std::unordered_map<std::string, Profile::ConstPtr>>>;
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();
88 friend class boost::serialization::access;
90 template <
class Archive>
93 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Profile);
104 EXPECT_EQ(profile.getKey(), 100);
105 tesseract_common::testSerialization<TestProfile>(profile,
"TestProfile");
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);
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);
121 tesseract_common::testSerialization<ProfileDictionary>(profile_dictionary,
"ProfileDictionary");
127 tesseract_common::testSerialization<GeneralResourceLocator>(locator,
"GeneralResourceLocator");
142 tesseract_common::testSerialization<KinematicLimits>(limits,
"KinematicLimits");
148 tesseract_common::testSerialization<ManipulatorInfo>(manip_info,
"ManipulatorInfo");
152 tesseract_common::testSerialization<ManipulatorInfo>(manip_info2,
"ManipulatorInfo2");
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;
165 tesseract_common::testSerialization<JointState>(joint_state,
"JointState");
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;
179 trajectory.
states.push_back(joint_state);
182 tesseract_common::testSerialization<JointTrajectory>(trajectory,
"JointTrajectory");
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");
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");
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");
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");
229 plugin.
config[
"test"] =
"value";
230 object->discrete_plugin_infos.default_plugin =
"test_string";
231 object->discrete_plugin_infos.plugins[
"plugin_key"] = plugin;
237 plugin.
config[
"test2"] =
"value2";
238 object->continuous_plugin_infos.default_plugin =
"test_string2";
239 object->continuous_plugin_infos.plugins[
"plugin_key2"] = plugin;
242 tesseract_common::testSerialization<ContactManagersPluginInfo>(*
object,
"ContactManagersPluginInfo");
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");
257 plugin.
config[
"test"] =
"value";
258 object->executor_plugin_infos.default_plugin =
"test_string";
259 object->executor_plugin_infos.plugins[
"plugin_key"] = plugin;
264 plugin.
config[
"test2"] =
"value2";
265 object->task_plugin_infos.default_plugin =
"test_string2";
266 object->task_plugin_infos.plugins[
"plugin_key2"] = plugin;
269 tesseract_common::testSerialization<TaskComposerPluginInfo>(*
object,
"TaskComposerPluginInfo");
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");
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;
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;
300 tesseract_common::testSerialization<KinematicsPluginInfo>(*
object,
"KinematicsPluginInfo");
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");
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");
322 TEST(TesseractCommonSerializeUnit, VectorXd)
328 boost::archive::xml_oarchive oa(os);
329 oa << BOOST_SERIALIZATION_NVP(ev);
336 boost::archive::xml_iarchive ia(ifs);
339 ia >> BOOST_SERIALIZATION_NVP(nev);
344 for (
int i = 0; i < 5; ++i)
346 Eigen::VectorXd ev = Eigen::VectorXd::Random(6);
350 boost::archive::xml_oarchive oa(os);
351 oa << BOOST_SERIALIZATION_NVP(ev);
354 Eigen::VectorXd nev = Eigen::VectorXd::Random(6);
358 boost::archive::xml_iarchive ia(ifs);
361 ia >> BOOST_SERIALIZATION_NVP(nev);
364 EXPECT_TRUE(ev.isApprox(nev, 1e-5));
368 for (
int i = 0; i < 5; ++i)
370 Eigen::VectorXd ev = Eigen::VectorXd::Random(6);
374 boost::archive::xml_oarchive oa(os);
375 oa << BOOST_SERIALIZATION_NVP(ev);
378 Eigen::VectorXd nev = Eigen::VectorXd::Random(3);
382 boost::archive::xml_iarchive ia(ifs);
385 ia >> BOOST_SERIALIZATION_NVP(nev);
388 EXPECT_TRUE(ev.isApprox(nev, 1e-5));
392 for (
int i = 0; i < 5; ++i)
394 Eigen::VectorXd ev = Eigen::VectorXd::Random(6);
398 boost::archive::xml_oarchive oa(os);
399 oa << BOOST_SERIALIZATION_NVP(ev);
406 boost::archive::xml_iarchive ia(ifs);
409 ia >> BOOST_SERIALIZATION_NVP(nev);
412 EXPECT_TRUE(ev.isApprox(nev, 1e-5));
416 TEST(TesseractCommonSerializeUnit, VectorXi)
422 boost::archive::xml_oarchive oa(os);
423 oa << BOOST_SERIALIZATION_NVP(ev);
430 boost::archive::xml_iarchive ia(ifs);
433 ia >> BOOST_SERIALIZATION_NVP(nev);
438 for (
int i = 0; i < 5; ++i)
440 Eigen::VectorXi ev = Eigen::VectorXi::Random(6);
444 boost::archive::xml_oarchive oa(os);
445 oa << BOOST_SERIALIZATION_NVP(ev);
448 Eigen::VectorXi nev = Eigen::VectorXi::Random(6);
452 boost::archive::xml_iarchive ia(ifs);
455 ia >> BOOST_SERIALIZATION_NVP(nev);
458 EXPECT_TRUE(ev == nev);
462 for (
int i = 0; i < 5; ++i)
464 Eigen::VectorXi ev = Eigen::VectorXi::Random(6);
468 boost::archive::xml_oarchive oa(os);
469 oa << BOOST_SERIALIZATION_NVP(ev);
472 Eigen::VectorXi nev = Eigen::VectorXi::Random(3);
476 boost::archive::xml_iarchive ia(ifs);
479 ia >> BOOST_SERIALIZATION_NVP(nev);
482 EXPECT_TRUE(ev == nev);
486 for (
int i = 0; i < 5; ++i)
488 Eigen::VectorXi ev = Eigen::VectorXi::Random(6);
492 boost::archive::xml_oarchive oa(os);
493 oa << BOOST_SERIALIZATION_NVP(ev);
500 boost::archive::xml_iarchive ia(ifs);
503 ia >> BOOST_SERIALIZATION_NVP(nev);
506 EXPECT_TRUE(ev == nev);
510 TEST(TesseractCommonSerializeUnit, Vector3d)
513 Eigen::Vector3d ev = Eigen::Vector3d::Zero();
516 boost::archive::xml_oarchive oa(os);
517 oa << BOOST_SERIALIZATION_NVP(ev);
524 boost::archive::xml_iarchive ia(ifs);
527 ia >> BOOST_SERIALIZATION_NVP(nev);
532 for (
int i = 0; i < 3; ++i)
534 Eigen::Vector3d ev = Eigen::Vector3d::Random();
538 boost::archive::xml_oarchive oa(os);
539 oa << BOOST_SERIALIZATION_NVP(ev);
542 Eigen::Vector3d nev = Eigen::Vector3d::Random();
546 boost::archive::xml_iarchive ia(ifs);
549 ia >> BOOST_SERIALIZATION_NVP(nev);
552 EXPECT_TRUE(ev.isApprox(nev, 1e-5));
556 for (
int i = 0; i < 3; ++i)
558 Eigen::Vector3d ev = Eigen::Vector3d::Random();
562 boost::archive::xml_oarchive oa(os);
563 oa << BOOST_SERIALIZATION_NVP(ev);
570 boost::archive::xml_iarchive ia(ifs);
573 ia >> BOOST_SERIALIZATION_NVP(nev);
576 EXPECT_TRUE(ev.isApprox(nev, 1e-5));
580 TEST(TesseractCommonSerializeUnit, Vector4d)
583 Eigen::Vector4d ev = Eigen::Vector4d::Zero();
586 boost::archive::xml_oarchive oa(os);
587 oa << BOOST_SERIALIZATION_NVP(ev);
594 boost::archive::xml_iarchive ia(ifs);
597 ia >> BOOST_SERIALIZATION_NVP(nev);
602 for (
int i = 0; i < 4; ++i)
604 Eigen::Vector4d ev = Eigen::Vector4d::Random();
608 boost::archive::xml_oarchive oa(os);
609 oa << BOOST_SERIALIZATION_NVP(ev);
612 Eigen::Vector4d nev = Eigen::Vector4d::Random();
616 boost::archive::xml_iarchive ia(ifs);
619 ia >> BOOST_SERIALIZATION_NVP(nev);
622 EXPECT_TRUE(ev.isApprox(nev, 1e-5));
626 for (
int i = 0; i < 4; ++i)
628 Eigen::Vector4d ev = Eigen::Vector4d::Random();
632 boost::archive::xml_oarchive oa(os);
633 oa << BOOST_SERIALIZATION_NVP(ev);
640 boost::archive::xml_iarchive ia(ifs);
643 ia >> BOOST_SERIALIZATION_NVP(nev);
646 EXPECT_TRUE(ev.isApprox(nev, 1e-5));
650 TEST(TesseractCommonSerializeUnit, MatrixX2d)
657 boost::archive::xml_oarchive oa(os);
658 oa << BOOST_SERIALIZATION_NVP(em);
661 Eigen::MatrixX2d nem;
665 boost::archive::xml_iarchive ia(ifs);
668 ia >> BOOST_SERIALIZATION_NVP(nem);
671 EXPECT_TRUE(em.isApprox(nem, 1e-5));
675 for (
int i = 0; i < 5; ++i)
677 Eigen::MatrixX2d em = Eigen::MatrixX2d::Random(4, 2);
681 boost::archive::xml_oarchive oa(os);
682 oa << BOOST_SERIALIZATION_NVP(em);
685 Eigen::MatrixX2d nem = Eigen::MatrixX2d::Random(4, 2);
689 boost::archive::xml_iarchive ia(ifs);
692 ia >> BOOST_SERIALIZATION_NVP(nem);
695 EXPECT_TRUE(em.isApprox(nem, 1e-5));
699 for (
int i = 0; i < 5; ++i)
701 Eigen::MatrixX2d em = Eigen::MatrixX2d::Random(4, 2);
705 boost::archive::xml_oarchive oa(os);
706 oa << BOOST_SERIALIZATION_NVP(em);
709 Eigen::MatrixX2d nem = Eigen::MatrixX2d::Random(2, 2);
713 boost::archive::xml_iarchive ia(ifs);
716 ia >> BOOST_SERIALIZATION_NVP(nem);
719 EXPECT_TRUE(em.isApprox(nem, 1e-5));
723 for (
int i = 0; i < 5; ++i)
725 Eigen::MatrixX2d em = Eigen::MatrixX2d::Random(4, 2);
729 boost::archive::xml_oarchive oa(os);
730 oa << BOOST_SERIALIZATION_NVP(em);
733 Eigen::MatrixX2d nem;
737 boost::archive::xml_iarchive ia(ifs);
740 ia >> BOOST_SERIALIZATION_NVP(nem);
743 EXPECT_TRUE(em.isApprox(nem, 1e-5));
747 TEST(TesseractCommonSerializeUnit, Isometry3d)
749 for (
int i = 0; i < 5; ++i)
751 Eigen::Isometry3d pose =
752 Eigen::Isometry3d::Identity() * Eigen::AngleAxisd(M_PI, Eigen::Vector3d::Random().normalized());
753 pose.translation() = Eigen::Vector3d::Random();
757 boost::archive::xml_oarchive oa(os);
758 oa << BOOST_SERIALIZATION_NVP(pose);
761 Eigen::Isometry3d npose;
765 boost::archive::xml_iarchive ia(ifs);
768 ia >> BOOST_SERIALIZATION_NVP(npose);
771 EXPECT_TRUE(pose.isApprox(npose, 1e-5));
778 std::atomic<bool> value{
true };
785 value = other.
value.load();
791 value = other.
value.load();
798 friend class boost::serialization::access;
800 template <
class Archive>
803 ar& BOOST_SERIALIZATION_NVP(value);
810 TEST(TesseractCommonSerializeUnit, StdAtomic)
814 tesseract_common::testSerialization<TestAtomic>(
object,
"TestAtomic");
829 TEST(TesseractCommonSerializeUnit, ExtensionXmlMacro)
832 EXPECT_EQ(ext,
".etax");
835 EXPECT_EQ(default_ext,
".trsx");
838 TEST(TesseractCommonSerializeUnit, ExtensionBinaryMacro)
841 EXPECT_EQ(ext,
".etab");
844 EXPECT_EQ(default_ext,
".trsb");
847 int main(
int argc,
char** argv)
849 testing::InitGoogleTest(&argc, argv);
851 return RUN_ALL_TESTS();