39 #include <gtest/gtest.h> 40 #include <Eigen/Dense> 100 const Real h = 0.0025;
103 const Vector3<S>
half_size{w / 2, d / 2, h / 2};
104 const Real
r = 0.0015;
105 auto sphere_geometry = std::make_shared<fcl::Sphere<S>>(
r);
106 auto box_geometry = std::make_shared<fcl::Box<S>>(w, d, h);
116 const Real target_depth = r * 0.5;
118 const Real sz = h / 2 + r - target_depth;
119 const Real pz = h / 2 - target_depth / 2;
149 const std::vector<Real> x_values{
152 const std::vector<Real> y_values{
155 for (Real sx : x_values) {
156 for (Real sy : y_values ) {
158 X_WS.translation() << sx, sy, sz;
161 auto evaluate_collision = [&collision_request, &X_WS](
167 std::size_t contact_count =
168 fcl::collide(s1, s2, collision_request, collision_result);
172 std::vector<fcl::Contact<S>> contacts;
177 EXPECT_NEAR(contact.penetration_depth, expected_depth, eps)
178 <<
"Sphere at: " << X_WS.translation().transpose();
183 <<
"Sphere at: " << X_WS.translation().transpose();
186 <<
"Sphere at: " << X_WS.translation().transpose();
188 EXPECT_TRUE(
false) <<
"No contacts reported for sphere at: " 189 << X_WS.translation().transpose();
193 Vector3<S> expected_pos{sx, sy, pz};
194 evaluate_collision(&sphere, &box, expected_depth, expected_normal,
196 evaluate_collision(&box, &sphere, expected_depth, -expected_normal,
213 int main(
int argc,
char* argv[]) {
214 ::testing::InitGoogleTest(&argc, argv);
215 return RUN_ALL_TESTS();
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)
GTEST_TEST(FCL_SPHERE_BOX, LargBoxSmallSphere_ccd)
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.
Vector3< S > expected_normal
the object for collision or distance computation, contains the geometry and the transform information...
void LargeBoxSmallSphereTest(fcl::GJKSolverType solver_type)
#define EXPECT_TRUE(args)
GJKSolverType
Type of narrow phase GJK solver.
int main(int argc, char *argv[])