40 #include <gtest/gtest.h>
44 TEST(SphereBoundingCylinder, Sphere1)
70 TEST(SphereBoundingCylinder, Sphere2)
74 Eigen::Isometry3d pose(Eigen::Isometry3d::TranslationType(1, 2, 3));
88 pose *= Eigen::AngleAxisd(
M_PI_2, Eigen::Vector3d(1, 1, 1).normalized());
101 Eigen::Quaterniond quat;
103 for (
size_t i = 0; i < 10; ++i)
106 quat.x() = quatData[0];
107 quat.y() = quatData[1];
108 quat.z() = quatData[2];
109 quat.w() = quatData[3];
110 pose.linear() = quat.toRotationMatrix();
124 TEST(BoxBoundingCylinder, Box1)
164 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).x(), 1e-4);
167 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
178 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).x(), 1e-4);
181 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
193 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).y(), 1e-4);
195 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
207 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).y(), 1e-4);
209 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
214 TEST(BoxBoundingCylinder, Box2)
218 Eigen::Isometry3d pose;
220 pose.translation() = Eigen::Vector3d(1, 2, 3);
235 Eigen::AngleAxisd rot(
M_PI_2, Eigen::Vector3d(1, 1, 1).normalized());
243 EXPECT_NEAR(Eigen::Quaterniond(rot).
x(), Eigen::Quaterniond(bcyl.
pose.linear()).x(), 1e-4);
244 EXPECT_NEAR(Eigen::Quaterniond(rot).
y(), Eigen::Quaterniond(bcyl.
pose.linear()).y(), 1e-4);
245 EXPECT_NEAR(Eigen::Quaterniond(rot).
z(), Eigen::Quaterniond(bcyl.
pose.linear()).z(), 1e-4);
246 EXPECT_NEAR(Eigen::Quaterniond(rot).w(), Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
251 TEST(CylinderBoundingCylinder, Cylinder1)
283 TEST(CylinderBoundingCylinder, Cylinder2)
287 Eigen::Isometry3d pose;
289 pose.translation() = Eigen::Vector3d(1, 2, 3);
304 pose.linear() = Eigen::AngleAxisd(
M_PI_2, Eigen::Vector3d(1, 1, 1).normalized()).toRotationMatrix();
311 EXPECT_NEAR(Eigen::Quaterniond(pose.linear()).x(), Eigen::Quaterniond(bcyl.
pose.linear()).x(), 1e-4);
312 EXPECT_NEAR(Eigen::Quaterniond(pose.linear()).y(), Eigen::Quaterniond(bcyl.
pose.linear()).y(), 1e-4);
313 EXPECT_NEAR(Eigen::Quaterniond(pose.linear()).z(), Eigen::Quaterniond(bcyl.
pose.linear()).z(), 1e-4);
314 EXPECT_NEAR(Eigen::Quaterniond(pose.linear()).w(), Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
406 TEST(MeshBoundingCylinder, Mesh1)
441 radiusScaled = 2 * sqrt(0.5 * 0.5 + 1 * 1);
442 EXPECT_LE(radiusScaled, bcyl.
radius);
443 EXPECT_GE(radiusScaled + 1.0, bcyl.
radius);
445 EXPECT_LE(lengthScaled, bcyl.
length);
446 EXPECT_GE(lengthScaled + 2 * 1.0, bcyl.
length);
454 body2.computeBoundingCylinder(bcyl);
459 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).x(), 1e-4);
462 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
468 body2.setPadding(1.0);
469 body2.computeBoundingCylinder(bcyl);
474 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).x(), 1e-4);
477 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
478 radiusScaled = 2 * sqrt(0.5 * 0.5 + 1 * 1);
479 EXPECT_LE(radiusScaled, bcyl.
radius);
480 EXPECT_GE(radiusScaled + 1.0, bcyl.
radius);
482 EXPECT_LE(lengthScaled, bcyl.
length);
483 EXPECT_GE(lengthScaled + 2 * 1.0, bcyl.
length);
489 body3.computeBoundingCylinder(bcyl);
495 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).y(), 1e-4);
497 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
503 body3.setPadding(1.0);
504 body3.computeBoundingCylinder(bcyl);
510 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).y(), 1e-4);
512 EXPECT_NEAR(M_SQRT1_2, Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
513 radiusScaled = 2 * sqrt(0.5 * 0.5 + 1 * 1);
514 EXPECT_LE(radiusScaled, bcyl.
radius);
515 EXPECT_GE(radiusScaled + 1.0, bcyl.
radius);
517 EXPECT_LE(lengthScaled, bcyl.
length);
518 EXPECT_GE(lengthScaled + 2 * 1.0, bcyl.
length);
523 TEST(MeshBoundingCylinder, Mesh2)
528 Eigen::Isometry3d pose;
530 pose.translation() = Eigen::Vector3d(1, 2, 3);
533 body.computeBoundingCylinder(bcyl);
546 Eigen::AngleAxisd rot(
M_PI_2, Eigen::Vector3d(1, 1, 1).normalized());
549 body.computeBoundingCylinder(bcyl);
554 EXPECT_NEAR(Eigen::Quaterniond(rot).
x(), Eigen::Quaterniond(bcyl.
pose.linear()).x(), 1e-4);
555 EXPECT_NEAR(Eigen::Quaterniond(rot).
y(), Eigen::Quaterniond(bcyl.
pose.linear()).y(), 1e-4);
556 EXPECT_NEAR(Eigen::Quaterniond(rot).
z(), Eigen::Quaterniond(bcyl.
pose.linear()).z(), 1e-4);
557 EXPECT_NEAR(Eigen::Quaterniond(rot).w(), Eigen::Quaterniond(bcyl.
pose.linear()).w(), 1e-4);
565 int main(
int argc,
char** argv)
567 testing::InitGoogleTest(&argc, argv);
568 return RUN_ALL_TESTS();