43 #include <gtest/gtest.h> 44 #include <Eigen/Dense> 60 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80 : box_spec_1_(box_spec_1), box_spec_2_(box_spec_2) {
92 iso_poses_[
"top"] = Transform3<S>::Identity();
93 iso_poses_[
"bottom"] =
94 Transform3<S>{AngleAxis<S>(pi, Vector3<S>::UnitX())};
96 Transform3<S>{AngleAxis<S>(pi / 2, Vector3<S>::UnitX())};
98 Transform3<S>{AngleAxis<S>(3 * pi / 2, Vector3<S>::UnitX())};
100 Transform3<S>{AngleAxis<S>(pi / 2, Vector3<S>::UnitY())};
101 iso_poses_[
"right"] =
102 Transform3<S>{AngleAxis<S>(3 * pi / 2, Vector3<S>::UnitY())};
125 const std::string& origin_name) {
129 for (
const auto& reorient_pair : iso_poses_) {
130 const std::string& top_face = reorient_pair.first;
135 box_spec_2_.X_FB * pre_pose
140 RunSingleTest(box_spec_1_,
146 origin_name +
" (1, 2) - " + top_face);
150 RunSingleTest(box_2_posed,
156 origin_name +
" (2, 1) - " + top_face);
186 const std::string& origin_name) {
187 using CollisionGeometryPtr_t = std::shared_ptr<fcl::CollisionGeometry<S>>;
188 CollisionGeometryPtr_t box_geometry_A(
new fcl::Box<S>(box_spec_A.
size));
189 CollisionGeometryPtr_t box_geometry_B(
new fcl::Box<S>(box_spec_B.
size));
198 fcl::collide(&box_A, &box_B, collisionRequest, collisionResult);
200 std::vector<fcl::Contact<S>> contacts;
202 GTEST_ASSERT_EQ(contacts.size(), 1u) << origin_name;
210 << origin_name <<
":\n\texpected: " 211 << expected_contact.
normal.transpose()
212 <<
"\n\tcontact.normal: " << contact.normal.transpose();
213 contact_pos_test(contact.pos, test_tolerance, origin_name);
218 map<string, fcl::Transform3<S>, std::less<string>,
219 Eigen::aligned_allocator<std::pair<const string, fcl::Transform3<S>>>>
258 template <
typename S>
274 S expected_depth = size_1 * sqrt(2) / 2;
277 const std::string& origin_name) {
278 const double expected_pos_z = -size_1 * std::sqrt(2) / 4;
279 EXPECT_NEAR(expected_pos_z, pos(2), tolerance) << origin_name;
281 EXPECT_LE(pos(1), 0.5) << origin_name;
282 EXPECT_GE(pos(1), -0.5) << origin_name;
286 tests.
RunTests(solver_type, test_tolerance, expected_normal, expected_depth,
287 contact_pos_test,
"test_colliion_box_box_all_contacts");
296 GTEST_TEST(FCL_BOX_BOX, collision_box_box_all_contacts_indep)
342 template <
typename S>
348 const S tilt = pi / 8;
356 box_2.X_FB.translation() << 0, 0, -0.75;
359 const S expected_depth{sqrt(2) / 2 * cos(pi / 4 - tilt) - 0.25};
367 const S expected_z{-0.25 - expected_depth / 2};
368 const S expected_y{-sqrt(2) / 2 * sin(pi / 4 - tilt)};
369 const S expected_x{sqrt(2) / 2 + expected_y +
371 EXPECT_NEAR(expected_z, pos(2), tolerance) << origin_name;
372 EXPECT_NEAR(expected_y, pos(1), tolerance) << origin_name;
373 EXPECT_GE(pos(0), -expected_x);
374 EXPECT_LE(pos(0), expected_x);
378 tests.
RunTests(solver_type, test_tolerance, expected_normal, expected_depth,
379 contact_pos_test,
"test_collision_box_box_cull_contacts");
388 GTEST_TEST(FCL_BOX_BOX, collision_box_box_cull_contacts_indep)
422 template <
typename S>
432 const S expected_depth = 0.1;
433 box_1.X_FB.translation() = dir * (size * sqrt(2) -
expected_depth);
441 const S dist = size * sqrt(2) / 2 - expected_depth / 2;
445 <<
"\n\tpos: " << pos.transpose();
449 tests.
RunTests(solver_type, test_tolerance, -dir, expected_depth,
450 contact_pos_test,
"test_collision_box_box_edge_contact");
459 GTEST_TEST(FCL_BOX_BOX, collision_box_box_edge_contact_indep)
466 int main(
int argc,
char* argv[])
468 ::testing::InitGoogleTest(&argc, argv);
469 return RUN_ALL_TESTS();
void RunTests(fcl::GJKSolverType solver_type, S test_tolerance, const fcl::Vector3< S > &expected_normal, S expected_depth, std::function< void(const fcl::Vector3< S > &, S, const std::string &)> contact_pos_test, const std::string &origin_name)
void RunSingleTest(const BoxSpecification< S > &box_spec_A, const BoxSpecification< S > &box_spec_B, fcl::GJKSolverType solver_type, S test_tolerance, const fcl::Contact< S > &expected_contact, std::function< void(const fcl::Vector3< S > &, S, const std::string &)> contact_pos_test, const std::string &origin_name)
void test_collision_box_box_all_contacts(fcl::GJKSolverType solver_type, S test_tolerance)
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
void getContacts(std::vector< Contact< S >> &contacts_)
get all the contacts
#define EXPECT_NEAR(a, b, prec)
Eigen::Matrix< S, 3, 1 > Vector3
Vector3< S > expected_pos
Eigen::AngleAxis< S > AngleAxis
GJKSolverType gjk_solver_type
Enumeration indicating the GJK solver implementation to use.
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
BoxBoxTest(const BoxSpecification< S > &box_spec_1, const BoxSpecification< S > &box_spec_2)
Parameters for performing collision request.
int main(int argc, char *argv[])
Center at zero point, axis aligned box.
map< string, fcl::Transform3< S >, std::less< string >, Eigen::aligned_allocator< std::pair< const string, fcl::Transform3< S > > > > iso_poses_
static constexpr S pi()
The mathematical constant pi.
Eigen::Translation< S, 3 > Translation3
const BoxSpecification< S > box_spec_2_
fcl::Transform3< S > X_FB
Vector3< S > expected_normal
the object for collision or distance computation, contains the geometry and the transform information...
void test_collision_box_box_cull_contacts(fcl::GJKSolverType solver_type, S test_tolerance)
GTEST_TEST(FCL_BOX_BOX, collision_box_box_all_contacts_ccd)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW fcl::Vector3< S > size
const BoxSpecification< S > box_spec_1_
void test_collision_box_box_edge_contact(fcl::GJKSolverType solver_type, S test_tolerance)
bool isCollision() const
return binary collision result
#define EXPECT_TRUE(args)
GJKSolverType
Type of narrow phase GJK solver.