tesseract_geometry_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 <octomap/octomap.h>
31 
35 #include <tesseract_common/utils.h>
39 
40 using namespace tesseract_geometry;
41 
42 TEST(TesseractGeometrySerializeUnit, Box) // NOLINT
43 {
44  auto object = std::make_shared<Box>(1, 2, 3);
45  tesseract_common::testSerialization<Box>(*object, "Box");
46  tesseract_common::testSerializationDerivedClass<Geometry, Box>(object, "Box");
47 }
48 
49 TEST(TesseractGeometrySerializeUnit, Capsule) // NOLINT
50 {
51  auto object = std::make_shared<Capsule>(1, 2);
52  tesseract_common::testSerialization<Capsule>(*object, "Capsule");
53  tesseract_common::testSerializationDerivedClass<Geometry, Capsule>(object, "Capsule");
54 }
55 
56 TEST(TesseractGeometrySerializeUnit, Cone) // NOLINT
57 {
58  auto object = std::make_shared<Cone>(1.1, 2.2);
59  tesseract_common::testSerialization<Cone>(*object, "Cone");
60  tesseract_common::testSerializationDerivedClass<Geometry, Cone>(object, "Cone");
61 }
62 
63 TEST(TesseractGeometrySerializeUnit, ConvexMesh) // NOLINT
64 {
66  std::string path = "package://tesseract_support/meshes/sphere_p25m.stl";
67  auto object = tesseract_geometry::createMeshFromResource<tesseract_geometry::ConvexMesh>(
68  locator.locateResource(path), Eigen::Vector3d(.1, .2, .3), true, true, true, true, true);
69  tesseract_common::testSerialization<ConvexMesh>(*object.front(), "ConvexMesh");
70  tesseract_common::testSerializationDerivedClass<Geometry, ConvexMesh>(object.front(), "ConvexMesh");
71  tesseract_common::testSerializationDerivedClass<PolygonMesh, ConvexMesh>(object.front(), "ConvexMesh");
72 }
73 
74 TEST(TesseractGeometrySerializeUnit, CompoundConvexMesh) // NOLINT
75 {
77  std::string path = "package://tesseract_support/meshes/sphere_p25m.stl";
78  auto object = tesseract_geometry::createMeshFromResource<tesseract_geometry::ConvexMesh>(
79  locator.locateResource(path), Eigen::Vector3d(.1, .2, .3), true, true, true, true, true);
80  std::vector<tesseract_geometry::PolygonMesh::Ptr> meshes;
81  meshes.push_back(object.front());
82  meshes.push_back(object.front());
83  meshes.push_back(object.front());
84 
85  auto compound_object = std::make_shared<CompoundMesh>(meshes);
86  tesseract_common::testSerialization<CompoundMesh>(*compound_object, "CompundConvexMesh");
87  tesseract_common::testSerializationDerivedClass<Geometry, CompoundMesh>(compound_object, "CompundConvexMesh");
88 }
89 
90 TEST(TesseractGeometrySerializeUnit, Cylinder) // NOLINT
91 {
92  auto object = std::make_shared<Cylinder>(3.3, 4.4);
93  tesseract_common::testSerialization<Cylinder>(*object, "Cylinder");
94  tesseract_common::testSerializationDerivedClass<Geometry, Cylinder>(object, "Cylinder");
95 }
96 
97 TEST(TesseractGeometrySerializeUnit, Mesh) // NOLINT
98 {
100  std::string path = "package://tesseract_support/meshes/sphere_p25m.stl";
101  auto object = tesseract_geometry::createMeshFromResource<tesseract_geometry::Mesh>(
102  locator.locateResource(path), Eigen::Vector3d(.1, .2, .3), true, true, true, true, true);
103  tesseract_common::testSerialization<Mesh>(*object.front(), "Mesh");
104  tesseract_common::testSerializationDerivedClass<Geometry, Mesh>(object.front(), "Mesh");
105  tesseract_common::testSerializationDerivedClass<PolygonMesh, Mesh>(object.front(), "Mesh");
106 }
107 
108 TEST(TesseractGeometrySerializeUnit, CompoundMesh) // NOLINT
109 {
111  std::string path = "package://tesseract_support/meshes/sphere_p25m.stl";
112  auto object = tesseract_geometry::createMeshFromResource<tesseract_geometry::Mesh>(
113  locator.locateResource(path), Eigen::Vector3d(.1, .2, .3), true, true, true, true, true);
114  std::vector<tesseract_geometry::PolygonMesh::Ptr> meshes;
115  meshes.push_back(object.front());
116  meshes.push_back(object.front());
117  meshes.push_back(object.front());
118 
119  auto compound_object = std::make_shared<CompoundMesh>(meshes);
120  tesseract_common::testSerialization<CompoundMesh>(*compound_object, "CompoundMesh");
121  tesseract_common::testSerializationDerivedClass<Geometry, CompoundMesh>(compound_object, "CompoundMesh");
122 }
123 
124 TEST(TesseractGeometrySerializeUnit, Octree) // NOLINT
125 {
126  struct TestPointCloud
127  {
128  struct point
129  {
130  point(double x, double y, double z) : x(x), y(y), z(z) {}
131  double x;
132  double y;
133  double z;
134  };
135 
136  std::vector<point> points;
137  };
138 
139  TestPointCloud pc;
140  pc.points.emplace_back(.5, 0.5, 0.5);
141  pc.points.emplace_back(-.5, -0.5, -0.5);
142  pc.points.emplace_back(-.5, 0.5, 0.5);
143  {
144  auto octree = tesseract_geometry::createOctree(pc, 1, false, true);
145  auto object = std::make_shared<tesseract_geometry::Octree>(
146  std::move(octree), tesseract_geometry::OctreeSubType::BOX, false, true);
147  tesseract_common::testSerialization<Octree>(*object, "Binary_Octree");
148  tesseract_common::testSerializationDerivedClass<Geometry, Octree>(object, "Binary_Octree");
149  }
150  {
151  auto octree = tesseract_geometry::createOctree(pc, 1, false, false);
152  auto object = std::make_shared<tesseract_geometry::Octree>(
153  std::move(octree), tesseract_geometry::OctreeSubType::BOX, false, false);
154  tesseract_common::testSerialization<Octree>(*object, "Full_Octree");
155  tesseract_common::testSerializationDerivedClass<Geometry, Octree>(object, "Full_Octree");
156  }
157 }
158 
159 TEST(TesseractGeometrySerializeUnit, Plane) // NOLINT
160 {
161  auto object = std::make_shared<Plane>(1.1, 2, 3.3, 4);
162  tesseract_common::testSerialization<Plane>(*object, "Plane");
163  tesseract_common::testSerializationDerivedClass<Geometry, Plane>(object, "Plane");
164 }
165 
166 TEST(TesseractGeometrySerializeUnit, PolygonMesh) // NOLINT
167 {
169  std::string path = "package://tesseract_support/meshes/sphere_p25m.stl";
170  auto object = tesseract_geometry::createMeshFromResource<tesseract_geometry::PolygonMesh>(
171  locator.locateResource(path), Eigen::Vector3d(.1, .2, .3), true, true, true, true, true);
172  tesseract_common::testSerialization<PolygonMesh>(*object.front(), "PolygonMesh");
173  tesseract_common::testSerializationDerivedClass<Geometry, PolygonMesh>(object.front(), "PolygonMesh");
174 }
175 
176 TEST(TesseractGeometrySerializeUnit, SDFMesh) // NOLINT
177 {
179  std::string path = "package://tesseract_support/meshes/sphere_p25m.stl";
180  auto object = tesseract_geometry::createMeshFromResource<tesseract_geometry::SDFMesh>(
181  locator.locateResource(path), Eigen::Vector3d(.1, .2, .3), true, true, true, true, true);
182  tesseract_common::testSerialization<SDFMesh>(*object.front(), "SDFMesh");
183  tesseract_common::testSerializationDerivedClass<Geometry, SDFMesh>(object.front(), "SDFMesh");
184  tesseract_common::testSerializationDerivedClass<PolygonMesh, SDFMesh>(object.front(), "SDFMesh");
185 }
186 
187 TEST(TesseractGeometrySerializeUnit, Sphere) // NOLINT
188 {
189  auto object = std::make_shared<Sphere>(3.3);
190  tesseract_common::testSerialization<Sphere>(*object, "Sphere");
191  tesseract_common::testSerializationDerivedClass<Geometry, Sphere>(object, "Sphere");
192 }
193 
194 int main(int argc, char** argv)
195 {
196  testing::InitGoogleTest(&argc, argv);
197 
198  return RUN_ALL_TESTS();
199 }
tesseract_geometry::ConvexMesh
Definition: convex_mesh.h:45
front
typename detail::front_impl< Seq >::type front
tesseract_geometry::Mesh
Definition: mesh.h:45
tesseract_geometry::Octree
Definition: octree.h:58
tesseract_geometry::Plane
Definition: plane.h:44
tesseract_geometry::Sphere
Definition: sphere.h:44
utils.h
resource_locator.h
tesseract_geometry::createOctree
std::unique_ptr< octomap::OcTree > createOctree(const PointT &point_cloud, const double resolution, const bool prune, const bool binary=true)
Definition: octree_utils.h:59
TEST
TEST(TesseractGeometrySerializeUnit, Box)
Definition: tesseract_geometry_serialization_unit.cpp:42
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_geometry::SDFMesh
Definition: sdf_mesh.h:45
tesseract_geometry::Cylinder
Definition: cylinder.h:44
serialization.h
mesh_parser.h
tesseract_geometry::Capsule
Definition: capsule.h:44
geometries.h
Tesseract Geometries.
tesseract_common::GeneralResourceLocator::locateResource
std::shared_ptr< Resource > locateResource(const std::string &url) const override
tesseract_geometry::PolygonMesh
Definition: polygon_mesh.h:51
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_geometry
Definition: fwd.h:31
tesseract_common::GeneralResourceLocator
unit_test_utils.h
macros.h
tesseract_geometry::Cone
Definition: cone.h:44
tesseract_geometry::Box
Definition: box.h:44
main
int main(int argc, char **argv)
Definition: tesseract_geometry_serialization_unit.cpp:194
tesseract_geometry::OctreeSubType::BOX
@ BOX
tesseract_geometry::CompoundMesh
This is store meshes that are associated with as single resource.
Definition: compound_mesh.h:49
octree_utils.h


tesseract_geometry
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:46