39 #include <gtest/gtest.h> 40 #include <Eigen/Dense> 63 return Vector3d{vector.v[0], vector.v[1], vector.v[2]};
69 const ccd_vec3_t& tested,
72 return ::testing::AssertionFailure() <<
"Invalid tolerance: " 77 Vector3d error = (expected - ccd).cwiseAbs();
79 for (
int i = 0; i < 3; ++i) {
81 return ::testing::AssertionFailure()
82 <<
"Values at index " << i
83 <<
" exceed tolerance; " << expected(i) <<
" vs " 84 << ccd(i) <<
", diff = " << error(i)
85 <<
", tolerance = " << tolerance <<
"\nexpected = " 86 << expected.transpose() <<
"\ntested = " 87 << ccd.transpose() <<
"\n|delta| = " 91 return ::testing::AssertionSuccess();
123 const ccd_real_t almost_eps = eps * 0.75;
124 const ccd_real_t extra_eps = eps * 1.5;
142 const double scale = 100;
143 p << scale, scale, scale;
160 p << 0.01, 0.01, 0.01;
251 const ccd_real_t theta_e = asin(eps);
258 const ccd_real_t colinear_theta = tan(theta_e * 0.75);
259 Vector3d c_prime = b + (b.norm() * colinear_theta) * v_hat;
265 const ccd_real_t good_tan = tan(theta_e * 1.5);
266 c_prime = b + (b.norm() * good_tan) * v_hat;
281 for (
int i = 0; i < 3; ++i) {
301 const char* message) {
339 return a * s + b * (1 - s);
348 const Vector3d t1_[3] = {{0, 0.25, 0.25}, {1, 0.25, 0.25}, {0.5, 0.8, 1.0}};
392 "ExtractFrom1Simplex");
409 const double s = 1 / 3.0;
410 ASSERT_TRUE(s >= 0 && s <= 1);
448 const double s = 1 / 3.0;
449 ASSERT_TRUE(s >= 0 && s <= 1);
456 "ExtractFrom2Simplex");
480 "ExtractFrom2SimplexDegenerate");
488 const double alpha = 0.25;
489 const double beta = 0.33;
490 ASSERT_TRUE(alpha >= 0 && alpha <= 1 && beta >= 0 && beta <= 1 &&
500 return a * s1 + b * s2 + c * (1 - s1 - s2);
503 ccd_vec3_t closest =
eigen_to_ccd(interpolate(m0, m1, m2, alpha, beta));
508 "ExtractFrom3Simplex");
523 for (
auto i : {1, 2}) {
536 "ExtractFrom3SimplexDegenerateCoincident");
548 const double s = 1 / 3.0;
549 ASSERT_TRUE(s >= 0 && s <= 1);
562 auto linearly_combine = [](
const ccd_vec3_t& a,
const ccd_vec3_t& b,
574 "ExtractFrom3SimplexDegenerateColinear");
581 int main(
int argc,
char* argv[]) {
582 ::testing::InitGoogleTest(&argc, argv);
583 return RUN_ALL_TESTS();
int last
index of last added point
TEST_F(ExtractClosestPoint, ExtractFrom1SimplexSupport)
static Real eps_78()
Returns ε^(7/8) for the precision of the underlying scalar type.
bool are_coincident(const Vector3d &p, const Vector3d &q)
::testing::AssertionResult are_same(const Vector3d &expected, const ccd_vec3_t &tested, double tolerance)
static constexpr Real eps()
Returns ε for the precision of the underlying scalar type.
ccd_vec3_t eigen_to_ccd(const Vector3d &vector)
Eigen::Matrix< S, 3, 1 > Vector3
Vector3< double > Vector3d
#define EXPECT_FALSE(args)
static bool triangle_area_is_zero(const ccd_vec3_t &a, const ccd_vec3_t &b, const ccd_vec3_t &c)
ccd_vec3_t v
Support point in minkowski sum.
Vector3d ccd_to_eigen(const ccd_vec3_t &vector)
static void extractObjectPointsFromPoint(ccd_support_t *q, ccd_vec3_t *p1, ccd_vec3_t *p2)
ccd_vec3_t v1
Support point in obj1.
static void extractClosestPoints(ccd_simplex_t *simplex, ccd_vec3_t *p1, ccd_vec3_t *p2, ccd_vec3_t *p)
GTEST_TEST(FCL_GJK_EPA, faceNormalPointingOutward)
_ccd_inline void ccdSupportCopy(ccd_support_t *, const ccd_support_t *s)
ccd_vec3_t v2
Support point in obj2.
static bool are_coincident(const ccd_vec3_t &p, const ccd_vec3_t &q)
static void extractObjectPointsFromSegment(ccd_support_t *a, ccd_support_t *b, ccd_vec3_t *p1, ccd_vec3_t *p2, ccd_vec3_t *p)
#define EXPECT_TRUE(args)
bool triangle_area_is_zero(const Vector3d &a, const Vector3d &b, const Vector3d &c)