@@ -293,6 +293,144 @@ GTEST_TEST(FCL_GJK_EPA, isOutsidePolytopeFace) {
293
293
CheckPointOutsidePolytopeFace (0 , 0 , 0 , 3 , expect_inside);
294
294
}
295
295
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
+
296
434
// Construct a polytope with the following shape, namely an equilateral triangle
297
435
// on the top, and an equilateral triangle of the same size, but rotate by 60
298
436
// degrees on the bottom. We will then connect the vertices of the equilateral
0 commit comments