hpp-fcl  3.0.0
HPP fork of FCL -- The Flexible Collision Library
traversal_node_hfield_shape.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021-2024, INRIA.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Open Source Robotics Foundation nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #ifndef HPP_FCL_TRAVERSAL_NODE_HFIELD_SHAPE_H
38 #define HPP_FCL_TRAVERSAL_NODE_HFIELD_SHAPE_H
39 
41 
42 #include <hpp/fcl/collision_data.h>
50 #include <hpp/fcl/hfield.h>
51 #include <hpp/fcl/shape/convex.h>
52 
53 namespace hpp {
54 namespace fcl {
55 
58 
59 namespace details {
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();
66 
67  const FCL_REAL min_height = model.getMinHeight();
68 
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);
73 
74  assert(cell.maxCoeff() > min_height &&
75  "max_height is lower than min_height"); // Check whether the geometry
76  // is degenerated
77 
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)),
87  }));
88 
89  std::shared_ptr<std::vector<Quadrilateral>> polygons(
90  new std::vector<Quadrilateral>(6));
91  (*polygons)[0].set(0, 3, 2, 1); // x+ side
92  (*polygons)[1].set(0, 1, 5, 4); // y- side
93  (*polygons)[2].set(1, 2, 6, 5); // x- side
94  (*polygons)[3].set(2, 3, 7, 6); // y+ side
95  (*polygons)[4].set(3, 0, 4, 7); // z- side
96  (*polygons)[5].set(4, 5, 6, 7); // z+ side
97 
98  return Convex<Quadrilateral>(pts, // points
99  8, // num points
100  polygons,
101  6 // number of polygons
102  );
103 }
104 
105 enum class FaceOrientationConvexPart1 {
106  BOTTOM = 0,
107  TOP = 1,
108  WEST = 2,
109  SOUTH_EAST = 4,
110  NORTH = 8,
111 };
112 
113 enum class FaceOrientationConvexPart2 {
114  BOTTOM = 0,
115  TOP = 1,
116  SOUTH = 2,
117  NORTH_WEST = 4,
118  EAST = 8,
119 };
120 
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();
129 
130  const FCL_REAL min_height = model.getMinHeight();
131 
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);
137 
138  const int contact_active_faces = node.contact_active_faces;
139  convex1_active_faces = 0;
140  convex2_active_faces = 0;
141 
142  typedef HFNodeBase::FaceOrientation FaceOrientation;
143 
144  if (contact_active_faces & FaceOrientation::TOP) {
145  convex1_active_faces |= int(details::FaceOrientationConvexPart1::TOP);
146  convex2_active_faces |= int(details::FaceOrientationConvexPart2::TOP);
147  }
148 
149  if (contact_active_faces & FaceOrientation::BOTTOM) {
150  convex1_active_faces |= int(details::FaceOrientationConvexPart1::BOTTOM);
151  convex2_active_faces |= int(details::FaceOrientationConvexPart2::BOTTOM);
152  }
153 
154  // Specific orientation for Convex1
155  if (contact_active_faces & FaceOrientation::WEST) {
156  convex1_active_faces |= int(details::FaceOrientationConvexPart1::WEST);
157  }
158 
159  if (contact_active_faces & FaceOrientation::NORTH) {
160  convex1_active_faces |= int(details::FaceOrientationConvexPart1::NORTH);
161  }
162 
163  // Specific orientation for Convex2
164  if (contact_active_faces & FaceOrientation::EAST) {
165  convex2_active_faces |= int(details::FaceOrientationConvexPart2::EAST);
166  }
167 
168  if (contact_active_faces & FaceOrientation::SOUTH) {
169  convex2_active_faces |= int(details::FaceOrientationConvexPart2::SOUTH);
170  }
171 
172  assert(max_height > min_height &&
173  "max_height is lower than min_height"); // Check whether the geometry
174  // is degenerated
175  HPP_FCL_UNUSED_VARIABLE(max_height);
176 
177  {
178  std::shared_ptr<std::vector<Vec3f>> pts(new std::vector<Vec3f>({
179  Vec3f(x0, y0, min_height), // A
180  Vec3f(x0, y1, min_height), // B
181  Vec3f(x1, y0, min_height), // C
182  Vec3f(x0, y0, cell(0, 0)), // D
183  Vec3f(x0, y1, cell(1, 0)), // E
184  Vec3f(x1, y0, cell(0, 1)), // F
185  }));
186 
187  std::shared_ptr<std::vector<Triangle>> triangles(
188  new std::vector<Triangle>(8));
189  (*triangles)[0].set(0, 2, 1); // bottom
190  (*triangles)[1].set(3, 4, 5); // top
191  (*triangles)[2].set(0, 1, 3); // West 1
192  (*triangles)[3].set(3, 1, 4); // West 2
193  (*triangles)[4].set(1, 2, 5); // South-East 1
194  (*triangles)[5].set(1, 5, 4); // South-East 1
195  (*triangles)[6].set(0, 5, 2); // North 1
196  (*triangles)[7].set(5, 0, 3); // North 2
197 
198  convex1.set(pts, // points
199  6, // num points
200  triangles,
201  8 // number of polygons
202  );
203  }
204 
205  {
206  std::shared_ptr<std::vector<Vec3f>> pts(new std::vector<Vec3f>({
207  Vec3f(x0, y1, min_height), // A
208  Vec3f(x1, y1, min_height), // B
209  Vec3f(x1, y0, min_height), // C
210  Vec3f(x0, y1, cell(1, 0)), // D
211  Vec3f(x1, y1, cell(1, 1)), // E
212  Vec3f(x1, y0, cell(0, 1)), // F
213  }));
214 
215  std::shared_ptr<std::vector<Triangle>> triangles(
216  new std::vector<Triangle>(8));
217  (*triangles)[0].set(2, 1, 0); // bottom
218  (*triangles)[1].set(3, 4, 5); // top
219  (*triangles)[2].set(0, 1, 3); // South 1
220  (*triangles)[3].set(3, 1, 4); // South 2
221  (*triangles)[4].set(0, 5, 2); // North West 1
222  (*triangles)[5].set(0, 3, 5); // North West 2
223  (*triangles)[6].set(1, 2, 5); // East 1
224  (*triangles)[7].set(4, 1, 2); // East 2
225 
226  convex2.set(pts, // points
227  6, // num points
228  triangles,
229  8 // number of polygons
230  );
231  }
232 }
233 
234 inline Vec3f projectTriangle(const Vec3f& pointA, const Vec3f& pointB,
235  const Vec3f& pointC, const Vec3f& point) {
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;
241 
242  return res;
243 }
244 
245 inline Vec3f projectTetrahedra(const Vec3f& pointA, const Vec3f& pointB,
246  const Vec3f& pointC, const Vec3f& pointD,
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;
254 
255  return res;
256 }
257 
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]];
263 
264  const Vec3f normal = (pointB - pointA).cross(pointC - pointA).normalized();
265  assert(!normal.array().isNaN().any() && "normal is ill-defined");
266 
267  return normal;
268 }
269 
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]];
276 
277  const Vec3f contact_point_projected =
278  projectTriangle(pointA, pointB, pointC, contact_point);
279 
280  return contact_point_projected;
281 }
282 
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();
289 }
290 
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]");
296 
297  const std::vector<Vec3f>& points = *(convex.points);
298  if (face_id <= 1) {
299  const Triangle& triangle = (*(convex.polygons))[face_id];
300  closest_face_id = face_id;
301  return distanceContactPointToTriangle(contact_point, triangle, points);
302  } else {
303  const Triangle& triangle1 = (*(convex.polygons))[face_id];
304  const FCL_REAL distance_to_triangle1 =
305  distanceContactPointToTriangle(contact_point, triangle1, points);
306 
307  const Triangle& triangle2 = (*(convex.polygons))[face_id + 1];
308  const FCL_REAL distance_to_triangle2 =
309  distanceContactPointToTriangle(contact_point, triangle2, points);
310 
311  if (distance_to_triangle1 > distance_to_triangle2) {
312  closest_face_id = face_id + 1;
313  return distance_to_triangle2;
314  } else {
315  closest_face_id = face_id;
316  return distance_to_triangle1;
317  }
318  }
319 }
320 
321 template <typename Polygone, typename Shape>
322 bool binCorrection(const Convex<Polygone>& convex,
323  const int convex_active_faces, const Shape& shape,
324  const Transform3f& shape_pose, FCL_REAL& distance,
325  Vec3f& contact_1, Vec3f& contact_2, Vec3f& normal,
326  Vec3f& face_normal, const bool is_collision) {
327  const FCL_REAL prec = 1e-12;
328  const std::vector<Vec3f>& points = *(convex.points);
329 
330  bool hfield_witness_is_on_bin_side = true;
331 
332  // int closest_face_id_bottom_face = -1;
333  // int closest_face_id_top_face = -1;
334 
335  std::vector<size_t> active_faces;
336  active_faces.reserve(5);
337  active_faces.push_back(0);
338  active_faces.push_back(1);
339 
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);
343 
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);
351 
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;
357  break;
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;
361  }
362  }
363 
364  // We correct only if there is a collision with the bin
365  if (is_collision) {
366  if (!face_triangle.isValid())
367  HPP_FCL_THROW_PRETTY("face_triangle is not initialized",
368  std::logic_error);
369 
370  const Vec3f face_pointA = points[face_triangle[0]];
371  face_normal = computeTriangleNormal(face_triangle, points);
372 
373  int hint = 0;
374  // Since we compute the support manually, we need to take into account the
375  // sphere swept radius of the shape.
376  // TODO: take into account the swept-sphere radius of the bin.
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();
381 
382  // Project support into the inclined bin having triangle
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);
387 
388  const Vec3f projected_support =
389  support - distance_support_projection_plane * face_normal;
390 
391  // We need now to project the projected in the triangle shape
392  contact_1 =
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);
397  }
398 
399  return hfield_witness_is_on_bin_side;
400 }
401 
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,
409  FCL_REAL& distance, Vec3f& c1, Vec3f& c2, Vec3f& normal,
410  Vec3f& normal_top, bool& hfield_witness_is_on_bin_side) {
411  enum { RTIsIdentity = Options & RelativeTransformationIsIdentity };
412 
413  const Transform3f Id;
414  // The solver `nsolver` has already been set up by the collision request
415  // `request`. If GJK early stopping is enabled through `request`, it will be
416  // used.
417  // The only thing we need to make sure is that in case of collision, the
418  // penetration information is computed (as we do bins comparison).
419  const bool compute_penetration = true;
420  Vec3f contact1_1, contact1_2, contact2_1, contact2_2;
421  Vec3f normal1, normal1_top, normal2, normal2_top;
422  FCL_REAL distance1, distance2;
423 
424  if (RTIsIdentity) {
425  distance1 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
426  &convex1, Id, &shape, tf2, nsolver, compute_penetration, contact1_1,
427  contact1_2, normal1);
428  } else {
429  distance1 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
430  &convex1, tf1, &shape, tf2, nsolver, compute_penetration, contact1_1,
431  contact1_2, normal1);
432  }
433  bool collision1 = (distance1 - request.security_margin <=
434  request.collision_distance_threshold);
435 
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);
439 
440  if (RTIsIdentity) {
441  distance2 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
442  &convex2, Id, &shape, tf2, nsolver, compute_penetration, contact2_1,
443  contact2_2, normal2);
444  } else {
445  distance2 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
446  &convex2, tf1, &shape, tf2, nsolver, compute_penetration, contact2_1,
447  contact2_2, normal2);
448  }
449  bool collision2 = (distance2 - request.security_margin <=
450  request.collision_distance_threshold);
451 
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);
455 
456  if (collision1 && collision2) {
457  if (distance1 > distance2) // switch values
458  {
459  distance = distance2;
460  c1 = contact2_1;
461  c2 = contact2_2;
462  normal = normal2;
463  normal_top = normal2_top;
464  hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side2;
465  } else {
466  distance = distance1;
467  c1 = contact1_1;
468  c2 = contact1_2;
469  normal = normal1;
470  normal_top = normal1_top;
471  hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side1;
472  }
473  return true;
474  } else if (collision1) {
475  distance = distance1;
476  c1 = contact1_1;
477  c2 = contact1_2;
478  normal = normal1;
479  normal_top = normal1_top;
480  hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side1;
481  return true;
482  } else if (collision2) {
483  distance = distance2;
484  c1 = contact2_1;
485  c2 = contact2_2;
486  normal = normal2;
487  normal_top = normal2_top;
488  hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side2;
489  return true;
490  }
491 
492  if (distance1 > distance2) // switch values
493  {
494  distance = distance2;
495  c1 = contact2_1;
496  c2 = contact2_2;
497  normal = normal2;
498  normal_top = normal2_top;
499  hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side2;
500  } else {
501  distance = distance1;
502  c1 = contact1_1;
503  c2 = contact1_2;
504  normal = normal1;
505  normal_top = normal1_top;
506  hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side1;
507  }
508  return false;
509 }
510 
511 } // namespace details
512 
514 template <typename BV, typename S,
515  int _Options = RelativeTransformationIsIdentity>
516 class HeightFieldShapeCollisionTraversalNode
517  : public CollisionTraversalNodeBase {
518  public:
519  typedef CollisionTraversalNodeBase Base;
520  typedef Eigen::Array<FCL_REAL, 1, 2> Array2d;
521 
522  enum {
523  Options = _Options,
524  RTIsIdentity = _Options & RelativeTransformationIsIdentity
525  };
526 
527  HeightFieldShapeCollisionTraversalNode(const CollisionRequest& request)
528  : CollisionTraversalNodeBase(request) {
529  model1 = NULL;
530  model2 = NULL;
531 
532  num_bv_tests = 0;
533  num_leaf_tests = 0;
534  query_time_seconds = 0.0;
535 
536  nsolver = NULL;
537  count = 0;
538  }
539 
541  bool isFirstNodeLeaf(unsigned int b) const {
542  return model1->getBV(b).isLeaf();
543  }
544 
546  int getFirstLeftChild(unsigned int b) const {
547  return static_cast<int>(model1->getBV(b).leftChild());
548  }
549 
551  int getFirstRightChild(unsigned int b) const {
552  return static_cast<int>(model1->getBV(b).rightChild());
553  }
554 
560  bool BVDisjoints(unsigned int b1, unsigned int /*b2*/,
561  FCL_REAL& sqrDistLowerBound) const {
562  if (this->enable_statistics) this->num_bv_tests++;
563 
564  bool disjoint;
565  if (RTIsIdentity) {
566  assert(false && "must never happened");
567  disjoint = !this->model1->getBV(b1).bv.overlap(
568  this->model2_bv, this->request, sqrDistLowerBound);
569  } else {
570  disjoint = !overlap(this->tf1.getRotation(), this->tf1.getTranslation(),
571  this->model1->getBV(b1).bv, this->model2_bv,
572  this->request, sqrDistLowerBound);
573  }
574 
575  if (disjoint)
576  internal::updateDistanceLowerBoundFromBV(this->request, *this->result,
577  sqrDistLowerBound);
578 
579  assert(!disjoint || sqrDistLowerBound > 0);
580  return disjoint;
581  }
582 
584  void leafCollides(unsigned int b1, unsigned int /*b2*/,
585  FCL_REAL& sqrDistLowerBound) const {
586  count++;
587  if (this->enable_statistics) this->num_leaf_tests++;
588  const HFNode<BV>& node = this->model1->getBV(b1);
589 
590  // Split quadrilateral primitives into two convex shapes corresponding to
591  // polyhedron with triangular bases. This is essential to keep the convexity
592 
593  // typedef Convex<Quadrilateral> ConvexQuadrilateral;
594  // const ConvexQuadrilateral convex =
595  // details::buildConvexQuadrilateral(node,*this->model1);
596 
597  typedef Convex<Triangle> ConvexTriangle;
598  ConvexTriangle convex1, convex2;
599  int convex1_active_faces, convex2_active_faces;
600  // TODO: inherit from hfield's inflation here
601  details::buildConvexTriangles(node, *this->model1, convex1,
602  convex1_active_faces, convex2,
603  convex2_active_faces);
604 
605  // Compute aabb_local for BoundingVolumeGuess case in the GJK solver
606  if (nsolver->gjk_initial_guess == GJKInitialGuess::BoundingVolumeGuess) {
607  convex1.computeLocalAABB();
608  convex2.computeLocalAABB();
609  }
610 
612  // Vec3f contact_point, normal;
613  Vec3f c1, c2, normal, normal_face;
614  bool hfield_witness_is_on_bin_side;
615 
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);
620 
621  FCL_REAL distToCollision = distance - this->request.security_margin;
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,
628  (int)Contact::NONE, c1, c2, normal,
629  distance));
630  assert(this->result->isCollision());
631  }
632  }
633  } else
634  sqrDistLowerBound = distToCollision * distToCollision;
635 
636  // const Vec3f c1 = contact_point - distance * 0.5 * normal;
637  // const Vec3f c2 = contact_point + distance * 0.5 * normal;
638  internal::updateDistanceLowerBoundFromLeaf(this->request, *this->result,
639  distToCollision, c1, c2, normal);
640 
641  assert(this->result->isCollision() || sqrDistLowerBound > 0);
642  }
643 
644  const GJKSolver* nsolver;
645 
646  const HeightField<BV>* model1;
647  const S* model2;
648  BV model2_bv;
649 
650  mutable int num_bv_tests;
651  mutable int num_leaf_tests;
652  mutable FCL_REAL query_time_seconds;
653  mutable int count;
654 };
655 
657 
660 
662 template <typename BV, typename S,
663  int _Options = RelativeTransformationIsIdentity>
664 class HeightFieldShapeDistanceTraversalNode : public DistanceTraversalNodeBase {
665  public:
666  typedef DistanceTraversalNodeBase Base;
667 
668  enum {
669  Options = _Options,
670  RTIsIdentity = _Options & RelativeTransformationIsIdentity
671  };
672 
673  HeightFieldShapeDistanceTraversalNode() : DistanceTraversalNodeBase() {
674  model1 = NULL;
675  model2 = NULL;
676 
677  num_leaf_tests = 0;
678  query_time_seconds = 0.0;
679 
680  rel_err = 0;
681  abs_err = 0;
682  nsolver = NULL;
683  }
684 
686  bool isFirstNodeLeaf(unsigned int b) const {
687  return model1->getBV(b).isLeaf();
688  }
689 
691  int getFirstLeftChild(unsigned int b) const {
692  return model1->getBV(b).leftChild();
693  }
694 
696  int getFirstRightChild(unsigned int b) const {
697  return model1->getBV(b).rightChild();
698  }
699 
701  FCL_REAL BVDistanceLowerBound(unsigned int b1, unsigned int /*b2*/) const {
702  return model1->getBV(b1).bv.distance(
703  model2_bv); // TODO(jcarpent): tf1 is not taken into account here.
704  }
705 
710  void leafComputeDistance(unsigned int b1, unsigned int /*b2*/) const {
711  if (this->enable_statistics) this->num_leaf_tests++;
712 
713  const BVNode<BV>& node = this->model1->getBV(b1);
714 
715  typedef Convex<Quadrilateral> ConvexQuadrilateral;
716  const ConvexQuadrilateral convex =
717  details::buildConvexQuadrilateral(node, *this->model1);
718 
719  Vec3f p1, p2, normal;
720  const FCL_REAL distance =
721  internal::ShapeShapeDistance<ConvexQuadrilateral, S>(
722  &convex, this->tf1, this->model2, this->tf2, this->nsolver,
723  this->request.enable_signed_distance, p1, p2, normal);
724 
725  this->result->update(distance, this->model1, this->model2, b1,
726  DistanceResult::NONE, p1, p2, normal);
727  }
728 
730  bool canStop(FCL_REAL c) const {
731  if ((c >= this->result->min_distance - abs_err) &&
732  (c * (1 + rel_err) >= this->result->min_distance))
733  return true;
734  return false;
735  }
736 
737  FCL_REAL rel_err;
738  FCL_REAL abs_err;
739 
740  const GJKSolver* nsolver;
741 
742  const HeightField<BV>* model1;
743  const S* model2;
744  BV model2_bv;
745 
746  mutable int num_bv_tests;
747  mutable int num_leaf_tests;
748  mutable FCL_REAL query_time_seconds;
749 };
750 
752 
753 } // namespace fcl
754 } // namespace hpp
755 
757 
758 #endif
#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:109
static const int NONE
invalid contact primitive information
Definition: collision_data.h:1088
FaceOrientation
Definition: hfield.h:57