38 #include <gtest/gtest.h> 51 const S radius = 0.05;
52 const S length = 4 * radius;
55 auto cylinder = std::make_shared<Cylinder<S>>(radius, length);
72 fcl::collide(&half_space_co, &cylinder_co, request, result);
73 vector<Contact<S>> contacts;
76 EXPECT_EQ(static_cast<int>(contacts.size()), 1);
77 EXPECT_NEAR(contacts[0].penetration_depth, 0.051, kTolerance);
81 Vector3d::UnitX()).matrix();
88 fcl::collide(&half_space_co, &cylinder_co, request, result);
91 EXPECT_EQ(static_cast<int>(contacts.size()), 1);
92 EXPECT_NEAR(contacts[0].penetration_depth, 0.051, kTolerance);
95 GTEST_TEST(FCL_GEOMETRIC_SHAPES, collision_cylinder_half_space_libccd)
100 GTEST_TEST(FCL_GEOMETRIC_SHAPES, collision_cylinder_half_space_indep)
105 int main(
int argc,
char* argv[])
107 ::testing::InitGoogleTest(&argc, argv);
108 return RUN_ALL_TESTS();
int main(int argc, char *argv[])
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
void test_collision_cylinder_half_space(fcl::GJKSolverType solver_type)
void getContacts(std::vector< Contact< S >> &contacts_)
get all the contacts
#define EXPECT_NEAR(a, b, prec)
Eigen::Matrix< S, 3, 1 > Vector3
void setTransform(const Matrix3< S > &R, const Vector3< S > &T)
set object's transform
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)
Parameters for performing collision request.
static constexpr S pi()
The mathematical constant pi.
Eigen::Translation< S, 3 > Translation3
GTEST_TEST(FCL_GEOMETRIC_SHAPES, collision_cylinder_half_space_libccd)
the object for collision or distance computation, contains the geometry and the transform information...
GJKSolverType
Type of narrow phase GJK solver.
void clear()
clear the results obtained