43 #include <Eigen/StdVector>
44 #include <gtest/gtest.h>
72 using PoseVector = std::vector<Transform3<S>,
73 Eigen::aligned_allocator<Transform3<S>>>;
78 static std::string value() {
return "unknown"; }
82 struct ScalarString<double> {
83 static std::string value() {
return "double"; }
87 struct ScalarString<float> {
88 static std::string value() {
return "float"; }
97 explicit Polytope(S scale)
98 : vertices_(std::make_shared<std::vector<
Vector3<S>>>()),
99 polygons_(std::make_shared<std::vector<int>>()), scale_(scale) {}
101 Polytope(
const Polytope &other)
102 : vertices_(std::make_shared<std::vector<
Vector3<S>>>(*(other.vertices_))),
103 polygons_(std::make_shared<std::vector<int>>(*(other.polygons_))),
104 scale_(other.scale_) {}
106 virtual int face_count()
const = 0;
107 virtual int vertex_count()
const = 0;
108 virtual S volume()
const {
throw std::logic_error(
"Not implemented yet"); }
109 virtual Vector3<S> com()
const {
110 throw std::logic_error(
"Not implemented yet");
112 virtual Matrix3<S> principal_inertia_tensor()
const {
113 throw std::logic_error(
"Not implemented yet");
115 virtual std::string description()
const {
116 throw std::logic_error(
"Not implemented yet");
120 S scale()
const {
return scale_; }
121 std::shared_ptr<const std::vector<Vector3<S>>> points()
const {
124 std::shared_ptr<const std::vector<int>> polygons()
const {
127 Convex<S> MakeConvex(
bool throw_if_invalid =
true)
const {
128 return Convex<S>(points(), face_count(), polygons(), throw_if_invalid);
130 Vector3<S> min_point()
const {
133 for (
const auto& v : *vertices_) {
134 for (
int i = 0; i < 3; ++i) {
135 if (v(i) < m(i)) m(i) = v(i);
140 Vector3<S> max_point()
const {
143 for (
const auto& v : *vertices_) {
144 for (
int i = 0; i < 3; ++i) {
145 if (v(i) > m(i)) m(i) = v(i);
150 Vector3<S> aabb_center()
const {
151 return (max_point() + min_point()) / 2;
153 S aabb_radius()
const {
return (min_point() - aabb_center()).norm(); }
154 void SetPose(
const Transform3<S>& X_WP) {
155 for (
auto& v : *vertices_) {
161 void add_vertex(
const Vector3<S>& vertex) { vertices_->push_back(vertex); }
162 void add_face(std::initializer_list<int> indices) {
163 polygons_->push_back(
static_cast<int>(indices.size()));
164 polygons_->insert(polygons_->end(), indices);
168 void confirm_data() {
170 GTEST_ASSERT_EQ(vertex_count(),
static_cast<int>(vertices_->size()));
176 while (i <
static_cast<int>(polygons_->size())) {
178 i += (*polygons_)[i] + 1;
180 GTEST_ASSERT_EQ(i,
static_cast<int>(polygons_->size()))
181 <<
"Badly defined polygons";
182 GTEST_ASSERT_EQ(face_count(), count);
186 std::shared_ptr<std::vector<Vector3<S>>> vertices_;
187 std::shared_ptr<std::vector<int>> polygons_;
193 template <
typename S>
194 class EquilateralTetrahedron :
public Polytope<S> {
197 explicit EquilateralTetrahedron(S scale) : Polytope<S>(scale) {
200 const S z_base = -1 / S(2 * sqrt(6.));
201 Vector3<S> points_T[] = {{S(0.5), S(-0.5 / sqrt(3.)), z_base},
202 {S(-0.5), S(-0.5 / sqrt(3.)), z_base},
203 {S(0), S(1. / sqrt(3.)), z_base},
204 {S(0), S(0), S(sqrt(3. / 8))}};
205 for (
const auto& v : points_T) {
206 this->add_vertex(scale * v);
210 this->add_face({0, 1, 2});
211 this->add_face({1, 0, 3});
212 this->add_face({0, 2, 3});
213 this->add_face({2, 1, 3});
215 this->confirm_data();
218 int face_count() const final {
return 4; }
219 int vertex_count() const final {
return 4; }
220 S volume() const final {
222 const S s = this->scale_;
223 return S(sqrt(2) / 12) * s * s * s;
225 Vector3<S> com() const final {
return Vector3<S>::Zero(); }
226 std::string description() const final {
227 return "Tetrahedron with scale: " + std::to_string(this->scale());
232 template <
typename S>
233 class Cube :
public Polytope<S> {
235 Cube(S scale) : Polytope<S>(scale) {
237 Vector3<S> points_C[] = {{S(-0.5), S(-0.5), S(-0.5)},
238 {S(0.5), S(-0.5), S(-0.5)},
239 {S(-0.5), S(0.5), S(-0.5)},
240 {S(0.5), S(0.5), S(-0.5)},
241 {S(-0.5), S(-0.5), S(0.5)},
242 {S(0.5), S(-0.5), S(0.5)},
243 {S(-0.5), S(0.5), S(0.5)},
244 {S(0.5), S(0.5), S(0.5)}};
245 for (
const auto& v : points_C) {
246 this->add_vertex(scale * v);
250 this->add_face({1, 3, 7, 5});
251 this->add_face({0, 4, 6, 2});
252 this->add_face({4, 5, 7, 6});
253 this->add_face({0, 2, 3, 1});
254 this->add_face({6, 7, 3, 2});
255 this->add_face({0, 1, 5, 4});
257 this->confirm_data();
261 int face_count() const final {
return 6; }
262 int vertex_count() const final {
return 8; }
263 virtual S volume() const final {
267 virtual Vector3<S> com() const final {
return Vector3<S>::Zero(); }
268 virtual Matrix3<S> principal_inertia_tensor()
const {
269 S scale_sqd = this->scale() * this->scale();
271 return Eigen::DiagonalMatrix<S, 3>(1. / 6., 1. / 6., 1. / 6.) * scale_sqd;
273 std::string description() const final {
274 return "Cube with scale: " + std::to_string(this->scale());
278 void testConvexConstruction() {
279 Cube<double> cube{1};
282 Vector3<double> p_WB(1, 2, 3);
294 template <
template <
typename>
class Shape,
typename S>
295 void testAABBComputation(
const Shape<S>& model,
const Transform3<S>& X_WS) {
296 Shape<S> shape(model);
298 Convex<S> convex = shape.MakeConvex();
299 convex.computeLocalAABB();
302 EXPECT_NEAR(shape.aabb_radius(), convex.aabb_radius, eps);
308 template <
template <
typename>
class Shape,
typename S>
309 void testVolume(
const Shape<S>& model,
const Transform3<S>& X_WS,
312 GTEST_ASSERT_LE(bits_lost, 10);
314 Shape<S> shape(model);
316 Convex<S> convex = shape.MakeConvex();
325 S scale =
max(shape.volume(), S(1));
326 EXPECT_NEAR(shape.volume(), convex.computeVolume(), eps * scale)
327 << shape.description() <<
" at\n" << X_WS.matrix()
328 <<
"\nusing scalar: " << ScalarString<S>::value();
331 template <
template <
typename>
class Shape,
typename S>
332 void testCenterOfMass(
const Shape<S>& model,
const Transform3<S>& X_WS,
335 GTEST_ASSERT_LE(bits_lost, 10);
337 Shape<S> shape(model);
339 Convex<S> convex = shape.MakeConvex();
349 S scale =
max(shape.volume(), S(1));
352 << shape.description() <<
" at\n" << X_WS.matrix()
353 <<
"\nusing scalar: " << ScalarString<S>::value();
356 template <
template <
typename>
class Shape,
typename S>
357 void testMomentOfInertia(
const Shape<S>& model,
const Transform3<S>& X_WS,
360 GTEST_ASSERT_LE(bits_lost, 10);
362 Shape<S> shape(model);
364 Convex<S> convex = shape.MakeConvex();
374 S scale =
max(shape.volume(), S(1));
377 shape.principal_inertia_tensor() * X_WS.linear(),
378 convex.computeMomentofInertiaRelatedToCOM(), eps * scale))
379 << shape.description() <<
" at\n" << X_WS.matrix()
380 <<
"\nusing scalar: " << ScalarString<S>::value();
384 template <
typename S>
385 struct SupportVertexTest {
394 template <
template <
typename>
class Shape,
typename S>
395 void testSupportVertex(
const Shape<S>& model,
const Transform3<S>& X_WS,
396 const std::vector<SupportVertexTest<S>>& tests) {
397 Shape<S> shape_W(model);
398 shape_W.SetPose(X_WS);
399 Convex<S> convex_W = shape_W.MakeConvex();
400 for (
const auto& test : tests) {
401 const Vector3<S> v_W = X_WS.linear() * test.v_S;
402 const Vector3<S> p_WE = X_WS * test.p_SE;
406 << shape_W.description() <<
" at\n"
407 << X_WS.matrix() <<
"\nusing scalar: " << ScalarString<S>::value()
408 <<
"\n v_W = " << v_W.transpose();
412 template <
typename S>
413 PoseVector<S> GetPoses() {
416 poses.push_back(Transform3<S>::Identity());
420 for (
int i = 0; i < 3; ++i) {
421 X_WS = Transform3<S>::Identity();
423 Vector3<S>::Unit(i)).matrix();
424 poses.push_back(X_WS);
428 X_WS.linear() = AngleAxis<S>(S(1e-5), Vector3<S>{1, 2, 3}.normalized())
430 poses.push_back(X_WS);
434 Vector3<S>{1, 2, 3}.normalized()).matrix();
435 poses.push_back(X_WS);
447 std::vector<double> get_test_scales() {
448 return std::vector<double>{0.001, 1, 1000.};
451 template <
template <
typename>
class Shape,
typename S>
452 void testLocalAABBComputation(
const Shape<S>& shape) {
453 for (
const auto& X_WP : GetPoses<S>()) {
454 testAABBComputation<Shape>(shape, X_WP);
458 template <
template <
typename>
class Shape,
typename S>
459 void testVolumeComputation(
const Shape<S>& shape,
int bits_lost) {
460 for (
const auto& X_WP : GetPoses<S>()) {
461 testVolume<Shape>(shape, X_WP, bits_lost);
465 template <
template <
typename>
class Shape,
typename S>
466 void testCenterOfMassComputation(
const Shape<S>& shape,
int bits_lost) {
467 for (
const auto& X_WP : GetPoses<S>()) {
468 testCenterOfMass<Shape>(shape, X_WP, bits_lost);
472 template <
template <
typename>
class Shape,
typename S>
473 void testMomentOfInertiaComputation(
const Shape<S>& shape,
int bits_lost) {
474 for (
const auto& X_WP : GetPoses<S>()) {
475 testMomentOfInertia<Shape>(shape, X_WP, bits_lost);
479 template <
template <
typename>
class Shape,
typename S>
480 void testSupportVertexComputation(
481 const Shape<S>& shape,
const std::vector<SupportVertexTest<S>>& tests) {
482 for (
const auto& X_WP : GetPoses<S>()) {
483 testSupportVertex<Shape>(shape, X_WP, tests);
488 testConvexConstruction();
491 GTEST_TEST(ConvexGeometry, LocalAABBComputation_Cube) {
492 for (
double scale : get_test_scales()) {
493 Cube<double> cube_d(scale);
494 testLocalAABBComputation(cube_d);
495 Cube<float> cube_f(
static_cast<float>(scale));
496 testLocalAABBComputation(cube_f);
501 for (
double scale : get_test_scales()) {
502 Cube<double> cube_d(scale);
503 testVolumeComputation(cube_d, 0);
504 Cube<float> cube_f(
static_cast<float>(scale));
509 const int bits_lost = scale > 1 ? 2 : 0;
510 testVolumeComputation(cube_f, bits_lost);
514 GTEST_TEST(ConvexGeometry, CenterOfMass_Cube) {
515 for (
double scale : get_test_scales()) {
516 Cube<double> cube_d(scale);
517 testCenterOfMassComputation(cube_d, 0);
518 Cube<float> cube_f(
static_cast<float>(scale));
519 testCenterOfMassComputation(cube_f, 0);
523 GTEST_TEST(ConvexGeometry, MomentOfInertia_Cube) {
524 for (
double scale : get_test_scales()) {
525 Cube<double> cube_d(scale);
526 testMomentOfInertiaComputation(cube_d, 0);
527 Cube<float> cube_f(
static_cast<float>(scale));
528 testMomentOfInertiaComputation(cube_f, 0);
532 GTEST_TEST(ConvexGeometry, LocalAABBComputation_Tetrahedron) {
533 for (
double scale : get_test_scales()) {
534 EquilateralTetrahedron<double> tet_d(scale);
535 testLocalAABBComputation(tet_d);
536 EquilateralTetrahedron<float> tet_f(
static_cast<float>(scale));
537 testLocalAABBComputation(tet_f);
541 GTEST_TEST(ConvexGeometry, Volume_Tetrahedron) {
542 for (
double scale : get_test_scales()) {
543 EquilateralTetrahedron<double> tet_d(scale);
548 const int bits_lost = scale > 1 ? 1 : 0;
549 testVolumeComputation(tet_d, bits_lost);
550 EquilateralTetrahedron<float> tet_f(
static_cast<float>(scale));
551 testVolumeComputation(tet_f, 0);
555 GTEST_TEST(ConvexGeometry, CenterOfMass_Tetrahedron) {
556 for (
double scale : get_test_scales()) {
557 EquilateralTetrahedron<double> tet_d(scale);
558 testCenterOfMassComputation(tet_d, 0);
559 EquilateralTetrahedron<float> tet_f(
static_cast<float>(scale));
560 testCenterOfMassComputation(tet_f, 0);
568 template <
typename S>
569 std::vector<SupportVertexTest<S>> BuildSupportVertexTests(
570 const Polytope<S>& polytope) {
571 std::vector<SupportVertexTest<S>> tests;
572 for (
const auto& p_SV : *polytope.points()) {
573 tests.push_back({p_SV, p_SV});
578 GTEST_TEST(ConvexGeometry, SupportVertex_Tetrahedron) {
579 for (
double scale : get_test_scales()) {
580 EquilateralTetrahedron<double> tet_d(scale);
581 std::vector<SupportVertexTest<double>> tests_d =
582 BuildSupportVertexTests(tet_d);
583 testSupportVertexComputation(tet_d, tests_d);
585 EquilateralTetrahedron<float> tet_f(scale);
586 std::vector<SupportVertexTest<float>> tests_f =
587 BuildSupportVertexTests(tet_f);
588 testSupportVertexComputation(tet_f, tests_f);
595 class CoPlanarTetrahedron final :
public Polytope<double> {
597 CoPlanarTetrahedron() : Polytope<double>(1.0) {
600 Vector3d points_T[] = {{0.5, -0.5 / sqrt(3.), 0},
601 {-0.5, -0.5 / sqrt(3.), 0},
602 {0, 1. / sqrt(3.), 0},
603 {0, 0, sqrt(3. / 8)}};
604 const Vector3d center = (points_T[0] + points_T[1] + points_T[2]) / 3.0;
605 this->add_vertex(center);
606 for (
const auto& v : points_T) {
611 this->add_face({0, 1, 2});
612 this->add_face({0, 2, 3});
613 this->add_face({0, 3, 1});
614 this->add_face({1, 3, 4});
615 this->add_face({3, 2, 4});
616 this->add_face({1, 4, 2});
618 this->confirm_data();
621 int face_count() const final {
return 6; }
622 int vertex_count() const final {
return 5; }
629 GTEST_TEST(ConvexGeometry, SupportVertexCoPlanarFaces) {
630 CoPlanarTetrahedron tet;
634 const Vector3d p_WE_expected = tet.points()->at(4);
645 class HoleTetrahedron final :
public Polytope<double> {
647 HoleTetrahedron() : Polytope<double>(1.0) {
650 EquilateralTetrahedron<double> tet(1.0);
651 vertices_->insert(vertices_->begin(), tet.points()->begin(),
652 tet.points()->end());
655 const std::vector<int>& polys = *tet.polygons();
658 const int face1 = polys[0] + 1;
659 polygons_->insert(polygons_->end(), polys.begin() + face1, polys.end());
661 this->confirm_data();
664 int face_count() const final {
return 3; }
665 int vertex_count() const final {
return 4; }
670 class CrackTetrahedron final :
public Polytope<double> {
672 CrackTetrahedron() : Polytope<double>(1.0) {
673 EquilateralTetrahedron<double> tet(1.0);
674 vertices_->insert(vertices_->begin(), tet.points()->begin(),
675 tet.points()->end());
676 vertices_->push_back((*vertices_)[0]);
680 this->add_face({4, 1, 2});
681 this->add_face({1, 0, 3});
682 this->add_face({0, 2, 3});
683 this->add_face({2, 1, 3});
685 this->confirm_data();
688 int face_count() const final {
return 4; }
689 int vertex_count() const final {
return 5; }
693 class StrayVertexTetrahedron final :
public Polytope<double> {
695 StrayVertexTetrahedron() : Polytope<double>(1.0) {
696 EquilateralTetrahedron<double> tet(1.0);
697 vertices_->insert(vertices_->begin(), tet.points()->begin(),
698 tet.points()->end());
700 vertices_->push_back({-1, -1, -1});
703 const std::vector<int>& polys = *tet.polygons();
704 polygons_->insert(polygons_->end(), polys.begin(), polys.end());
706 this->confirm_data();
709 int face_count() const final {
return 4; }
710 int vertex_count() const final {
return 5; }
714 class NonManifoldTetrahedron final :
public Polytope<double> {
716 NonManifoldTetrahedron() : Polytope<double>(1.0) {
717 EquilateralTetrahedron<double> tet(1.0);
718 vertices_->insert(vertices_->begin(), tet.points()->begin(),
719 tet.points()->end());
720 vertices_->push_back({0, 0, -5});
722 polygons_->insert(polygons_->end(), tet.polygons()->begin(),
723 tet.polygons()->end());
725 this->add_face({0, 1, 4});
727 this->confirm_data();
730 int face_count() const final {
return 5; }
731 int vertex_count() const final {
return 5; }
738 GTEST_TEST(ConvexGeometry, WaterTightValidation) {
741 HoleTetrahedron bad_tet;
743 bad_tet.MakeConvex(), std::runtime_error,
744 "Found errors in the Convex mesh[^]+ Edge between vertices \\d+ and "
745 "\\d+ is shared by 1 faces .+");
750 StrayVertexTetrahedron bad_tet;
752 bad_tet.MakeConvex(), std::runtime_error,
753 "Found errors in the Convex mesh[^]+ Not all vertices are connected[^]+"
754 " Vertex \\d+ is not included in any faces[^]*");
759 CrackTetrahedron bad_tet;
761 bad_tet.MakeConvex(), std::runtime_error,
762 "Found errors in the Convex mesh[^]+ Edge between vertices \\d+ and "
763 "\\d+ is shared by 1 faces .+");
768 NonManifoldTetrahedron bad_tet;
770 bad_tet.MakeConvex(), std::runtime_error,
771 "Found errors in the Convex mesh[^]+ Edge between vertices 0 and 1 is "
772 "shared by 3 faces [^]+");
777 class TessellatedSphere final :
public Polytope<double> {
779 TessellatedSphere() : Polytope<double>(1.0) {
781 const double dphi =
M_PI / 8;
782 auto slice_height = [dphi](
int slice_index) {
784 return std::cos(slice_index * dphi);
786 auto slice_radius = [dphi](
int slice_index) {
788 return std::sin(slice_index * dphi);
791 vertices_->push_back({0, 0, 1});
794 const double dtheta = 2 *
M_PI / 8;
795 for (
int slice = 1; slice < 8; ++slice) {
796 double z = slice_height(slice);
797 double r = slice_radius(slice);
798 for (
int i = 0; i < 8; ++i) {
799 const double theta = dtheta * i;
800 vertices_->emplace_back(std::cos(theta) *
r,
806 vertices_->push_back({0, 0, -1});
822 for (
int slice = 2; slice < 8; ++slice) {
836 this->confirm_data();
839 int face_count() const final {
return 64; }
840 int vertex_count() const final {
return 58; }
844 GTEST_TEST(ConvexGeometry, UseEdgeWalkingConditions) {
845 const bool throw_if_invalid{
true};
848 EquilateralTetrahedron<double> poly(1.0);
854 HoleTetrahedron poly;
861 TessellatedSphere poly;
879 std::make_shared<std::vector<Vector3<double>>>(
880 std::initializer_list<Vector3<double>>{
881 Vector3<double>(0, 0, 0), Vector3<double>(1.5, 0, 0),
882 Vector3<double>(0, 1.5, 0), Vector3<double>(1, 1.5, 0),}),
884 std::make_shared<std::vector<int>>(
885 std::initializer_list<int>{ 3, 0, 1, 2, 3, 1, 3, 2,}),
895 int main(
int argc,
char *argv[]) {
896 ::testing::InitGoogleTest(&argc, argv);
897 return RUN_ALL_TESTS();