tesseract_geometry_unit.cpp
Go to the documentation of this file.
3 #include <gtest/gtest.h>
4 #include <algorithm>
5 #include <memory>
7 
12 #include <tesseract_common/utils.h>
13 
14 TEST(TesseractGeometryUnit, Instantiation) // NOLINT
15 {
16  std::shared_ptr<const tesseract_common::VectorVector3d> vertices =
17  std::make_shared<const tesseract_common::VectorVector3d>();
18  std::shared_ptr<const Eigen::VectorXi> faces = std::make_shared<const Eigen::VectorXi>();
19 
20  auto box = std::make_shared<tesseract_geometry::Box>(1, 1, 1);
21  auto cone = std::make_shared<tesseract_geometry::Cone>(1, 1);
22  auto cylinder = std::make_shared<tesseract_geometry::Cylinder>(1, 1);
23  auto capsule = std::make_shared<tesseract_geometry::Capsule>(1, 1);
24  auto plane = std::make_shared<tesseract_geometry::Plane>(1, 1, 1, 1);
25  auto sphere = std::make_shared<tesseract_geometry::Sphere>(1);
26  auto convex_mesh = std::make_shared<tesseract_geometry::ConvexMesh>(vertices, faces);
27  auto mesh = std::make_shared<tesseract_geometry::Mesh>(vertices, faces);
28  auto sdf_mesh = std::make_shared<tesseract_geometry::SDFMesh>(vertices, faces);
29  auto octree = std::make_shared<tesseract_geometry::Octree>(nullptr, tesseract_geometry::OctreeSubType::BOX);
30  auto compound_mesh =
31  std::make_shared<tesseract_geometry::CompoundMesh>(std::vector<std::shared_ptr<tesseract_geometry::PolygonMesh>>{
32  std::make_shared<tesseract_geometry::Mesh>(vertices, faces),
33  std::make_shared<tesseract_geometry::Mesh>(vertices, faces) });
34 
35  // Instead making this depend on pcl it expects the structure to have a member called points which is a vector
36  // of another object with has float members x, y and z.
37  struct TestPointCloud
38  {
39  struct point
40  {
41  double x;
42  double y;
43  double z;
44  };
45 
46  std::vector<point> points;
47  };
48 
49  TestPointCloud pc;
50  auto co = tesseract_geometry::createOctree(pc, 0.01, false);
51  auto octree_pc =
52  std::make_shared<tesseract_geometry::Octree>(std::move(co), tesseract_geometry::OctreeSubType::BOX, false);
53 }
54 
55 TEST(TesseractGeometryUnit, Box) // NOLINT
56 {
57  using T = tesseract_geometry::Box;
58  auto geom = std::make_shared<T>(1, 1, 1);
59  EXPECT_NEAR(geom->getX(), 1, 1e-5);
60  EXPECT_NEAR(geom->getY(), 1, 1e-5);
61  EXPECT_NEAR(geom->getZ(), 1, 1e-5);
62  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::BOX);
63  EXPECT_FALSE(geom->getUUID().is_nil());
64 
65  auto geom_clone = geom->clone();
66  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getX(), 1, 1e-5);
67  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getY(), 1, 1e-5);
68  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getZ(), 1, 1e-5);
69  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::BOX);
70  EXPECT_FALSE(geom_clone->getUUID().is_nil());
71  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
72 
73  geom->setUUID(geom_clone->getUUID());
74  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
75 
76  // Test isIdentical
77  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
78  EXPECT_FALSE(tesseract_geometry::isIdentical(*geom, tesseract_geometry::Box(2, 1, 1)));
79  EXPECT_FALSE(tesseract_geometry::isIdentical(*geom, tesseract_geometry::Box(1, 2, 1)));
80  EXPECT_FALSE(tesseract_geometry::isIdentical(*geom, tesseract_geometry::Box(1, 1, 2)));
82 }
83 
84 TEST(TesseractGeometryUnit, Cone) // NOLINT
85 {
86  using T = tesseract_geometry::Cone;
87  auto geom = std::make_shared<T>(1, 1);
88  EXPECT_NEAR(geom->getRadius(), 1, 1e-5);
89  EXPECT_NEAR(geom->getLength(), 1, 1e-5);
90  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::CONE);
91  EXPECT_FALSE(geom->getUUID().is_nil());
92 
93  auto geom_clone = geom->clone();
94  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getRadius(), 1, 1e-5);
95  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getLength(), 1, 1e-5);
96  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::CONE);
97  EXPECT_FALSE(geom_clone->getUUID().is_nil());
98  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
99 
100  geom->setUUID(geom_clone->getUUID());
101  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
102 
103  // Test isIdentical
104  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
105  EXPECT_FALSE(tesseract_geometry::isIdentical(*geom, tesseract_geometry::Cone(2, 1)));
106  EXPECT_FALSE(tesseract_geometry::isIdentical(*geom, tesseract_geometry::Cone(1, 2)));
107 }
108 
109 TEST(TesseractGeometryUnit, Cylinder) // NOLINT
110 {
112  auto geom = std::make_shared<T>(1, 1);
113  EXPECT_NEAR(geom->getRadius(), 1, 1e-5);
114  EXPECT_NEAR(geom->getLength(), 1, 1e-5);
115  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::CYLINDER);
116  EXPECT_FALSE(geom->getUUID().is_nil());
117 
118  auto geom_clone = geom->clone();
119  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getRadius(), 1, 1e-5);
120  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getLength(), 1, 1e-5);
121  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::CYLINDER);
122  EXPECT_FALSE(geom_clone->getUUID().is_nil());
123  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
124 
125  geom->setUUID(geom_clone->getUUID());
126  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
127 
128  // Test isIdentical
129  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
132 }
133 
134 TEST(TesseractGeometryUnit, Capsule) // NOLINT
135 {
136  using T = tesseract_geometry::Capsule;
137  auto geom = std::make_shared<T>(1, 1);
138  EXPECT_NEAR(geom->getRadius(), 1, 1e-5);
139  EXPECT_NEAR(geom->getLength(), 1, 1e-5);
140  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::CAPSULE);
141  EXPECT_FALSE(geom->getUUID().is_nil());
142 
143  auto geom_clone = geom->clone();
144  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getRadius(), 1, 1e-5);
145  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getLength(), 1, 1e-5);
146  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::CAPSULE);
147  EXPECT_FALSE(geom_clone->getUUID().is_nil());
148  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
149 
150  geom->setUUID(geom_clone->getUUID());
151  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
152 
153  // Test isIdentical
154  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
157 }
158 
159 TEST(TesseractGeometryUnit, Sphere) // NOLINT
160 {
161  using T = tesseract_geometry::Sphere;
162  auto geom = std::make_shared<T>(1);
163  EXPECT_NEAR(geom->getRadius(), 1, 1e-5);
164  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::SPHERE);
165  EXPECT_FALSE(geom->getUUID().is_nil());
166 
167  auto geom_clone = geom->clone();
168  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getRadius(), 1, 1e-5);
169  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::SPHERE);
170  EXPECT_FALSE(geom_clone->getUUID().is_nil());
171  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
172 
173  geom->setUUID(geom_clone->getUUID());
174  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
175 
176  // Test isIdentical
177  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
179 }
180 
181 TEST(TesseractGeometryUnit, Plane) // NOLINT
182 {
183  using T = tesseract_geometry::Plane;
184  auto geom = std::make_shared<T>(1, 1, 1, 1);
185  EXPECT_NEAR(geom->getA(), 1, 1e-5);
186  EXPECT_NEAR(geom->getB(), 1, 1e-5);
187  EXPECT_NEAR(geom->getC(), 1, 1e-5);
188  EXPECT_NEAR(geom->getD(), 1, 1e-5);
189  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::PLANE);
190  EXPECT_FALSE(geom->getUUID().is_nil());
191 
192  auto geom_clone = geom->clone();
193  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getA(), 1, 1e-5);
194  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getB(), 1, 1e-5);
195  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getC(), 1, 1e-5);
196  EXPECT_NEAR(std::static_pointer_cast<T>(geom_clone)->getD(), 1, 1e-5);
197  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::PLANE);
198  EXPECT_FALSE(geom_clone->getUUID().is_nil());
199  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
200 
201  geom->setUUID(geom_clone->getUUID());
202  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
203 
204  // Test isIdentical
205  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
206  EXPECT_FALSE(tesseract_geometry::isIdentical(*geom, tesseract_geometry::Plane(2, 1, 1, 1)));
207  EXPECT_FALSE(tesseract_geometry::isIdentical(*geom, tesseract_geometry::Plane(1, 2, 1, 1)));
208  EXPECT_FALSE(tesseract_geometry::isIdentical(*geom, tesseract_geometry::Plane(1, 1, 2, 1)));
209  EXPECT_FALSE(tesseract_geometry::isIdentical(*geom, tesseract_geometry::Plane(1, 1, 1, 2)));
210 }
211 
212 TEST(TesseractGeometryUnit, PolygonMesh) // NOLINT
213 {
214  auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
215  vertices->emplace_back(1, 1, 0);
216  vertices->emplace_back(1, -1, 0);
217  vertices->emplace_back(-1, -1, 0);
218  vertices->emplace_back(1, -1, 0);
219 
220  auto faces = std::make_shared<Eigen::VectorXi>();
221  faces->resize(5);
222  (*faces)(0) = 4;
223  (*faces)(1) = 0;
224  (*faces)(2) = 1;
225  (*faces)(3) = 2;
226  (*faces)(4) = 3;
227 
229  auto geom = std::make_shared<T>(vertices, faces);
230  EXPECT_TRUE(geom->getVertices() != nullptr);
231  EXPECT_TRUE(geom->getFaces() != nullptr);
232  EXPECT_TRUE(geom->getVertexCount() == 4);
233  EXPECT_TRUE(geom->getFaceCount() == 1);
234  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::POLYGON_MESH);
235  EXPECT_FALSE(geom->getUUID().is_nil());
236 
237  auto geom_clone = geom->clone();
238  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertices() != nullptr);
239  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaces() != nullptr);
240  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertexCount() == 4);
241  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaceCount() == 1);
242  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::POLYGON_MESH);
243  EXPECT_FALSE(geom_clone->getUUID().is_nil());
244  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
245 
246  geom->setUUID(geom_clone->getUUID());
247  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
248 
249  // Test isIdentical
250  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
251  EXPECT_FALSE(tesseract_geometry::isIdentical(
252  *geom,
253  tesseract_geometry::PolygonMesh(std::make_shared<tesseract_common::VectorVector3d>(),
254  std::make_shared<Eigen::VectorXi>())));
255 }
256 
257 TEST(TesseractGeometryUnit, ConvexMesh) // NOLINT
258 {
259  auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
260  vertices->emplace_back(1, 1, 0);
261  vertices->emplace_back(1, -1, 0);
262  vertices->emplace_back(-1, -1, 0);
263  vertices->emplace_back(1, -1, 0);
264 
265  auto faces = std::make_shared<Eigen::VectorXi>();
266  faces->resize(5);
267  (*faces)(0) = 4;
268  (*faces)(1) = 0;
269  (*faces)(2) = 1;
270  (*faces)(3) = 2;
271  (*faces)(4) = 3;
272 
274  auto geom = std::make_shared<T>(vertices, faces);
275  EXPECT_TRUE(geom->getVertices() != nullptr);
276  EXPECT_TRUE(geom->getFaces() != nullptr);
277  EXPECT_TRUE(geom->getVertexCount() == 4);
278  EXPECT_TRUE(geom->getFaceCount() == 1);
279  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::CONVEX_MESH);
280  EXPECT_EQ(geom->getCreationMethod(), tesseract_geometry::ConvexMesh::CreationMethod::DEFAULT);
281  geom->setCreationMethod(tesseract_geometry::ConvexMesh::CreationMethod::CONVERTED);
282  EXPECT_EQ(geom->getCreationMethod(), tesseract_geometry::ConvexMesh::CreationMethod::CONVERTED);
283  EXPECT_FALSE(geom->getUUID().is_nil());
284 
285  auto geom_clone = geom->clone();
286  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertices() != nullptr);
287  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaces() != nullptr);
288  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertexCount() == 4);
289  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaceCount() == 1);
290  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::CONVEX_MESH);
291  EXPECT_EQ(geom->getCreationMethod(), tesseract_geometry::ConvexMesh::CreationMethod::CONVERTED);
292  EXPECT_FALSE(geom_clone->getUUID().is_nil());
293  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
294 
295  geom->setUUID(geom_clone->getUUID());
296  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
297 
298  // Test isIdentical
299  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
300  EXPECT_FALSE(tesseract_geometry::isIdentical(
301  *geom,
302  tesseract_geometry::ConvexMesh(std::make_shared<tesseract_common::VectorVector3d>(),
303  std::make_shared<Eigen::VectorXi>())));
304 }
305 
306 TEST(TesseractGeometryUnit, CompoundConvexMesh) // NOLINT
307 {
308  auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
309  vertices->emplace_back(1, 1, 0);
310  vertices->emplace_back(1, -1, 0);
311  vertices->emplace_back(-1, -1, 0);
312  vertices->emplace_back(1, -1, 0);
313 
314  auto faces = std::make_shared<Eigen::VectorXi>();
315  faces->resize(5);
316  (*faces)(0) = 4;
317  (*faces)(1) = 0;
318  (*faces)(2) = 1;
319  (*faces)(3) = 2;
320  (*faces)(4) = 3;
321 
323  auto sub_geom = std::make_shared<T>(vertices, faces);
324  EXPECT_TRUE(sub_geom->getVertices() != nullptr);
325  EXPECT_TRUE(sub_geom->getFaces() != nullptr);
326  EXPECT_TRUE(sub_geom->getVertexCount() == 4);
327  EXPECT_TRUE(sub_geom->getFaceCount() == 1);
328  EXPECT_EQ(sub_geom->getType(), tesseract_geometry::GeometryType::CONVEX_MESH);
329  EXPECT_FALSE(sub_geom->getUUID().is_nil());
330 
331  std::vector<tesseract_geometry::PolygonMesh::Ptr> poly_meshes;
332  poly_meshes.push_back(sub_geom);
333  poly_meshes.push_back(sub_geom);
334  poly_meshes.push_back(sub_geom);
335 
336  auto geom = std::make_shared<tesseract_geometry::CompoundMesh>(poly_meshes);
337  EXPECT_EQ(geom->getMeshes().size(), 3);
338  EXPECT_EQ(geom->getResource(), geom->getMeshes().front()->getResource());
339  EXPECT_TRUE(tesseract_common::almostEqualRelativeAndAbs(geom->getScale(), geom->getMeshes().front()->getScale()));
340  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::COMPOUND_MESH);
341 
342  auto geom_clone = std::static_pointer_cast<tesseract_geometry::CompoundMesh>(geom->clone());
343  EXPECT_EQ(geom_clone->getMeshes().size(), 3);
344  EXPECT_EQ(geom_clone->getResource(), geom->getMeshes().front()->getResource());
345  EXPECT_TRUE(
346  tesseract_common::almostEqualRelativeAndAbs(geom_clone->getScale(), geom->getMeshes().front()->getScale()));
347  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::COMPOUND_MESH);
348  EXPECT_FALSE(geom_clone->getUUID().is_nil());
349  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
350 
351  geom->setUUID(geom_clone->getUUID());
352  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
353 
354  // Test isIdentical
355  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
357 
358  { // Test convex hull constructors
359  std::vector<tesseract_geometry::ConvexMesh::Ptr> convex_meshes;
360  convex_meshes.push_back(sub_geom);
361  convex_meshes.push_back(sub_geom);
362  convex_meshes.push_back(sub_geom);
363 
364  auto geom = std::make_shared<tesseract_geometry::CompoundMesh>(convex_meshes);
365  EXPECT_EQ(geom->getMeshes().size(), 3);
366  EXPECT_EQ(geom->getResource(), geom->getMeshes().front()->getResource());
367  EXPECT_TRUE(tesseract_common::almostEqualRelativeAndAbs(geom->getScale(), geom->getMeshes().front()->getScale()));
368  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::COMPOUND_MESH);
369  }
370 
371  { // Test convex hull constructors
372  auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
373  vertices->emplace_back(1, 1, 0);
374  vertices->emplace_back(1, -1, 0);
375  vertices->emplace_back(-1, -1, 0);
376  vertices->emplace_back(1, -1, 0);
377 
378  auto faces = std::make_shared<Eigen::VectorXi>();
379  faces->resize(8);
380  (*faces)(0) = 3;
381  (*faces)(1) = 0;
382  (*faces)(2) = 1;
383  (*faces)(3) = 2;
384 
385  (*faces)(4) = 3;
386  (*faces)(5) = 0;
387  (*faces)(6) = 2;
388  (*faces)(7) = 3;
389 
390  using T = tesseract_geometry::SDFMesh;
391  auto sub_geom = std::make_shared<T>(vertices, faces);
392  EXPECT_TRUE(sub_geom->getVertices() != nullptr);
393  EXPECT_TRUE(sub_geom->getFaces() != nullptr);
394  EXPECT_TRUE(sub_geom->getVertexCount() == 4);
395  EXPECT_TRUE(sub_geom->getFaceCount() == 2);
396  EXPECT_EQ(sub_geom->getType(), tesseract_geometry::GeometryType::SDF_MESH);
397  EXPECT_FALSE(geom->getUUID().is_nil());
398 
399  std::vector<tesseract_geometry::SDFMesh::Ptr> sdf_meshes;
400  sdf_meshes.push_back(sub_geom);
401  sdf_meshes.push_back(sub_geom);
402  sdf_meshes.push_back(sub_geom);
403 
404  auto geom = std::make_shared<tesseract_geometry::CompoundMesh>(sdf_meshes);
405  EXPECT_EQ(geom->getMeshes().size(), 3);
406  EXPECT_EQ(geom->getResource(), geom->getMeshes().front()->getResource());
407  EXPECT_TRUE(tesseract_common::almostEqualRelativeAndAbs(geom->getScale(), geom->getMeshes().front()->getScale()));
408  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::COMPOUND_MESH);
409  }
410 
411  { // Test convex hull constructors
412  auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
413  vertices->emplace_back(1, 1, 0);
414  vertices->emplace_back(1, -1, 0);
415  vertices->emplace_back(-1, -1, 0);
416  vertices->emplace_back(1, -1, 0);
417 
418  auto faces = std::make_shared<Eigen::VectorXi>();
419  faces->resize(8);
420  (*faces)(0) = 3;
421  (*faces)(1) = 0;
422  (*faces)(2) = 1;
423  (*faces)(3) = 2;
424 
425  (*faces)(4) = 3;
426  (*faces)(5) = 0;
427  (*faces)(6) = 2;
428  (*faces)(7) = 3;
429 
430  using T = tesseract_geometry::Mesh;
431  auto sub_geom = std::make_shared<T>(vertices, faces);
432  EXPECT_TRUE(sub_geom->getVertices() != nullptr);
433  EXPECT_TRUE(sub_geom->getFaces() != nullptr);
434  EXPECT_TRUE(sub_geom->getVertexCount() == 4);
435  EXPECT_TRUE(sub_geom->getFaceCount() == 2);
436  EXPECT_EQ(sub_geom->getType(), tesseract_geometry::GeometryType::MESH);
437  EXPECT_FALSE(geom->getUUID().is_nil());
438 
439  std::vector<tesseract_geometry::Mesh::Ptr> meshes;
440  meshes.push_back(sub_geom);
441  meshes.push_back(sub_geom);
442  meshes.push_back(sub_geom);
443 
444  auto geom = std::make_shared<tesseract_geometry::CompoundMesh>(meshes);
445  EXPECT_EQ(geom->getMeshes().size(), 3);
446  EXPECT_EQ(geom->getResource(), geom->getMeshes().front()->getResource());
447  EXPECT_TRUE(tesseract_common::almostEqualRelativeAndAbs(geom->getScale(), geom->getMeshes().front()->getScale()));
448  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::COMPOUND_MESH);
449  }
450 }
451 
452 TEST(TesseractGeometryUnit, Mesh) // NOLINT
453 {
454  auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
455  vertices->emplace_back(1, 1, 0);
456  vertices->emplace_back(1, -1, 0);
457  vertices->emplace_back(-1, -1, 0);
458  vertices->emplace_back(1, -1, 0);
459 
460  auto faces = std::make_shared<Eigen::VectorXi>();
461  faces->resize(8);
462  (*faces)(0) = 3;
463  (*faces)(1) = 0;
464  (*faces)(2) = 1;
465  (*faces)(3) = 2;
466 
467  (*faces)(4) = 3;
468  (*faces)(5) = 0;
469  (*faces)(6) = 2;
470  (*faces)(7) = 3;
471 
472  using T = tesseract_geometry::Mesh;
473 
474  {
475  auto geom = std::make_shared<T>(vertices, faces);
476  EXPECT_TRUE(geom->getVertices() != nullptr);
477  EXPECT_TRUE(geom->getFaces() != nullptr);
478  EXPECT_TRUE(geom->getVertexCount() == 4);
479  EXPECT_TRUE(geom->getFaceCount() == 2);
480  EXPECT_TRUE(geom->getMaterial() == nullptr);
481  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::MESH);
482  EXPECT_FALSE(geom->getUUID().is_nil());
483 
484  auto geom_clone = geom->clone();
485  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertices() != nullptr);
486  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaces() != nullptr);
487  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertexCount() == 4);
488  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaceCount() == 2);
489  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getMaterial() == nullptr);
490  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::MESH);
491  EXPECT_FALSE(geom_clone->getUUID().is_nil());
492  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
493 
494  geom->setUUID(geom_clone->getUUID());
495  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
496 
497  // Test isIdentical
498  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
499  EXPECT_FALSE(
501  tesseract_geometry::Mesh(std::make_shared<tesseract_common::VectorVector3d>(),
502  std::make_shared<Eigen::VectorXi>())));
503  }
504 
505  {
506  auto mat = std::make_shared<tesseract_geometry::MeshMaterial>();
507  auto geom = std::make_shared<T>(vertices, faces, nullptr, Eigen::Vector3d(1, 1, 1), nullptr, nullptr, mat);
508  EXPECT_TRUE(geom->getVertices() != nullptr);
509  EXPECT_TRUE(geom->getFaces() != nullptr);
510  EXPECT_TRUE(geom->getVertexCount() == 4);
511  EXPECT_TRUE(geom->getFaceCount() == 2);
512  EXPECT_TRUE(geom->getMaterial() != nullptr);
513  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::MESH);
514  EXPECT_FALSE(geom->getUUID().is_nil());
515 
516  auto geom_clone = geom->clone();
517  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertices() != nullptr);
518  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaces() != nullptr);
519  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertexCount() == 4);
520  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaceCount() == 2);
521  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getMaterial() != nullptr);
522  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::MESH);
523  EXPECT_FALSE(geom_clone->getUUID().is_nil());
524  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
525 
526  geom->setUUID(geom_clone->getUUID());
527  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
528 
529  // Test isIdentical
530  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
531  EXPECT_FALSE(
533  tesseract_geometry::Mesh(std::make_shared<tesseract_common::VectorVector3d>(),
534  std::make_shared<Eigen::VectorXi>())));
535  }
536 }
537 
538 TEST(TesseractGeometryUnit, CompoundMesh) // NOLINT
539 {
540  auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
541  vertices->emplace_back(1, 1, 0);
542  vertices->emplace_back(1, -1, 0);
543  vertices->emplace_back(-1, -1, 0);
544  vertices->emplace_back(1, -1, 0);
545 
546  auto faces = std::make_shared<Eigen::VectorXi>();
547  faces->resize(8);
548  (*faces)(0) = 3;
549  (*faces)(1) = 0;
550  (*faces)(2) = 1;
551  (*faces)(3) = 2;
552 
553  (*faces)(4) = 3;
554  (*faces)(5) = 0;
555  (*faces)(6) = 2;
556  (*faces)(7) = 3;
557 
558  using T = tesseract_geometry::Mesh;
559 
560  auto sub_geom = std::make_shared<T>(vertices, faces);
561  EXPECT_TRUE(sub_geom->getVertices() != nullptr);
562  EXPECT_TRUE(sub_geom->getFaces() != nullptr);
563  EXPECT_TRUE(sub_geom->getVertexCount() == 4);
564  EXPECT_TRUE(sub_geom->getFaceCount() == 2);
565  EXPECT_TRUE(sub_geom->getMaterial() == nullptr);
566  EXPECT_EQ(sub_geom->getType(), tesseract_geometry::GeometryType::MESH);
567  EXPECT_FALSE(sub_geom->getUUID().is_nil());
568 
569  std::vector<tesseract_geometry::PolygonMesh::Ptr> meshes;
570  meshes.push_back(sub_geom);
571  meshes.push_back(sub_geom);
572  meshes.push_back(sub_geom);
573 
574  auto geom = std::make_shared<tesseract_geometry::CompoundMesh>(meshes);
575  EXPECT_EQ(geom->getMeshes().size(), 3);
576  EXPECT_EQ(geom->getResource(), geom->getMeshes().front()->getResource());
577  EXPECT_TRUE(tesseract_common::almostEqualRelativeAndAbs(geom->getScale(), geom->getMeshes().front()->getScale()));
578  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::COMPOUND_MESH);
579  EXPECT_FALSE(geom->getUUID().is_nil());
580 
581  auto geom_clone = std::static_pointer_cast<tesseract_geometry::CompoundMesh>(geom->clone());
582  EXPECT_EQ(geom_clone->getMeshes().size(), 3);
583  EXPECT_EQ(geom_clone->getResource(), geom->getMeshes().front()->getResource());
584  EXPECT_TRUE(
585  tesseract_common::almostEqualRelativeAndAbs(geom_clone->getScale(), geom->getMeshes().front()->getScale()));
586  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::COMPOUND_MESH);
587  EXPECT_FALSE(geom_clone->getUUID().is_nil());
588  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
589 
590  geom->setUUID(geom_clone->getUUID());
591  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
592 
593  // Test Failure
594  meshes.clear();
595  meshes.push_back(sub_geom);
596  EXPECT_ANY_THROW(std::make_shared<tesseract_geometry::CompoundMesh>(meshes)); // NOLINT
597 
598  // Test isIdentical
599  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
601 
602  meshes.push_back(sub_geom);
604 }
605 
606 TEST(TesseractGeometryUnit, SDFMesh) // NOLINT
607 {
608  auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
609  vertices->emplace_back(1, 1, 0);
610  vertices->emplace_back(1, -1, 0);
611  vertices->emplace_back(-1, -1, 0);
612  vertices->emplace_back(1, -1, 0);
613 
614  auto faces = std::make_shared<Eigen::VectorXi>();
615  faces->resize(8);
616  (*faces)(0) = 3;
617  (*faces)(1) = 0;
618  (*faces)(2) = 1;
619  (*faces)(3) = 2;
620 
621  (*faces)(4) = 3;
622  (*faces)(5) = 0;
623  (*faces)(6) = 2;
624  (*faces)(7) = 3;
625 
626  using T = tesseract_geometry::SDFMesh;
627  auto geom = std::make_shared<T>(vertices, faces);
628  EXPECT_TRUE(geom->getVertices() != nullptr);
629  EXPECT_TRUE(geom->getFaces() != nullptr);
630  EXPECT_TRUE(geom->getVertexCount() == 4);
631  EXPECT_TRUE(geom->getFaceCount() == 2);
632  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::SDF_MESH);
633  EXPECT_FALSE(geom->getUUID().is_nil());
634 
635  auto geom_clone = geom->clone();
636  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertices() != nullptr);
637  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaces() != nullptr);
638  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getVertexCount() == 4);
639  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getFaceCount() == 2);
640  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::SDF_MESH);
641  EXPECT_FALSE(geom_clone->getUUID().is_nil());
642  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
643 
644  geom->setUUID(geom_clone->getUUID());
645  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
646 
647  // Test isIdentical
648  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
649  EXPECT_FALSE(
651  tesseract_geometry::SDFMesh(std::make_shared<tesseract_common::VectorVector3d>(),
652  std::make_shared<Eigen::VectorXi>())));
653 }
654 
655 TEST(TesseractGeometryUnit, Octree) // NOLINT
656 {
657  using T = tesseract_geometry::Octree;
658 
660  auto octree = tesseract_geometry::createOctree(pc, 0.01, false);
661  auto geom = std::make_shared<T>(std::move(octree), tesseract_geometry::OctreeSubType::BOX, false);
662  EXPECT_TRUE(geom->getOctree() != nullptr);
663  EXPECT_TRUE(geom->getSubType() == tesseract_geometry::OctreeSubType::BOX);
664  EXPECT_EQ(geom->getType(), tesseract_geometry::GeometryType::OCTREE);
665  EXPECT_FALSE(geom->getUUID().is_nil());
666 
667  auto geom_clone = geom->clone();
668  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getOctree() != nullptr);
669  EXPECT_TRUE(std::static_pointer_cast<T>(geom_clone)->getSubType() == tesseract_geometry::OctreeSubType::BOX);
670  EXPECT_EQ(geom_clone->getType(), tesseract_geometry::GeometryType::OCTREE);
671  EXPECT_FALSE(geom_clone->getUUID().is_nil());
672  EXPECT_NE(geom_clone->getUUID(), geom->getUUID());
673 
674  geom->setUUID(geom_clone->getUUID());
675  EXPECT_EQ(geom_clone->getUUID(), geom->getUUID());
676 
677  // Test isIdentical
678  EXPECT_TRUE(tesseract_geometry::isIdentical(*geom, *geom_clone));
679 }
680 
681 TEST(TesseractGeometryUnit, LoadMeshUnit) // NOLINT
682 {
683  using namespace tesseract_geometry;
684 
686  std::string mesh_file = locator.locateResource("package://tesseract_support/meshes/sphere_p25m.stl")->getFilePath();
687  std::vector<Mesh::Ptr> meshes = createMeshFromPath<Mesh>(mesh_file);
688  EXPECT_TRUE(meshes.size() == 1);
689  EXPECT_TRUE(meshes[0]->getFaceCount() == 80);
690  EXPECT_TRUE(meshes[0]->getVertexCount() == 42);
691 
692  mesh_file = locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath();
693  meshes = createMeshFromPath<Mesh>(mesh_file);
694  EXPECT_TRUE(meshes.size() == 1);
695  EXPECT_TRUE(meshes[0]->getFaceCount() == 80);
696  EXPECT_TRUE(meshes[0]->getVertexCount() == 42);
697 
698  mesh_file = locator.locateResource("package://tesseract_support/meshes/sphere_p25m.dae")->getFilePath();
699  meshes = createMeshFromPath<Mesh>(mesh_file);
700  EXPECT_TRUE(meshes.size() == 2);
701  EXPECT_TRUE(meshes[0]->getFaceCount() == 80);
702  EXPECT_TRUE(meshes[0]->getVertexCount() == 42);
703  EXPECT_TRUE(meshes[1]->getFaceCount() == 80);
704  EXPECT_TRUE(meshes[1]->getVertexCount() == 42);
705 
706  mesh_file = locator.locateResource("package://tesseract_support/meshes/sphere_p25m.dae")->getFilePath();
707  meshes = createMeshFromPath<Mesh>(mesh_file, Eigen::Vector3d(1, 1, 1), false, true);
708  EXPECT_TRUE(meshes.size() == 1);
709  EXPECT_TRUE(meshes[0]->getFaceCount() == 2 * 80);
710  EXPECT_TRUE(meshes[0]->getVertexCount() == 2 * 42);
711 
712  mesh_file = locator.locateResource("package://tesseract_support/meshes/box_2m.ply")->getFilePath();
713  meshes = createMeshFromPath<Mesh>(mesh_file, Eigen::Vector3d(1, 1, 1), true, true);
714  EXPECT_TRUE(meshes.size() == 1);
715  EXPECT_TRUE(meshes[0]->getFaceCount() == 12);
716  EXPECT_TRUE(meshes[0]->getVertexCount() == 8);
717 
718  mesh_file = locator.locateResource("package://tesseract_support/meshes/box_2m.ply")->getFilePath();
719  meshes = createMeshFromPath<Mesh>(mesh_file, Eigen::Vector3d(1, 1, 1), true, true);
720  EXPECT_TRUE(meshes.size() == 1);
721  EXPECT_TRUE(meshes[0]->getFaceCount() == 12);
722  EXPECT_TRUE(meshes[0]->getVertexCount() == 8);
723 
724  mesh_file = locator.locateResource("package://tesseract_support/meshes/box_2m.ply")->getFilePath();
725  std::vector<ConvexMesh::Ptr> convex_meshes =
726  createMeshFromPath<ConvexMesh>(mesh_file, Eigen::Vector3d(1, 1, 1), false, false);
727  EXPECT_TRUE(convex_meshes.size() == 1);
728  EXPECT_TRUE(convex_meshes[0]->getFaceCount() == 6);
729  EXPECT_TRUE(convex_meshes[0]->getVertexCount() == 8);
730 }
731 
732 #ifdef TESSERACT_ASSIMP_USE_PBRMATERIAL
733 
734 TEST(TesseractGeometryUnit, LoadMeshWithMaterialGltf2Unit) // NOLINT
735 {
736  using namespace tesseract_geometry;
737 
739  std::string mesh_file =
740  locator.locateResource("package://tesseract_support/meshes/tesseract_material_mesh.glb")->getFilePath();
741  std::vector<Mesh::Ptr> meshes =
742  createMeshFromPath<Mesh>(mesh_file, Eigen::Vector3d(1, 1, 1), true, true, true, true, true);
743  ASSERT_TRUE(meshes.size() == 4);
744 
745  auto& mesh0 = meshes[0];
746  auto& mesh1 = meshes[1];
747  auto& mesh2 = meshes[2];
748  auto& mesh3 = meshes[3];
749 
750  EXPECT_EQ(mesh0->getFaceCount(), 34);
751  EXPECT_EQ(mesh0->getVertexCount(), 68);
752  EXPECT_EQ(mesh1->getFaceCount(), 15);
753  EXPECT_EQ(mesh1->getVertexCount(), 17);
754  EXPECT_EQ(mesh2->getFaceCount(), 15);
755  EXPECT_EQ(mesh2->getVertexCount(), 17);
756  EXPECT_EQ(mesh3->getFaceCount(), 2);
757  EXPECT_EQ(mesh3->getVertexCount(), 4);
758 
759  auto mesh0_normals = mesh0->getNormals();
760  ASSERT_TRUE(mesh0_normals != nullptr);
761  EXPECT_EQ(mesh0_normals->size(), 68);
762  auto mesh1_normals = mesh1->getNormals();
763  ASSERT_TRUE(mesh1_normals != nullptr);
764  EXPECT_EQ(mesh1_normals->size(), 17);
765  auto mesh2_normals = mesh2->getNormals();
766  ASSERT_TRUE(mesh2_normals != nullptr);
767  EXPECT_EQ(mesh2_normals->size(), 17);
768  auto mesh3_normals = mesh3->getNormals();
769  ASSERT_TRUE(mesh3_normals != nullptr);
770  EXPECT_EQ(mesh3_normals->size(), 4);
771 
772  auto mesh0_material = mesh0->getMaterial();
773  EXPECT_TRUE(mesh0_material->getBaseColorFactor().isApprox(Eigen::Vector4d(0.7, 0.7, 0.7, 1), 0.01));
774  EXPECT_NEAR(mesh0_material->getMetallicFactor(), 0.0, 0.01);
775  EXPECT_NEAR(mesh0_material->getRoughnessFactor(), 0.5, 0.01);
776  EXPECT_TRUE(mesh0_material->getEmissiveFactor().isApprox(Eigen::Vector4d(0, 0, 0, 1), 0.01));
777 
778  auto mesh1_material = mesh1->getMaterial();
779  EXPECT_TRUE(mesh1_material->getBaseColorFactor().isApprox(Eigen::Vector4d(0.8, 0, 0, 1), 0.01));
780  EXPECT_NEAR(mesh1_material->getMetallicFactor(), 0.8, 0.01);
781  EXPECT_NEAR(mesh1_material->getRoughnessFactor(), 0.1, 0.01);
782  EXPECT_TRUE(mesh1_material->getEmissiveFactor().isApprox(Eigen::Vector4d(0, 0, 0, 1), 0.01));
783 
784  auto mesh2_material = mesh2->getMaterial();
785  EXPECT_TRUE(mesh2_material->getBaseColorFactor().isApprox(Eigen::Vector4d(0.05, 0.8, 0.05, 1), 0.01));
786  EXPECT_NEAR(mesh2_material->getMetallicFactor(), 0.9, 0.01);
787  EXPECT_NEAR(mesh2_material->getRoughnessFactor(), 0.7, 0.01);
788  EXPECT_TRUE(mesh2_material->getEmissiveFactor().isApprox(Eigen::Vector4d(0.1, 0.1, 0.5, 1), 0.01));
789 
790  auto mesh3_material = mesh3->getMaterial();
791  EXPECT_TRUE(mesh3_material->getBaseColorFactor().isApprox(Eigen::Vector4d(1, 1, 1, 1), 0.01));
792  EXPECT_NEAR(mesh3_material->getMetallicFactor(), 0, 0.01);
793  EXPECT_NEAR(mesh3_material->getRoughnessFactor(), 0.5, 0.01);
794  EXPECT_TRUE(mesh3_material->getEmissiveFactor().isApprox(Eigen::Vector4d(0, 0, 0, 1), 0.01));
795 
796  EXPECT_TRUE(mesh0->getTextures() == nullptr);
797  EXPECT_TRUE(mesh1->getTextures() == nullptr);
798  EXPECT_TRUE(mesh2->getTextures() == nullptr);
799 
800  ASSERT_TRUE(mesh3->getTextures() != nullptr);
801  ASSERT_EQ(mesh3->getTextures()->size(), 1);
802 
803  auto texture = mesh3->getTextures()->at(0);
804  EXPECT_EQ(texture->getTextureImage()->getResourceContents().size(), 38212);
805  EXPECT_EQ(texture->getUVs()->size(), 4);
806 }
807 #endif
808 
809 int main(int argc, char** argv)
810 {
811  testing::InitGoogleTest(&argc, argv);
812 
813  return RUN_ALL_TESTS();
814 }
tesseract_geometry::ConvexMesh
Definition: convex_mesh.h:45
tesseract_geometry::GeometryType::COMPOUND_MESH
@ COMPOUND_MESH
tesseract_geometry::Mesh
Definition: mesh.h:45
tesseract_geometry::GeometryType::CONE
@ CONE
tesseract_geometry::Octree
Definition: octree.h:58
tesseract_geometry::Plane
Definition: plane.h:44
tesseract_geometry::Sphere
Definition: sphere.h:44
utils.h
tesseract_common::almostEqualRelativeAndAbs
bool almostEqualRelativeAndAbs(const Eigen::Ref< const Eigen::VectorXd > &v1, const Eigen::Ref< const Eigen::VectorXd > &v2, const Eigen::Ref< const Eigen::VectorXd > &max_diff, const Eigen::Ref< const Eigen::VectorXd > &max_rel_diff)
TEST
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH TESSERACT_COMMON_IGNORE_WARNINGS_POP TEST(TesseractGeometryUnit, Instantiation)
Definition: tesseract_geometry_unit.cpp:14
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
tesseract_geometry::isIdentical
bool isIdentical(const Geometry &geom1, const Geometry &geom2)
Check if two Geometries are identical.
Definition: utils.cpp:38
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_geometry::GeometryType::MESH
@ MESH
tesseract_geometry::GeometryType::CYLINDER
@ CYLINDER
main
int main(int argc, char **argv)
Definition: tesseract_geometry_unit.cpp:809
utils.h
Tesseract Geometry Utility Function.
tesseract_geometry::PointCloud
A basic point cloud structure to leverage instead of PCL.
Definition: octree_utils.h:40
tesseract_geometry::SDFMesh
Definition: sdf_mesh.h:45
tesseract_geometry::Cylinder
Definition: cylinder.h:44
tesseract_geometry::GeometryType::PLANE
@ PLANE
tesseract_geometry::GeometryType::SPHERE
@ SPHERE
tesseract_geometry::GeometryType::CAPSULE
@ CAPSULE
mesh_parser.h
tesseract_geometry::Capsule
Definition: capsule.h:44
tesseract_geometry::GeometryType::SDF_MESH
@ SDF_MESH
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::GeometryType::BOX
@ BOX
tesseract_geometry
Definition: fwd.h:31
tesseract_geometry::GeometryType::OCTREE
@ OCTREE
tesseract_common::GeneralResourceLocator
tesseract_geometry::GeometryType::POLYGON_MESH
@ POLYGON_MESH
tesseract_geometry::GeometryType::CONVEX_MESH
@ CONVEX_MESH
macros.h
tesseract_geometry::Cone
Definition: cone.h:44
tesseract_geometry::Box
Definition: box.h:44
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