Skip to content

Commit d2471f2

Browse files
Add a guard to faceNormalPointingOutward to detect degeneracy
This adds the `triangle_area_is_zero` test to `faceNormalPointingOutward`. This is a prerequisite to the `isOutsidePolytopeFace` test. The test is rendered meaningless if the reported normal is defined by numerical noise. If a scenario is failing due to the `isOutsidePolytopFace` assertion failing, this will detect if its due to face degeneracies.
1 parent a278363 commit d2471f2

File tree

2 files changed

+207
-59
lines changed

2 files changed

+207
-59
lines changed

include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h

+69-59
Original file line numberDiff line numberDiff line change
@@ -765,6 +765,64 @@ static int simplexToPolytope4(const void *obj1, const void *obj2,
765765
return 0;
766766
}
767767

768+
/** Reports true if p and q are coincident. */
769+
static bool are_coincident(const ccd_vec3_t& p, const ccd_vec3_t& q) {
770+
// This uses a scale-dependent basis for determining coincidence. It examines
771+
// each axis independently, and only, if all three axes are sufficiently
772+
// close (relative to its own scale), are the two points considered
773+
// coincident.
774+
//
775+
// For dimension i, two values are considered the same if:
776+
// |pᵢ - qᵢ| <= ε·max(1, |pᵢ|, |pᵢ|)
777+
// And the points are coincident if the previous condition for all
778+
// `i ∈ {0, 1, 2}` (i.e. the x-, y-, *and* z-dimensions).
779+
using std::abs;
780+
using std::max;
781+
782+
const ccd_real_t eps = constants<ccd_real_t>::eps();
783+
// NOTE: Wrapping "1.0" with ccd_real_t accounts for mac problems where ccd
784+
// is actually float based.
785+
for (int i = 0; i < 3; ++i) {
786+
const ccd_real_t scale =
787+
max({ccd_real_t{1}, abs(p.v[i]), abs(q.v[i])}) * eps;
788+
const ccd_real_t delta = abs(p.v[i] - q.v[i]);
789+
if (delta > scale) return false;
790+
}
791+
return true;
792+
}
793+
794+
/** Determines if the the triangle defined by the three vertices has zero area.
795+
Area can be zero for one of two reasons:
796+
- the triangle is so small that the vertices are functionally coincident, or
797+
- the vertices are co-linear.
798+
Both conditions are computed with respect to machine precision.
799+
@returns true if the area is zero. */
800+
static bool triangle_area_is_zero(const ccd_vec3_t& a, const ccd_vec3_t& b,
801+
const ccd_vec3_t& c) {
802+
// First coincidence condition. This doesn't *explicitly* test for b and c
803+
// being coincident. That will be captured in the subsequent co-linearity
804+
// test. If b and c *were* coincident, it would be cheaper to perform the
805+
// coincidence test than the co-linearity test.
806+
// However, the expectation is that typically the triangle will not have zero
807+
// area. In that case, we want to minimize the number of tests performed on
808+
// the average, so we prefer to eliminate one coincidence test.
809+
if (are_coincident(a, b) || are_coincident(a, c)) return true;
810+
811+
// We're going to compute the *sine* of the angle θ between edges (given that
812+
// the vertices are *not* coincident). If the sin(θ) < ε, the edges are
813+
// co-linear.
814+
ccd_vec3_t AB, AC, n;
815+
ccdVec3Sub2(&AB, &b, &a);
816+
ccdVec3Sub2(&AC, &c, &a);
817+
ccdVec3Normalize(&AB);
818+
ccdVec3Normalize(&AC);
819+
ccdVec3Cross(&n, &AB, &AC);
820+
const ccd_real_t eps = constants<ccd_real_t>::eps();
821+
// Second co-linearity condition.
822+
if (ccdVec3Len2(&n) < eps * eps) return true;
823+
return false;
824+
}
825+
768826
/**
769827
* Computes the normal vector of a triangular face on a polytope, and the normal
770828
* vector points outward from the polytope. Notice we assume that the origin
@@ -778,6 +836,17 @@ static int simplexToPolytope4(const void *obj1, const void *obj2,
778836
*/
779837
static ccd_vec3_t faceNormalPointingOutward(const ccd_pt_t* polytope,
780838
const ccd_pt_face_t* face) {
839+
// This doesn't necessarily define a triangle; I don't know that the third
840+
// vertex added here is unique from the other two.
841+
#ifndef NDEBUG
842+
// quick test for degeneracy
843+
const ccd_vec3_t& a = face->edge[0]->vertex[1]->v.v;
844+
const ccd_vec3_t& b = face->edge[0]->vertex[0]->v.v;
845+
const ccd_vec3_t& test_v = face->edge[1]->vertex[0]->v.v;
846+
const ccd_vec3_t& c = are_coincident(test_v, a) || are_coincident(test_v, b) ?
847+
face->edge[1]->vertex[1]->v.v : test_v;
848+
assert(!triangle_area_is_zero(a, b, c));
849+
#endif
781850
// We find two edges of the triangle as e1 and e2, and the normal vector
782851
// of the face is e1.cross(e2).
783852
ccd_vec3_t e1, e2;
@@ -1363,65 +1432,6 @@ static int __ccdEPA(const void *obj1, const void *obj2,
13631432
return 0;
13641433
}
13651434

1366-
1367-
/** Reports true if p and q are coincident. */
1368-
static bool are_coincident(const ccd_vec3_t& p, const ccd_vec3_t& q) {
1369-
// This uses a scale-dependent basis for determining coincidence. It examines
1370-
// each axis independently, and only, if all three axes are sufficiently
1371-
// close (relative to its own scale), are the two points considered
1372-
// coincident.
1373-
//
1374-
// For dimension i, two values are considered the same if:
1375-
// |pᵢ - qᵢ| <= ε·max(1, |pᵢ|, |pᵢ|)
1376-
// And the points are coincident if the previous condition for all
1377-
// `i ∈ {0, 1, 2}` (i.e. the x-, y-, *and* z-dimensions).
1378-
using std::abs;
1379-
using std::max;
1380-
1381-
const ccd_real_t eps = constants<ccd_real_t>::eps();
1382-
// NOTE: Wrapping "1.0" with ccd_real_t accounts for mac problems where ccd
1383-
// is actually float based.
1384-
for (int i = 0; i < 3; ++i) {
1385-
const ccd_real_t scale =
1386-
max({ccd_real_t{1}, abs(p.v[i]), abs(q.v[i])}) * eps;
1387-
const ccd_real_t delta = abs(p.v[i] - q.v[i]);
1388-
if (delta > scale) return false;
1389-
}
1390-
return true;
1391-
}
1392-
1393-
/** Determines if the the triangle defined by the three vertices has zero area.
1394-
Area can be zero for one of two reasons:
1395-
- the triangle is so small that the vertices are functionally coincident, or
1396-
- the vertices are co-linear.
1397-
Both conditions are computed with respect to machine precision.
1398-
@returns true if the area is zero. */
1399-
static bool triangle_area_is_zero(const ccd_vec3_t& a, const ccd_vec3_t& b,
1400-
const ccd_vec3_t& c) {
1401-
// First coincidence condition. This doesn't *explicitly* test for b and c
1402-
// being coincident. That will be captured in the subsequent co-linearity
1403-
// test. If b and c *were* coincident, it would be cheaper to perform the
1404-
// coincidence test than the co-linearity test.
1405-
// However, the expectation is that typically the triangle will not have zero
1406-
// area. In that case, we want to minimize the number of tests performed on
1407-
// the average, so we prefer to eliminate one coincidence test.
1408-
if (are_coincident(a, b) || are_coincident(a, c)) return true;
1409-
1410-
// We're going to compute the *sine* of the angle θ between edges (given that
1411-
// the vertices are *not* coincident). If the sin(θ) < ε, the edges are
1412-
// co-linear.
1413-
ccd_vec3_t AB, AC, n;
1414-
ccdVec3Sub2(&AB, &b, &a);
1415-
ccdVec3Sub2(&AC, &c, &a);
1416-
ccdVec3Normalize(&AB);
1417-
ccdVec3Normalize(&AC);
1418-
ccdVec3Cross(&n, &AB, &AC);
1419-
const ccd_real_t eps = constants<ccd_real_t>::eps();
1420-
// Second co-linearity condition.
1421-
if (ccdVec3Len2(&n) < eps * eps) return true;
1422-
return false;
1423-
}
1424-
14251435
/** Given a single support point, `q`, extract the point `p1` and `p2`, the
14261436
points on object 1 and 2, respectively, in the support data of `q`. */
14271437
static void extractObjectPointsFromPoint(ccd_support_t *q, ccd_vec3_t *p1,

test/narrowphase/detail/convexity_based_algorithm/test_gjk_libccd-inl_epa.cpp

+138
Original file line numberDiff line numberDiff line change
@@ -293,6 +293,144 @@ GTEST_TEST(FCL_GJK_EPA, isOutsidePolytopeFace) {
293293
CheckPointOutsidePolytopeFace(0, 0, 0, 3, expect_inside);
294294
}
295295

296+
#ifndef NDEBUG
297+
298+
/** A degenerate tetrahedron due to vertices considered to be coincident.
299+
It is, strictly speaking a valid tetrahedron, but the points are so close that
300+
the calculations on edge lengths cannot be trusted.
301+
302+
More particularly, one face is *very* small but the other three faces are quite
303+
long with horrible aspect ratio.
304+
305+
Vertices v0, v1, and v2 are all close to each other, v3 is distant.
306+
Edges e0, e1, and e2 connect vertices (v0, v1, and v2) and, as such, have very
307+
short length. Edges e3, e4, and e5 connect to the distance vertex and have
308+
long length.
309+
310+
Face 0 is the small face. Faces 1-3 all include one edge of the small face.
311+
312+
All faces should be considered degenerate due to coincident points. */
313+
class CoincidentTetrahedron : public Polytope {
314+
public:
315+
CoincidentTetrahedron() : Polytope() {
316+
const ccd_real_t delta = constants<ccd_real_t>::eps() / 4;
317+
v().resize(4);
318+
e().resize(6);
319+
f().resize(4);
320+
auto AddTetrahedronVertex = [this](ccd_real_t x, ccd_real_t y,
321+
ccd_real_t z) {
322+
return ccdPtAddVertexCoords(&this->polytope(), x, y, z);
323+
};
324+
v()[0] = AddTetrahedronVertex(0.5, delta, delta);
325+
v()[1] = AddTetrahedronVertex(0.5, -delta, delta);
326+
v()[2] = AddTetrahedronVertex(0.5, -delta, -delta);
327+
v()[3] = AddTetrahedronVertex(-0.5, 0, 0);
328+
e()[0] = ccdPtAddEdge(&polytope(), &v(0), &v(1));
329+
e()[1] = ccdPtAddEdge(&polytope(), &v(1), &v(2));
330+
e()[2] = ccdPtAddEdge(&polytope(), &v(2), &v(0));
331+
e()[3] = ccdPtAddEdge(&polytope(), &v(0), &v(3));
332+
e()[4] = ccdPtAddEdge(&polytope(), &v(1), &v(3));
333+
e()[5] = ccdPtAddEdge(&polytope(), &v(2), &v(3));
334+
f()[0] = ccdPtAddFace(&polytope(), &e(0), &e(1), &e(2));
335+
f()[1] = ccdPtAddFace(&polytope(), &e(0), &e(3), &e(4));
336+
f()[2] = ccdPtAddFace(&polytope(), &e(1), &e(4), &e(5));
337+
f()[3] = ccdPtAddFace(&polytope(), &e(3), &e(5), &e(2));
338+
}
339+
};
340+
341+
// Tests against a polytope with a face where all the points are too close to
342+
// distinguish.
343+
GTEST_TEST(FCL_GJK_EPA, isOutsidePolytopeFace_DegenerateFace_Coincident0) {
344+
::testing::FLAGS_gtest_death_test_style = "threadsafe";
345+
CoincidentTetrahedron p;
346+
347+
// The test point doesn't matter; it'll never get that far.
348+
// NOTE: For platform compatibility, the assertion message is pared down to
349+
// the simplest component: the actual function call in the assertion.
350+
ccd_vec3_t pt{{10, 10, 10}};
351+
ASSERT_DEATH(
352+
libccd_extension::isOutsidePolytopeFace(&p.polytope(), &p.f(0), &pt),
353+
".*!triangle_area_is_zero.*");
354+
}
355+
356+
// Tests against a polytope with a face where *two* points are too close to
357+
// distinguish.
358+
GTEST_TEST(FCL_GJK_EPA, isOutsidePolytopeFace_DegenerateFace_Coincident1) {
359+
::testing::FLAGS_gtest_death_test_style = "threadsafe";
360+
CoincidentTetrahedron p;
361+
362+
// The test point doesn't matter; it'll never get that far.
363+
// NOTE: For platform compatibility, the assertion message is pared down to
364+
// the simplest component: the actual function call in the assertion.
365+
ccd_vec3_t pt{{10, 10, 10}};
366+
ASSERT_DEATH(
367+
libccd_extension::isOutsidePolytopeFace(&p.polytope(), &p.f(1), &pt),
368+
".*!triangle_area_is_zero.*");
369+
}
370+
371+
/** A degenerate tetrahedron due to vertices considered to be colinear.
372+
It is, strictly speaking a valid tetrahedron, but the vertices are so close to
373+
being colinear, that the area can't meaningfully be computed.
374+
375+
More particularly, one face is *very* large but the fourth vertex lies just
376+
slightly off that plane *over* one of the edges. The face that is incident to
377+
that edge and vertex will have colinear edges.
378+
379+
Vertices v0, v1, and v2 are form the large triangle. v3 is the slightly
380+
off-plane vertex. Edges e0, e1, and e2 connect vertices (v0, v1, and v2). v3
381+
projects onto edge e0. Edges e3 and e4 connect v0 and v1 to v3, respectively.
382+
Edges e3 and e4 are colinear. Edge e5 is the remaining, uninteresting edge.
383+
Face 0 is the large triangle.
384+
Face 1 is the bad face. Faces 2 and 3 are irrelevant. */
385+
class ColinearTetrahedron : public Polytope {
386+
public:
387+
ColinearTetrahedron() : Polytope() {
388+
const ccd_real_t delta = constants<ccd_real_t>::eps() / 100;
389+
v().resize(4);
390+
e().resize(6);
391+
f().resize(4);
392+
auto AddTetrahedronVertex = [this](ccd_real_t x, ccd_real_t y,
393+
ccd_real_t z) {
394+
return ccdPtAddVertexCoords(&this->polytope(), x, y, z);
395+
};
396+
v()[0] = AddTetrahedronVertex(0.5, -0.5 / std::sqrt(3), -1);
397+
v()[1] = AddTetrahedronVertex(-0.5, -0.5 / std::sqrt(3), -1);
398+
v()[2] = AddTetrahedronVertex(0, 1 / std::sqrt(3), -1);
399+
// This point should lie *slightly* above the edge connecting v0 and v1.
400+
v()[3] = AddTetrahedronVertex(0, -0.5 / std::sqrt(3), -1 + delta);
401+
402+
e()[0] = ccdPtAddEdge(&polytope(), &v(0), &v(1));
403+
e()[1] = ccdPtAddEdge(&polytope(), &v(1), &v(2));
404+
e()[2] = ccdPtAddEdge(&polytope(), &v(2), &v(0));
405+
e()[3] = ccdPtAddEdge(&polytope(), &v(0), &v(3));
406+
e()[4] = ccdPtAddEdge(&polytope(), &v(1), &v(3));
407+
e()[5] = ccdPtAddEdge(&polytope(), &v(2), &v(3));
408+
f()[0] = ccdPtAddFace(&polytope(), &e(0), &e(1), &e(2));
409+
f()[1] = ccdPtAddFace(&polytope(), &e(0), &e(3), &e(4));
410+
f()[2] = ccdPtAddFace(&polytope(), &e(1), &e(4), &e(5));
411+
f()[3] = ccdPtAddFace(&polytope(), &e(3), &e(5), &e(2));
412+
}
413+
};
414+
415+
// Tests against a polytope with a face where two edges are colinear.
416+
GTEST_TEST(FCL_GJK_EPA, isOutsidePolytopeFace_DegenerateFace_Colinear) {
417+
::testing::FLAGS_gtest_death_test_style = "threadsafe";
418+
ColinearTetrahedron p;
419+
420+
// This test point should pass w.r.t. the big face.
421+
ccd_vec3_t pt{{0, 0, -10}};
422+
EXPECT_TRUE(libccd_extension::isOutsidePolytopeFace(&p.polytope(), &p.f(0),
423+
&pt));
424+
// Face 1, however, is definitely colinear.
425+
// NOTE: For platform compatibility, the assertion message is pared down to
426+
// the simplest component: the actual function call in the assertion.
427+
ASSERT_DEATH(
428+
libccd_extension::isOutsidePolytopeFace(&p.polytope(), &p.f(1), &pt),
429+
".*!triangle_area_is_zero.*");
430+
}
431+
#endif
432+
433+
296434
// Construct a polytope with the following shape, namely an equilateral triangle
297435
// on the top, and an equilateral triangle of the same size, but rotate by 60
298436
// degrees on the bottom. We will then connect the vertices of the equilateral

0 commit comments

Comments
 (0)