Skip to content

Commit ef223df

Browse files
authored
Fix face normal pointing outward (#336)
* return the normal vector if we found a valid witness point that is definitely on one side of the hyperplane. * Fix the problem that the projection to the origin is mistaken for the projection to the plane. * add include array * Address Sherm's comments. * Address Sean's comments. * Address Sean's comments. * Address Sean's comment. * linting.
1 parent f15ffc2 commit ef223df

File tree

2 files changed

+152
-64
lines changed

2 files changed

+152
-64
lines changed

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

Lines changed: 36 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -860,6 +860,8 @@ static ccd_vec3_t faceNormalPointingOutward(const ccd_pt_t* polytope,
860860
// this corner case.
861861
ccdVec3Cross(&dir, &e1, &e2);
862862
const ccd_real_t dir_norm = std::sqrt(ccdVec3Len2(&dir));
863+
ccd_vec3_t unit_dir = dir;
864+
ccdVec3Scale(&unit_dir, 1.0 / dir_norm);
863865
// The winding of the triangle is *not* guaranteed. The normal `n = e₁ × e₂`
864866
// may point inside or outside. We rely on the fact that the origin lies
865867
// within the polytope to resolve this ambiguity. A vector from the origin to
@@ -879,44 +881,55 @@ static ccd_vec3_t faceNormalPointingOutward(const ccd_pt_t* polytope,
879881
// seems large, the fall through case of comparing the maximum distance will
880882
// always guarantee correctness.
881883
const ccd_real_t dist_tol = 0.01;
882-
ccd_real_t tol = dist_tol * dir_norm;
883-
ccd_real_t projection = ccdVec3Dot(&dir, &(face->edge[0]->vertex[0]->v.v));
884-
if (projection < -tol) {
884+
// origin_distance_to_plane computes the signed distance from the origin to
885+
// the plane nᵀ * (x - v) = 0 coinciding with the triangle, where v is a
886+
// point on the triangle.
887+
const ccd_real_t origin_distance_to_plane =
888+
ccdVec3Dot(&unit_dir, &(face->edge[0]->vertex[0]->v.v));
889+
if (origin_distance_to_plane < -dist_tol) {
885890
// Origin is more than `dist_tol` away from the plane, but the negative
886891
// value implies that the normal vector is pointing in the wrong direction;
887892
// flip it.
888893
ccdVec3Scale(&dir, ccd_real_t(-1));
889-
} else if (projection >= -tol && projection <= tol) {
894+
} else if (-dist_tol <= origin_distance_to_plane &&
895+
origin_distance_to_plane <= dist_tol) {
890896
// The origin is close to the plane of the face. Pick another vertex to test
891897
// the normal direction.
892-
ccd_real_t max_projection = -CCD_REAL_MAX;
893-
ccd_real_t min_projection = CCD_REAL_MAX;
898+
ccd_real_t max_distance_to_plane = -CCD_REAL_MAX;
899+
ccd_real_t min_distance_to_plane = CCD_REAL_MAX;
894900
ccd_pt_vertex_t* v;
895-
// If the magnitude of the projection is larger than tolerance, then it
896-
// means one of the vertices is at least 1cm away from the plane coinciding
897-
// with the face.
901+
// If the magnitude of the distance_to_plane is larger than dist_tol,
902+
// then it means one of the vertices is at least `dist_tol` away from the
903+
// plane coinciding with the face.
898904
ccdListForEachEntry(&polytope->vertices, v, ccd_pt_vertex_t, list) {
899-
projection = ccdVec3Dot(&dir, &(v->v.v));
900-
if (projection > tol) {
905+
// distance_to_plane is the signed distance from the
906+
// vertex v->v.v to the face, i.e., distance_to_plane = nᵀ *
907+
// (v->v.v - face_point). Note that origin_distance_to_plane = nᵀ *
908+
// face_point.
909+
const ccd_real_t distance_to_plane =
910+
ccdVec3Dot(&unit_dir, &(v->v.v)) - origin_distance_to_plane;
911+
if (distance_to_plane > dist_tol) {
901912
// The vertex is at least dist_tol away from the face plane, on the same
902913
// direction of `dir`. So we flip dir to point it outward from the
903914
// polytope.
904915
ccdVec3Scale(&dir, ccd_real_t(-1));
905-
break;
906-
} else if (projection < -tol) {
907-
// The vertex is at least 1cm away from the face plane, on the opposite
908-
// direction of `dir`. So `dir` points outward already.
909-
break;
916+
return dir;
917+
} else if (distance_to_plane < -dist_tol) {
918+
// The vertex is at least `dist_tol` away from the face plane, on the
919+
// opposite direction of `dir`. So `dir` points outward already.
920+
return dir;
910921
} else {
911-
max_projection = std::max(max_projection, projection);
912-
min_projection = std::min(min_projection, projection);
922+
max_distance_to_plane =
923+
std::max(max_distance_to_plane, distance_to_plane);
924+
min_distance_to_plane =
925+
std::min(min_distance_to_plane, distance_to_plane);
913926
}
914927
}
915-
// If max_projection > |min_projection|, it means that the vertices that are
916-
// on the positive side of the plane, has a larger maximal distance than the
917-
// vertices on the negative side of the plane. Thus we regard that `dir`
918-
// points into the polytope. Hence we flip `dir`.
919-
if (max_projection > std::abs(min_projection)) {
928+
// If max_distance_to_plane > |min_distance_to_plane|, it means that the
929+
// vertices that are on the positive side of the plane, has a larger maximal
930+
// distance than the vertices on the negative side of the plane. Thus we
931+
// regard that `dir` points into the polytope. Hence we flip `dir`.
932+
if (max_distance_to_plane > std::abs(min_distance_to_plane)) {
920933
ccdVec3Scale(&dir, ccd_real_t(-1));
921934
}
922935
}

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

Lines changed: 116 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141

4242
#include "fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h"
4343

44+
#include <array>
4445
#include <memory>
4546

4647
#include <gtest/gtest.h>
@@ -92,6 +93,53 @@ class Polytope {
9293
ccd_pt_t* polytope_;
9394
};
9495

96+
/**
97+
* A tetrahedron with some specific ordering on its edges, and faces.
98+
* The user should notice that due to the specific order of the edges, each face
99+
* has its own orientations. Namely for some faces f, f.e(0).cross(f.e(1))
100+
* points inward to the tetrahedron, for some other faces it points outward.
101+
*/
102+
class Tetrahedron : public Polytope {
103+
public:
104+
Tetrahedron(const std::array<fcl::Vector3<ccd_real_t>, 4>& vertices)
105+
: Polytope() {
106+
v().resize(4);
107+
e().resize(6);
108+
f().resize(4);
109+
for (int i = 0; i < 4; ++i) {
110+
v()[i] = ccdPtAddVertexCoords(&this->polytope(), vertices[i](0),
111+
vertices[i](1), vertices[i](2));
112+
}
113+
e()[0] = ccdPtAddEdge(&polytope(), &v(0), &v(1));
114+
e()[1] = ccdPtAddEdge(&polytope(), &v(1), &v(2));
115+
e()[2] = ccdPtAddEdge(&polytope(), &v(2), &v(0));
116+
e()[3] = ccdPtAddEdge(&polytope(), &v(0), &v(3));
117+
e()[4] = ccdPtAddEdge(&polytope(), &v(1), &v(3));
118+
e()[5] = ccdPtAddEdge(&polytope(), &v(2), &v(3));
119+
f()[0] = ccdPtAddFace(&polytope(), &e(0), &e(1), &e(2));
120+
f()[1] = ccdPtAddFace(&polytope(), &e(0), &e(3), &e(4));
121+
f()[2] = ccdPtAddFace(&polytope(), &e(1), &e(4), &e(5));
122+
f()[3] = ccdPtAddFace(&polytope(), &e(3), &e(5), &e(2));
123+
}
124+
};
125+
126+
std::array<fcl::Vector3<ccd_real_t>, 4> EquilateralTetrahedronVertices(
127+
ccd_real_t bottom_center_x, ccd_real_t bottom_center_y,
128+
ccd_real_t bottom_center_z, ccd_real_t edge_length) {
129+
std::array<fcl::Vector3<ccd_real_t>, 4> vertices;
130+
auto compute_vertex = [bottom_center_x, bottom_center_y, bottom_center_z,
131+
edge_length](ccd_real_t x, ccd_real_t y, ccd_real_t z,
132+
fcl::Vector3<ccd_real_t>* vertex) {
133+
*vertex << x * edge_length + bottom_center_x,
134+
y * edge_length + bottom_center_y, z * edge_length + bottom_center_z;
135+
};
136+
compute_vertex(0.5, -0.5 / std::sqrt(3), 0, &vertices[0]);
137+
compute_vertex(-0.5, -0.5 / std::sqrt(3), 0, &vertices[1]);
138+
compute_vertex(0, 1 / std::sqrt(3), 0, &vertices[2]);
139+
compute_vertex(0, 0, std::sqrt(2.0 / 3.0), &vertices[3]);
140+
return vertices;
141+
}
142+
95143
/**
96144
Simple equilateral tetrahedron.
97145
@@ -112,53 +160,30 @@ exercise the functionality for computing an outward normal.
112160
113161
All property accessors are *mutable*.
114162
*/
115-
class EquilateralTetrahedron : public Polytope {
163+
class EquilateralTetrahedron : public Tetrahedron {
116164
public:
117165
EquilateralTetrahedron(ccd_real_t bottom_center_x = 0,
118166
ccd_real_t bottom_center_y = 0,
119167
ccd_real_t bottom_center_z = 0,
120168
ccd_real_t edge_length = 1)
121-
: Polytope() {
122-
v().resize(4);
123-
e().resize(6);
124-
f().resize(4);
125-
auto AddTetrahedronVertex = [bottom_center_x, bottom_center_y,
126-
bottom_center_z, edge_length, this](
127-
ccd_real_t x, ccd_real_t y, ccd_real_t z) {
128-
return ccdPtAddVertexCoords(
129-
&this->polytope(), x * edge_length + bottom_center_x,
130-
y * edge_length + bottom_center_y, z * edge_length + bottom_center_z);
131-
};
132-
v()[0] = AddTetrahedronVertex(0.5, -0.5 / std::sqrt(3), 0);
133-
v()[1] = AddTetrahedronVertex(-0.5, -0.5 / std::sqrt(3), 0);
134-
v()[2] = AddTetrahedronVertex(0, 1 / std::sqrt(3), 0);
135-
v()[3] = AddTetrahedronVertex(0, 0, std::sqrt(2.0 / 3.0));
136-
e()[0] = ccdPtAddEdge(&polytope(), &v(0), &v(1));
137-
e()[1] = ccdPtAddEdge(&polytope(), &v(1), &v(2));
138-
e()[2] = ccdPtAddEdge(&polytope(), &v(2), &v(0));
139-
e()[3] = ccdPtAddEdge(&polytope(), &v(0), &v(3));
140-
e()[4] = ccdPtAddEdge(&polytope(), &v(1), &v(3));
141-
e()[5] = ccdPtAddEdge(&polytope(), &v(2), &v(3));
142-
f()[0] = ccdPtAddFace(&polytope(), &e(0), &e(1), &e(2));
143-
f()[1] = ccdPtAddFace(&polytope(), &e(0), &e(3), &e(4));
144-
f()[2] = ccdPtAddFace(&polytope(), &e(1), &e(4), &e(5));
145-
f()[3] = ccdPtAddFace(&polytope(), &e(3), &e(5), &e(2));
146-
}
169+
: Tetrahedron(EquilateralTetrahedronVertices(
170+
bottom_center_x, bottom_center_y, bottom_center_z, edge_length)) {}
147171
};
148172

173+
void CheckTetrahedronFaceNormal(const Tetrahedron& p) {
174+
for (int i = 0; i < 4; ++i) {
175+
const ccd_vec3_t n =
176+
libccd_extension::faceNormalPointingOutward(&p.polytope(), &p.f(i));
177+
for (int j = 0; j < 4; ++j) {
178+
EXPECT_LE(ccdVec3Dot(&n, &p.v(j).v.v),
179+
ccdVec3Dot(&n, &p.f(i).edge[0]->vertex[0]->v.v) +
180+
constants<ccd_real_t>::eps_34());
181+
}
182+
}
183+
}
184+
149185
GTEST_TEST(FCL_GJK_EPA, faceNormalPointingOutward) {
150186
// Construct a equilateral tetrahedron, compute the normal on each face.
151-
auto CheckTetrahedronFaceNormal = [](const EquilateralTetrahedron& p) {
152-
for (int i = 0; i < 4; ++i) {
153-
const ccd_vec3_t n =
154-
libccd_extension::faceNormalPointingOutward(&p.polytope(), &p.f(i));
155-
for (int j = 0; j < 4; ++j) {
156-
EXPECT_LE(ccdVec3Dot(&n, &p.v(j).v.v),
157-
ccdVec3Dot(&n, &p.f(i).edge[0]->vertex[0]->v.v) +
158-
constants<ccd_real_t>::eps_34());
159-
}
160-
}
161-
};
162187
/*
163188
p1-p4: The tetrahedron is positioned so that the origin is placed on each
164189
face (some requiring flipping, some not)
@@ -198,6 +223,57 @@ GTEST_TEST(FCL_GJK_EPA, faceNormalPointingOutward) {
198223
CheckTetrahedronFaceNormal(p8);
199224
}
200225

226+
GTEST_TEST(FCL_GJK_EPA, faceNormalPointingOutwardOriginNearFace1) {
227+
// Creates a downward pointing tetrahedron which contains the origin. The
228+
// origin is just below the "top" face of this tetrahedron. The remaining
229+
// vertex is far enough away from the top face that it is considered a
230+
// reliable witness to determine the direction of the face's normal. The top
231+
// face is not quite parallel with the z = 0 plane. This test captures the
232+
// failure condition reported in PR 334 -- a logic error made it so the
233+
// reliable witness could be ignored.
234+
const double face0_origin_distance = 0.005;
235+
std::array<fcl::Vector3<ccd_real_t>, 4> vertices;
236+
vertices[0] << 0.5, -0.5, face0_origin_distance;
237+
vertices[1] << 0, 1, face0_origin_distance;
238+
vertices[2] << -0.5, -0.5, face0_origin_distance;
239+
vertices[3] << 0, 0, -1;
240+
Eigen::AngleAxisd rotation(0.05 * M_PI, Eigen::Vector3d::UnitX());
241+
for (int i = 0; i < 4; ++i) {
242+
vertices[i] = rotation * vertices[i];
243+
}
244+
Tetrahedron p(vertices);
245+
{
246+
// Make sure that the e₀ × e₁ points upward.
247+
ccd_vec3_t f0_e0, f0_e1;
248+
ccdVec3Sub2(&f0_e0, &(p.f(0).edge[0]->vertex[1]->v.v),
249+
&(p.f(0).edge[0]->vertex[0]->v.v));
250+
ccdVec3Sub2(&f0_e1, &(p.f(0).edge[1]->vertex[1]->v.v),
251+
&(p.f(0).edge[1]->vertex[0]->v.v));
252+
ccd_vec3_t f0_e0_cross_e1;
253+
ccdVec3Cross(&f0_e0_cross_e1, &f0_e0, &f0_e1);
254+
EXPECT_GE(f0_e0_cross_e1.v[2], 0);
255+
}
256+
CheckTetrahedronFaceNormal(p);
257+
}
258+
259+
GTEST_TEST(FCL_GJK_EPA, faceNormalPointingOutwardOriginNearFace2) {
260+
// Similar to faceNormalPointingOutwardOriginNearFace1 with an important
261+
// difference: the fourth vertex is no longer a reliable witness; it lies
262+
// within the distance tolerance. However, it is unambiguously farther off the
263+
// plane of the top face than those that form the face. This confirms that
264+
// when there are no obviously reliable witness that the most distant point
265+
// serves.
266+
const double face0_origin_distance = 0.005;
267+
std::array<fcl::Vector3<ccd_real_t>, 4> vertices;
268+
vertices[0] << 0.5, -0.5, face0_origin_distance;
269+
vertices[1] << 0, 1, face0_origin_distance;
270+
vertices[2] << -0.5, -0.5, face0_origin_distance;
271+
vertices[3] << 0, 0, -0.001;
272+
273+
Tetrahedron p(vertices);
274+
CheckTetrahedronFaceNormal(p);
275+
}
276+
201277
GTEST_TEST(FCL_GJK_EPA, supportEPADirection) {
202278
auto CheckSupportEPADirection = [](
203279
const ccd_pt_t* polytope, const ccd_pt_el_t* nearest_pt,
@@ -419,8 +495,8 @@ GTEST_TEST(FCL_GJK_EPA, isOutsidePolytopeFace_DegenerateFace_Colinear) {
419495

420496
// This test point should pass w.r.t. the big face.
421497
ccd_vec3_t pt{{0, 0, -10}};
422-
EXPECT_TRUE(libccd_extension::isOutsidePolytopeFace(&p.polytope(), &p.f(0),
423-
&pt));
498+
EXPECT_TRUE(
499+
libccd_extension::isOutsidePolytopeFace(&p.polytope(), &p.f(0), &pt));
424500
// Face 1, however, is definitely colinear.
425501
// NOTE: For platform compatibility, the assertion message is pared down to
426502
// the simplest component: the actual function call in the assertion.
@@ -430,7 +506,6 @@ GTEST_TEST(FCL_GJK_EPA, isOutsidePolytopeFace_DegenerateFace_Colinear) {
430506
}
431507
#endif
432508

433-
434509
// Construct a polytope with the following shape, namely an equilateral triangle
435510
// on the top, and an equilateral triangle of the same size, but rotate by 60
436511
// degrees on the bottom. We will then connect the vertices of the equilateral

0 commit comments

Comments
 (0)