39 #include <gtest/gtest.h> 40 #include <Eigen/Dense> 103 template <
typename S>
113 const Real h_c = 0.0025;
114 const Real
r_s = 0.0015;
116 auto sphere_geometry = std::make_shared<fcl::Sphere<S>>(
r_s);
117 auto cylinder_geometry = std::make_shared<fcl::Cylinder<S>>(
r_c, h_c);
127 const Real target_depth = r_s * 0.5;
129 const Real sz = h_c / 2 + r_s - target_depth;
130 const Real pz = h_c / 2 - target_depth / 2;
159 const std::vector<Real> r_values{0, eps, r_c / 2, r_c - r_s};
161 const std::vector<Real> theta_values{0, pi/2, pi, 3 * pi / 4};
163 for (
const Real
r : r_values) {
164 for (
const Real theta : theta_values ) {
167 const Real angle = theta + pi / 7;
168 const Real sx = cos(angle) *
r;
169 const Real sy = sin(angle) *
r;
171 X_WS.translation() << sx, sy, sz;
174 auto evaluate_collision = [&collision_request, &X_WS](
180 std::size_t contact_count =
181 fcl::collide(s1, s2, collision_request, collision_result);
185 std::vector<fcl::Contact<S>> contacts;
190 EXPECT_NEAR(contact.penetration_depth, expected_depth, eps)
191 <<
"Sphere at: " << X_WS.translation().transpose();
196 <<
"Sphere at: " << X_WS.translation().transpose();
199 <<
"Sphere at: " << X_WS.translation().transpose();
201 EXPECT_TRUE(
false) <<
"No contacts reported for sphere at: " 202 << X_WS.translation().transpose();
206 Vector3<S> expected_pos{sx, sy, pz};
207 evaluate_collision(&sphere, &cylinder, expected_depth, expected_normal,
209 evaluate_collision(&cylinder, &sphere, expected_depth, -expected_normal,
215 GTEST_TEST(FCL_SPHERE_CYLINDER, LargCylinderSmallSphere_ccd) {
226 int main(
int argc,
char* argv[]) {
227 ::testing::InitGoogleTest(&argc, argv);
228 return RUN_ALL_TESTS();
void LargeCylinderSmallSphereTest(fcl::GJKSolverType solver_type)
size_t num_max_contacts
The maximum number of contacts that can be returned.
::testing::AssertionResult CompareMatrices(const Eigen::MatrixBase< DerivedA > &m1, const Eigen::MatrixBase< DerivedB > &m2, double tolerance=0.0, MatrixCompareType compare_type=MatrixCompareType::absolute)
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
static constexpr Real eps()
Returns ε for the precision of the underlying scalar type.
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
void setTransform(const Matrix3< S > &R, const Vector3< S > &T)
set object's transform
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)
detail::ScalarTrait< S >::type Real
Parameters for performing collision request.
static constexpr S pi()
The mathematical constant pi.
int main(int argc, char *argv[])
Vector3< S > expected_normal
the object for collision or distance computation, contains the geometry and the transform information...
GTEST_TEST(FCL_SPHERE_CYLINDER, LargCylinderSmallSphere_ccd)
#define EXPECT_TRUE(args)
GJKSolverType
Type of narrow phase GJK solver.