37 #ifndef HPP_FCL_TRAVERSAL_NODE_HFIELD_SHAPE_H
38 #define HPP_FCL_TRAVERSAL_NODE_HFIELD_SHAPE_H
60 template <
typename BV>
61 Convex<Quadrilateral> buildConvexQuadrilateral(
const HFNode<BV>& node,
62 const HeightField<BV>& model) {
63 const MatrixXf& heights = model.getHeights();
64 const VecXf& x_grid = model.getXGrid();
65 const VecXf& y_grid = model.getYGrid();
67 const FCL_REAL min_height = model.getMinHeight();
69 const FCL_REAL x0 = x_grid[node.x_id], x1 = x_grid[node.x_id + 1],
70 y0 = y_grid[node.y_id], y1 = y_grid[node.y_id + 1];
71 const Eigen::Block<const MatrixXf, 2, 2> cell =
72 heights.block<2, 2>(node.y_id, node.x_id);
74 assert(cell.maxCoeff() > min_height &&
75 "max_height is lower than min_height");
78 std::shared_ptr<std::vector<Vec3f>> pts(
new std::vector<Vec3f>({
79 Vec3f(x0, y0, min_height),
80 Vec3f(x0, y1, min_height),
81 Vec3f(x1, y1, min_height),
82 Vec3f(x1, y0, min_height),
83 Vec3f(x0, y0, cell(0, 0)),
84 Vec3f(x0, y1, cell(1, 0)),
85 Vec3f(x1, y1, cell(1, 1)),
86 Vec3f(x1, y0, cell(0, 1)),
89 std::shared_ptr<std::vector<Quadrilateral>> polygons(
90 new std::vector<Quadrilateral>(6));
91 (*polygons)[0].set(0, 3, 2, 1);
92 (*polygons)[1].set(0, 1, 5, 4);
93 (*polygons)[2].set(1, 2, 6, 5);
94 (*polygons)[3].set(2, 3, 7, 6);
95 (*polygons)[4].set(3, 0, 4, 7);
96 (*polygons)[5].set(4, 5, 6, 7);
98 return Convex<Quadrilateral>(pts,
105 enum class FaceOrientationConvexPart1 {
113 enum class FaceOrientationConvexPart2 {
121 template <
typename BV>
122 void buildConvexTriangles(
const HFNode<BV>& node,
const HeightField<BV>& model,
123 Convex<Triangle>& convex1,
int& convex1_active_faces,
124 Convex<Triangle>& convex2,
125 int& convex2_active_faces) {
126 const MatrixXf& heights = model.getHeights();
127 const VecXf& x_grid = model.getXGrid();
128 const VecXf& y_grid = model.getYGrid();
130 const FCL_REAL min_height = model.getMinHeight();
132 const FCL_REAL x0 = x_grid[node.x_id], x1 = x_grid[node.x_id + 1],
133 y0 = y_grid[node.y_id], y1 = y_grid[node.y_id + 1];
134 const FCL_REAL max_height = node.max_height;
135 const Eigen::Block<const MatrixXf, 2, 2> cell =
136 heights.block<2, 2>(node.y_id, node.x_id);
138 const int contact_active_faces = node.contact_active_faces;
139 convex1_active_faces = 0;
140 convex2_active_faces = 0;
144 if (contact_active_faces & FaceOrientation::TOP) {
145 convex1_active_faces |= int(details::FaceOrientationConvexPart1::TOP);
146 convex2_active_faces |= int(details::FaceOrientationConvexPart2::TOP);
149 if (contact_active_faces & FaceOrientation::BOTTOM) {
150 convex1_active_faces |= int(details::FaceOrientationConvexPart1::BOTTOM);
151 convex2_active_faces |= int(details::FaceOrientationConvexPart2::BOTTOM);
155 if (contact_active_faces & FaceOrientation::WEST) {
156 convex1_active_faces |= int(details::FaceOrientationConvexPart1::WEST);
159 if (contact_active_faces & FaceOrientation::NORTH) {
160 convex1_active_faces |= int(details::FaceOrientationConvexPart1::NORTH);
164 if (contact_active_faces & FaceOrientation::EAST) {
165 convex2_active_faces |= int(details::FaceOrientationConvexPart2::EAST);
168 if (contact_active_faces & FaceOrientation::SOUTH) {
169 convex2_active_faces |= int(details::FaceOrientationConvexPart2::SOUTH);
172 assert(max_height > min_height &&
173 "max_height is lower than min_height");
178 std::shared_ptr<std::vector<Vec3f>> pts(
new std::vector<Vec3f>({
179 Vec3f(x0, y0, min_height),
180 Vec3f(x0, y1, min_height),
181 Vec3f(x1, y0, min_height),
182 Vec3f(x0, y0, cell(0, 0)),
183 Vec3f(x0, y1, cell(1, 0)),
184 Vec3f(x1, y0, cell(0, 1)),
187 std::shared_ptr<std::vector<Triangle>> triangles(
188 new std::vector<Triangle>(8));
189 (*triangles)[0].set(0, 2, 1);
190 (*triangles)[1].set(3, 4, 5);
191 (*triangles)[2].set(0, 1, 3);
192 (*triangles)[3].set(3, 1, 4);
193 (*triangles)[4].set(1, 2, 5);
194 (*triangles)[5].set(1, 5, 4);
195 (*triangles)[6].set(0, 5, 2);
196 (*triangles)[7].set(5, 0, 3);
206 std::shared_ptr<std::vector<Vec3f>> pts(
new std::vector<Vec3f>({
207 Vec3f(x0, y1, min_height),
208 Vec3f(x1, y1, min_height),
209 Vec3f(x1, y0, min_height),
210 Vec3f(x0, y1, cell(1, 0)),
211 Vec3f(x1, y1, cell(1, 1)),
212 Vec3f(x1, y0, cell(0, 1)),
215 std::shared_ptr<std::vector<Triangle>> triangles(
216 new std::vector<Triangle>(8));
217 (*triangles)[0].set(2, 1, 0);
218 (*triangles)[1].set(3, 4, 5);
219 (*triangles)[2].set(0, 1, 3);
220 (*triangles)[3].set(3, 1, 4);
221 (*triangles)[4].set(0, 5, 2);
222 (*triangles)[5].set(0, 3, 5);
223 (*triangles)[6].set(1, 2, 5);
224 (*triangles)[7].set(4, 1, 2);
236 const Project::ProjectResult result =
237 Project::projectTriangle(pointA, pointB, pointC, point);
238 Vec3f res = result.parameterization[0] * pointA +
239 result.parameterization[1] * pointB +
240 result.parameterization[2] * pointC;
245 inline Vec3f projectTetrahedra(
const Vec3f& pointA,
const Vec3f& pointB,
247 const Vec3f& point) {
248 const Project::ProjectResult result =
249 Project::projectTetrahedra(pointA, pointB, pointC, pointD, point);
250 Vec3f res = result.parameterization[0] * pointA +
251 result.parameterization[1] * pointB +
252 result.parameterization[2] * pointC +
253 result.parameterization[3] * pointD;
258 inline Vec3f computeTriangleNormal(
const Triangle& triangle,
259 const std::vector<Vec3f>& points) {
260 const Vec3f pointA = points[triangle[0]];
261 const Vec3f pointB = points[triangle[1]];
262 const Vec3f pointC = points[triangle[2]];
264 const Vec3f normal = (pointB - pointA).cross(pointC - pointA).normalized();
265 assert(!normal.array().isNaN().any() &&
"normal is ill-defined");
270 inline Vec3f projectPointOnTriangle(
const Vec3f& contact_point,
271 const Triangle& triangle,
272 const std::vector<Vec3f>& points) {
273 const Vec3f pointA = points[triangle[0]];
274 const Vec3f pointB = points[triangle[1]];
275 const Vec3f pointC = points[triangle[2]];
277 const Vec3f contact_point_projected =
278 projectTriangle(pointA, pointB, pointC, contact_point);
280 return contact_point_projected;
283 inline FCL_REAL distanceContactPointToTriangle(
284 const Vec3f& contact_point,
const Triangle& triangle,
285 const std::vector<Vec3f>& points) {
286 const Vec3f contact_point_projected =
287 projectPointOnTriangle(contact_point, triangle, points);
288 return (contact_point_projected - contact_point).norm();
291 inline FCL_REAL distanceContactPointToFace(
const size_t face_id,
292 const Vec3f& contact_point,
293 const Convex<Triangle>& convex,
294 size_t& closest_face_id) {
295 assert((face_id >= 0 && face_id < 8) &&
"face_id should be in [0;7]");
297 const std::vector<Vec3f>& points = *(convex.points);
299 const Triangle& triangle = (*(convex.polygons))[face_id];
300 closest_face_id = face_id;
301 return distanceContactPointToTriangle(contact_point, triangle, points);
303 const Triangle& triangle1 = (*(convex.polygons))[face_id];
304 const FCL_REAL distance_to_triangle1 =
305 distanceContactPointToTriangle(contact_point, triangle1, points);
307 const Triangle& triangle2 = (*(convex.polygons))[face_id + 1];
308 const FCL_REAL distance_to_triangle2 =
309 distanceContactPointToTriangle(contact_point, triangle2, points);
311 if (distance_to_triangle1 > distance_to_triangle2) {
312 closest_face_id = face_id + 1;
313 return distance_to_triangle2;
315 closest_face_id = face_id;
316 return distance_to_triangle1;
321 template <
typename Polygone,
typename Shape>
322 bool binCorrection(
const Convex<Polygone>& convex,
323 const int convex_active_faces,
const Shape& shape,
326 Vec3f& face_normal,
const bool is_collision) {
328 const std::vector<Vec3f>& points = *(convex.points);
330 bool hfield_witness_is_on_bin_side =
true;
335 std::vector<size_t> active_faces;
336 active_faces.reserve(5);
337 active_faces.push_back(0);
338 active_faces.push_back(1);
340 if (convex_active_faces & 2) active_faces.push_back(2);
341 if (convex_active_faces & 4) active_faces.push_back(4);
342 if (convex_active_faces & 8) active_faces.push_back(6);
344 Triangle face_triangle;
345 FCL_REAL shortest_distance_to_face = (std::numeric_limits<FCL_REAL>::max)();
346 face_normal = normal;
347 for (
const size_t active_face : active_faces) {
348 size_t closest_face_id;
349 const FCL_REAL distance_to_face = distanceContactPointToFace(
350 active_face, contact_1, convex, closest_face_id);
352 const bool contact_point_is_on_face = distance_to_face <= prec;
353 if (contact_point_is_on_face) {
354 hfield_witness_is_on_bin_side =
false;
355 face_triangle = (*(convex.polygons))[closest_face_id];
356 shortest_distance_to_face = distance_to_face;
358 }
else if (distance_to_face < shortest_distance_to_face) {
359 face_triangle = (*(convex.polygons))[closest_face_id];
360 shortest_distance_to_face = distance_to_face;
366 if (!face_triangle.isValid())
370 const Vec3f face_pointA = points[face_triangle[0]];
371 face_normal = computeTriangleNormal(face_triangle, points);
377 const Vec3f _support = getSupport<details::SupportOptions::WithSweptSphere>(
378 &shape, -shape_pose.rotation().transpose() * face_normal, hint);
379 const Vec3f support =
380 shape_pose.rotation() * _support + shape_pose.translation();
383 const FCL_REAL offset_plane = face_normal.dot(face_pointA);
384 const Plane projection_plane(face_normal, offset_plane);
385 const FCL_REAL distance_support_projection_plane =
386 projection_plane.signedDistance(support);
388 const Vec3f projected_support =
389 support - distance_support_projection_plane * face_normal;
393 projectPointOnTriangle(projected_support, face_triangle, points);
394 contact_2 = contact_1 + distance_support_projection_plane * face_normal;
395 normal = face_normal;
396 distance = -std::fabs(distance_support_projection_plane);
399 return hfield_witness_is_on_bin_side;
402 template <
typename Polygone,
typename Shape,
int Options>
403 bool shapeDistance(
const GJKSolver* nsolver,
const CollisionRequest& request,
404 const Convex<Polygone>& convex1,
405 const int convex1_active_faces,
406 const Convex<Polygone>& convex2,
407 const int convex2_active_faces,
const Transform3f& tf1,
408 const Shape& shape,
const Transform3f& tf2,
410 Vec3f& normal_top,
bool& hfield_witness_is_on_bin_side) {
411 enum { RTIsIdentity = Options & RelativeTransformationIsIdentity };
413 const Transform3f Id;
419 const bool compute_penetration =
true;
420 Vec3f contact1_1, contact1_2, contact2_1, contact2_2;
421 Vec3f normal1, normal1_top, normal2, normal2_top;
425 distance1 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
426 &convex1, Id, &shape, tf2, nsolver, compute_penetration, contact1_1,
427 contact1_2, normal1);
429 distance1 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
430 &convex1, tf1, &shape, tf2, nsolver, compute_penetration, contact1_1,
431 contact1_2, normal1);
433 bool collision1 = (distance1 - request.security_margin <=
434 request.collision_distance_threshold);
436 bool hfield_witness_is_on_bin_side1 =
437 binCorrection(convex1, convex1_active_faces, shape, tf2, distance1,
438 contact1_1, contact1_2, normal1, normal1_top, collision1);
441 distance2 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
442 &convex2, Id, &shape, tf2, nsolver, compute_penetration, contact2_1,
443 contact2_2, normal2);
445 distance2 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
446 &convex2, tf1, &shape, tf2, nsolver, compute_penetration, contact2_1,
447 contact2_2, normal2);
449 bool collision2 = (distance2 - request.security_margin <=
450 request.collision_distance_threshold);
452 bool hfield_witness_is_on_bin_side2 =
453 binCorrection(convex2, convex2_active_faces, shape, tf2, distance2,
454 contact2_1, contact2_2, normal2, normal2_top, collision2);
456 if (collision1 && collision2) {
457 if (distance1 > distance2)
463 normal_top = normal2_top;
464 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side2;
470 normal_top = normal1_top;
471 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side1;
474 }
else if (collision1) {
479 normal_top = normal1_top;
480 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side1;
482 }
else if (collision2) {
487 normal_top = normal2_top;
488 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side2;
492 if (distance1 > distance2)
498 normal_top = normal2_top;
499 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side2;
505 normal_top = normal1_top;
506 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side1;
514 template <
typename BV,
typename S,
515 int _Options = RelativeTransformationIsIdentity>
516 class HeightFieldShapeCollisionTraversalNode
517 :
public CollisionTraversalNodeBase {
519 typedef CollisionTraversalNodeBase Base;
520 typedef Eigen::Array<FCL_REAL, 1, 2> Array2d;
524 RTIsIdentity = _Options & RelativeTransformationIsIdentity
527 HeightFieldShapeCollisionTraversalNode(
const CollisionRequest& request)
528 : CollisionTraversalNodeBase(request) {
534 query_time_seconds = 0.0;
541 bool isFirstNodeLeaf(
unsigned int b)
const {
542 return model1->getBV(b).isLeaf();
546 int getFirstLeftChild(
unsigned int b)
const {
547 return static_cast<int>(model1->getBV(b).leftChild());
551 int getFirstRightChild(
unsigned int b)
const {
552 return static_cast<int>(model1->getBV(b).rightChild());
560 bool BVDisjoints(
unsigned int b1,
unsigned int ,
561 FCL_REAL& sqrDistLowerBound)
const {
562 if (this->enable_statistics) this->num_bv_tests++;
566 assert(
false &&
"must never happened");
567 disjoint = !this->model1->getBV(b1).bv.overlap(
568 this->model2_bv, this->request, sqrDistLowerBound);
570 disjoint = !
overlap(this->tf1.getRotation(), this->tf1.getTranslation(),
571 this->model1->getBV(b1).bv, this->model2_bv,
572 this->request, sqrDistLowerBound);
579 assert(!disjoint || sqrDistLowerBound > 0);
584 void leafCollides(
unsigned int b1,
unsigned int ,
585 FCL_REAL& sqrDistLowerBound)
const {
587 if (this->enable_statistics) this->num_leaf_tests++;
588 const HFNode<BV>& node = this->model1->getBV(b1);
597 typedef Convex<Triangle> ConvexTriangle;
598 ConvexTriangle convex1, convex2;
599 int convex1_active_faces, convex2_active_faces;
601 details::buildConvexTriangles(node, *this->model1, convex1,
602 convex1_active_faces, convex2,
603 convex2_active_faces);
607 convex1.computeLocalAABB();
608 convex2.computeLocalAABB();
613 Vec3f c1, c2, normal, normal_face;
614 bool hfield_witness_is_on_bin_side;
616 bool collision = details::shapeDistance<Triangle, S, Options>(
617 nsolver, this->request, convex1, convex1_active_faces, convex2,
618 convex2_active_faces, this->tf1, *(this->model2), this->tf2,
distance,
619 c1, c2, normal, normal_face, hfield_witness_is_on_bin_side);
622 if (distToCollision <= this->request.collision_distance_threshold) {
623 sqrDistLowerBound = 0;
624 if (this->result->numContacts() < this->request.num_max_contacts) {
625 if (normal_face.isApprox(normal) &&
626 (collision || !hfield_witness_is_on_bin_side)) {
627 this->result->addContact(Contact(this->model1, this->model2, (
int)b1,
630 assert(this->result->isCollision());
634 sqrDistLowerBound = distToCollision * distToCollision;
639 distToCollision, c1, c2, normal);
641 assert(this->result->isCollision() || sqrDistLowerBound > 0);
644 const GJKSolver* nsolver;
646 const HeightField<BV>* model1;
650 mutable int num_bv_tests;
651 mutable int num_leaf_tests;
652 mutable FCL_REAL query_time_seconds;
662 template <
typename BV,
typename S,
663 int _Options = RelativeTransformationIsIdentity>
664 class HeightFieldShapeDistanceTraversalNode :
public DistanceTraversalNodeBase {
666 typedef DistanceTraversalNodeBase Base;
670 RTIsIdentity = _Options & RelativeTransformationIsIdentity
673 HeightFieldShapeDistanceTraversalNode() : DistanceTraversalNodeBase() {
678 query_time_seconds = 0.0;
686 bool isFirstNodeLeaf(
unsigned int b)
const {
687 return model1->getBV(b).isLeaf();
691 int getFirstLeftChild(
unsigned int b)
const {
692 return model1->getBV(b).leftChild();
696 int getFirstRightChild(
unsigned int b)
const {
697 return model1->getBV(b).rightChild();
701 FCL_REAL BVDistanceLowerBound(
unsigned int b1,
unsigned int )
const {
702 return model1->getBV(b1).bv.distance(
710 void leafComputeDistance(
unsigned int b1,
unsigned int )
const {
711 if (this->enable_statistics) this->num_leaf_tests++;
713 const BVNode<BV>& node = this->model1->getBV(b1);
715 typedef Convex<Quadrilateral> ConvexQuadrilateral;
716 const ConvexQuadrilateral convex =
717 details::buildConvexQuadrilateral(node, *this->model1);
719 Vec3f p1, p2, normal;
721 internal::ShapeShapeDistance<ConvexQuadrilateral, S>(
722 &convex, this->tf1, this->model2, this->tf2, this->nsolver,
723 this->request.enable_signed_distance, p1, p2, normal);
725 this->result->update(
distance, this->model1, this->model2, b1,
731 if ((c >= this->result->min_distance - abs_err) &&
732 (c * (1 + rel_err) >= this->result->min_distance))
740 const GJKSolver* nsolver;
742 const HeightField<BV>* model1;
746 mutable int num_bv_tests;
747 mutable int num_leaf_tests;
748 mutable FCL_REAL query_time_seconds;
#define HPP_FCL_THROW_PRETTY(message, exception)
Definition: fwd.hh:64
#define HPP_FCL_UNUSED_VARIABLE(var)
Definition: fwd.hh:56
FCL_REAL distance(const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
Approximate distance between two kIOS bounding volumes.
bool overlap(const Matrix3f &R0, const Vec3f &T0, const AABB &b1, const AABB &b2)
Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity.
void updateDistanceLowerBoundFromLeaf(const CollisionRequest &, CollisionResult &res, const FCL_REAL &distance, const Vec3f &p0, const Vec3f &p1, const Vec3f &normal)
Definition: collision_data.h:1186
void updateDistanceLowerBoundFromBV(const CollisionRequest &, CollisionResult &res, const FCL_REAL sqrDistLowerBound)
Definition: collision_data.h:1177
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:67
Eigen::Matrix< FCL_REAL, Eigen::Dynamic, Eigen::Dynamic > MatrixXf
Definition: data_types.h:76
Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 1 > VecXf
Definition: data_types.h:70
@ BoundingVolumeGuess
Definition: data_types.h:85
double FCL_REAL
Definition: data_types.h:66
Main namespace.
Definition: broadphase_bruteforce.h:44
static const int NONE
invalid contact primitive information
Definition: collision_data.h:1088
FaceOrientation
Definition: hfield.h:57