hpp-fcl  2.3.0
HPP fork of FCL -- The Flexible Collision Library
narrowphase.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * Copyright (c) 2018-2019, Centre National de la Recherche Scientifique
7  * All rights reserved.
8  * Copyright (c) 2021-2022, INRIA
9  * All rights reserved.
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of Open Source Robotics Foundation nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  */
37 
40 #ifndef HPP_FCL_NARROWPHASE_H
41 #define HPP_FCL_NARROWPHASE_H
42 
43 #include <limits>
44 #include <iostream>
45 
47 #include <hpp/fcl/collision_data.h>
48 
49 namespace hpp {
50 namespace fcl {
51 
55  typedef Eigen::Array<FCL_REAL, 1, 2> Array2d;
56 
58  template <typename S1, typename S2>
60  const S1& s1, const S2& s2, Vec3f& guess,
61  support_func_guess_t& support_hint) const {
62  switch (gjk_initial_guess) {
64  guess = Vec3f(1, 0, 0);
65  support_hint.setZero();
66  break;
68  guess = cached_guess;
69  support_hint = support_func_cached_guess;
70  break;
72  if (s1.aabb_local.volume() < 0 || s2.aabb_local.volume() < 0) {
74  "computeLocalAABB must have been called on the shapes before "
75  "using "
76  "GJKInitialGuess::BoundingVolumeGuess.",
77  std::logic_error);
78  }
79  guess.noalias() = s1.aabb_local.center() -
80  (shape.oR1 * s2.aabb_local.center() + shape.ot1);
81  support_hint.setZero();
82  break;
83  default:
84  HPP_FCL_THROW_PRETTY("Wrong initial guess for GJK.", std::logic_error);
85  }
86  // TODO: use gjk_initial_guess instead
89  if (enable_cached_guess) {
90  guess = cached_guess;
91  support_hint = support_func_cached_guess;
92  }
94 
95  gjk.setDistanceEarlyBreak(distance_upper_bound);
96 
97  gjk.gjk_variant = gjk_variant;
98  gjk.convergence_criterion = gjk_convergence_criterion;
99  gjk.convergence_criterion_type = gjk_convergence_criterion_type;
100  }
101 
103  template <typename S1, typename S2>
104  bool shapeIntersect(const S1& s1, const Transform3f& tf1, const S2& s2,
105  const Transform3f& tf2, FCL_REAL& distance_lower_bound,
106  bool enable_penetration, Vec3f* contact_points,
107  Vec3f* normal) const {
109  shape.set(&s1, &s2, tf1, tf2);
110 
111  Vec3f guess;
112  support_func_guess_t support_hint;
113  details::GJK gjk((unsigned int)gjk_max_iterations, gjk_tolerance);
114  initialize_gjk(gjk, shape, s1, s2, guess, support_hint);
115 
116  details::GJK::Status gjk_status = gjk.evaluate(shape, guess, support_hint);
119  if (gjk_initial_guess == GJKInitialGuess::CachedGuess ||
120  enable_cached_guess) {
121  cached_guess = gjk.getGuessFromSimplex();
122  support_func_cached_guess = gjk.support_hint;
123  }
125 
126  Vec3f w0, w1;
127  switch (gjk_status) {
129  if (!enable_penetration && contact_points == NULL && normal == NULL)
130  return true;
131  if (gjk.hasPenetrationInformation(shape)) {
132  gjk.getClosestPoints(shape, w0, w1);
133  distance_lower_bound = gjk.distance;
134  if (normal)
135  (*normal).noalias() = tf1.getRotation() * (w0 - w1).normalized();
136  if (contact_points) *contact_points = tf1.transform((w0 + w1) / 2);
137  return true;
138  } else {
139  details::EPA epa(epa_max_face_num, epa_max_vertex_num,
140  epa_max_iterations, epa_tolerance);
141  details::EPA::Status epa_status = epa.evaluate(gjk, -guess);
142  if (epa_status & details::EPA::Valid ||
143  epa_status == details::EPA::OutOfFaces // Warnings
144  || epa_status == details::EPA::OutOfVertices // Warnings
145  ) {
146  epa.getClosestPoints(shape, w0, w1);
147  distance_lower_bound = -epa.depth;
148  if (normal) (*normal).noalias() = tf1.getRotation() * epa.normal;
149  if (contact_points)
150  *contact_points =
151  tf1.transform(w0 - epa.normal * (epa.depth * 0.5));
152  return true;
153  } else if (epa_status == details::EPA::FallBack) {
154  epa.getClosestPoints(shape, w0, w1);
155  distance_lower_bound = -epa.depth; // Should be zero
156  if (normal) (*normal).noalias() = tf1.getRotation() * epa.normal;
157  if (contact_points) *contact_points = tf1.transform(w0);
158  return true;
159  }
160  distance_lower_bound = -(std::numeric_limits<FCL_REAL>::max)();
161  // EPA failed but we know there is a collision so we should
162  return true;
163  }
164  break;
165  case details::GJK::Valid:
166  distance_lower_bound = gjk.distance;
167  break;
168  default:;
169  }
170 
171  return false;
172  }
173 
177  template <typename S>
178  bool shapeTriangleInteraction(const S& s, const Transform3f& tf1,
179  const Vec3f& P1, const Vec3f& P2,
180  const Vec3f& P3, const Transform3f& tf2,
181  FCL_REAL& distance, Vec3f& p1, Vec3f& p2,
182  Vec3f& normal) const {
183  bool col;
184  // Express everything in frame 1
185  const Transform3f tf_1M2(tf1.inverseTimes(tf2));
186  TriangleP tri(tf_1M2.transform(P1), tf_1M2.transform(P2),
187  tf_1M2.transform(P3));
188 
190  shape.set(&s, &tri);
191 
192  Vec3f guess;
193  support_func_guess_t support_hint;
194  details::GJK gjk((unsigned int)gjk_max_iterations, gjk_tolerance);
195  initialize_gjk(gjk, shape, s, tri, guess, support_hint);
196 
197  details::GJK::Status gjk_status = gjk.evaluate(shape, guess, support_hint);
198 
201  if (gjk_initial_guess == GJKInitialGuess::CachedGuess ||
202  enable_cached_guess) {
203  cached_guess = gjk.getGuessFromSimplex();
204  support_func_cached_guess = gjk.support_hint;
205  }
207 
208  Vec3f w0, w1;
209  switch (gjk_status) {
211  col = true;
212  if (gjk.hasPenetrationInformation(shape)) {
213  gjk.getClosestPoints(shape, w0, w1);
214  distance = gjk.distance;
215  normal.noalias() = tf1.getRotation() * (w0 - w1).normalized();
216  p1 = p2 = tf1.transform((w0 + w1) / 2);
217  } else {
218  details::EPA epa(epa_max_face_num, epa_max_vertex_num,
219  epa_max_iterations, epa_tolerance);
220  details::EPA::Status epa_status = epa.evaluate(gjk, -guess);
221  if (epa_status & details::EPA::Valid ||
222  epa_status == details::EPA::OutOfFaces // Warnings
223  || epa_status == details::EPA::OutOfVertices // Warnings
224  ) {
225  epa.getClosestPoints(shape, w0, w1);
226  distance = -epa.depth;
227  normal.noalias() = tf1.getRotation() * epa.normal;
228  p1 = p2 = tf1.transform(w0 - epa.normal * (epa.depth * 0.5));
229  assert(distance <= 1e-6);
230  } else {
231  distance = -(std::numeric_limits<FCL_REAL>::max)();
232  gjk.getClosestPoints(shape, w0, w1);
233  p1 = p2 = tf1.transform(w0);
234  }
235  }
236  break;
237  case details::GJK::Valid:
239  col = false;
240 
241  gjk.getClosestPoints(shape, p1, p2);
242  // TODO On degenerated case, the closest point may be wrong
243  // (i.e. an object face normal is colinear to gjk.ray
244  // assert (distance == (w0 - w1).norm());
245  distance = gjk.distance;
246 
247  p1 = tf1.transform(p1);
248  p2 = tf1.transform(p2);
249  assert(distance > 0);
250  break;
251  default:
252  assert(false && "should not reach type part.");
253  return true;
254  }
255  return col;
256  }
257 
259  template <typename S1, typename S2>
260  bool shapeDistance(const S1& s1, const Transform3f& tf1, const S2& s2,
261  const Transform3f& tf2, FCL_REAL& distance, Vec3f& p1,
262  Vec3f& p2, Vec3f& normal) const {
263 #ifndef NDEBUG
264  FCL_REAL eps(sqrt(std::numeric_limits<FCL_REAL>::epsilon()));
265 #endif
267  shape.set(&s1, &s2, tf1, tf2);
268 
269  Vec3f guess;
270  support_func_guess_t support_hint;
271  details::GJK gjk((unsigned int)gjk_max_iterations, gjk_tolerance);
272  initialize_gjk(gjk, shape, s1, s2, guess, support_hint);
273 
274  details::GJK::Status gjk_status = gjk.evaluate(shape, guess, support_hint);
275  if (gjk_initial_guess == GJKInitialGuess::CachedGuess ||
276  enable_cached_guess) {
277  cached_guess = gjk.getGuessFromSimplex();
278  support_func_cached_guess = gjk.support_hint;
279  }
280 
281  if (gjk_status == details::GJK::Failed) {
282  // TODO: understand why GJK fails between cylinder and box
283  assert(distance * distance < sqrt(eps));
284  Vec3f w0, w1;
285  gjk.getClosestPoints(shape, w0, w1);
286  distance = 0;
287  p1 = tf1.transform(w0);
288  p2 = tf1.transform(w1);
289  normal.setZero();
290  return false;
291  } else if (gjk_status == details::GJK::Valid) {
292  gjk.getClosestPoints(shape, p1, p2);
293  // TODO On degenerated case, the closest point may be wrong
294  // (i.e. an object face normal is colinear to gjk.ray
295  // assert (distance == (w0 - w1).norm());
296  distance = gjk.distance;
297 
298  normal.noalias() = tf1.getRotation() * gjk.ray;
299  normal.normalize();
300  p1 = tf1.transform(p1);
301  p2 = tf1.transform(p2);
302  return true;
303  } else if (gjk_status == details::GJK::EarlyStopped) {
304  distance = gjk.distance;
305  p1 = p2 = normal =
306  Vec3f::Constant(std::numeric_limits<FCL_REAL>::quiet_NaN());
307  return true;
308  } else {
309  assert(gjk_status == details::GJK::Inside);
310  if (gjk.hasPenetrationInformation(shape)) {
311  gjk.getClosestPoints(shape, p1, p2);
312  distance = gjk.distance;
313  // Return contact points in case of collision
314  // p1 = tf1.transform (p1);
315  // p2 = tf1.transform (p2);
316  normal.noalias() = tf1.getRotation() * (p1 - p2);
317  normal.normalize();
318  p1 = tf1.transform(p1);
319  p2 = tf1.transform(p2);
320  } else {
321  details::EPA epa(epa_max_face_num, epa_max_vertex_num,
322  epa_max_iterations, epa_tolerance);
323  details::EPA::Status epa_status = epa.evaluate(gjk, -guess);
324  if (epa_status & details::EPA::Valid ||
325  epa_status == details::EPA::OutOfFaces // Warnings
326  || epa_status == details::EPA::OutOfVertices // Warnings
327  || epa_status == details::EPA::FallBack) {
328  Vec3f w0, w1;
329  epa.getClosestPoints(shape, w0, w1);
330  assert(epa.depth >= -eps);
331  distance = (std::min)(0., -epa.depth);
332  normal.noalias() = tf1.getRotation() * epa.normal;
333  p1 = tf1.transform(w0);
334  p2 = tf1.transform(w1);
335  return false;
336  }
337  distance = -(std::numeric_limits<FCL_REAL>::max)();
338  gjk.getClosestPoints(shape, p1, p2);
339  p1 = tf1.transform(p1);
340  p2 = tf1.transform(p2);
341  }
342  return false;
343  }
344  }
345 
350  gjk_max_iterations = 128;
351  gjk_tolerance = 1e-6;
352  epa_max_face_num = 128;
353  epa_max_vertex_num = 64;
354  epa_max_iterations = 255;
355  epa_tolerance = 1e-6;
356  enable_cached_guess = false; // TODO: use gjk_initial_guess instead
357  cached_guess = Vec3f(1, 0, 0);
358  support_func_cached_guess = support_func_guess_t::Zero();
359  distance_upper_bound = (std::numeric_limits<FCL_REAL>::max)();
360  gjk_initial_guess = GJKInitialGuess::DefaultGuess;
361  gjk_variant = GJKVariant::DefaultGJK;
362  gjk_convergence_criterion = GJKConvergenceCriterion::VDB;
363  gjk_convergence_criterion_type = GJKConvergenceCriterionType::Relative;
364  }
365 
370  GJKSolver(const DistanceRequest& request) {
371  cached_guess = Vec3f(1, 0, 0);
372  support_func_cached_guess = support_func_guess_t::Zero();
373  distance_upper_bound = (std::numeric_limits<FCL_REAL>::max)();
374 
375  // EPS settings
376  epa_max_face_num = 128;
377  epa_max_vertex_num = 64;
378  epa_max_iterations = 255;
379  epa_tolerance = 1e-6;
380 
381  set(request);
382  }
383 
388  void set(const DistanceRequest& request) {
389  gjk_initial_guess = request.gjk_initial_guess;
390  // TODO: use gjk_initial_guess instead
391  enable_cached_guess = request.enable_cached_gjk_guess;
392  gjk_variant = request.gjk_variant;
393  gjk_convergence_criterion = request.gjk_convergence_criterion;
394  gjk_convergence_criterion_type = request.gjk_convergence_criterion_type;
395  gjk_tolerance = request.gjk_tolerance;
396  gjk_max_iterations = request.gjk_max_iterations;
397  if (gjk_initial_guess == GJKInitialGuess::CachedGuess ||
398  enable_cached_guess) {
399  cached_guess = request.cached_gjk_guess;
400  support_func_cached_guess = request.cached_support_func_guess;
401  }
402  }
403 
408  GJKSolver(const CollisionRequest& request) {
409  cached_guess = Vec3f(1, 0, 0);
410  support_func_cached_guess = support_func_guess_t::Zero();
411  distance_upper_bound = (std::numeric_limits<FCL_REAL>::max)();
412 
413  // EPS settings
414  epa_max_face_num = 128;
415  epa_max_vertex_num = 64;
416  epa_max_iterations = 255;
417  epa_tolerance = 1e-6;
418 
419  set(request);
420  }
421 
426  void set(const CollisionRequest& request) {
427  gjk_initial_guess = request.gjk_initial_guess;
428  // TODO: use gjk_initial_guess instead
429  enable_cached_guess = request.enable_cached_gjk_guess;
430  gjk_variant = request.gjk_variant;
431  gjk_convergence_criterion = request.gjk_convergence_criterion;
432  gjk_convergence_criterion_type = request.gjk_convergence_criterion_type;
433  gjk_tolerance = request.gjk_tolerance;
434  gjk_max_iterations = request.gjk_max_iterations;
435  if (gjk_initial_guess == GJKInitialGuess::CachedGuess ||
436  enable_cached_guess) {
437  cached_guess = request.cached_gjk_guess;
438  support_func_cached_guess = request.cached_support_func_guess;
439  }
440 
441  // The distance upper bound should be at least greater to the requested
442  // security margin. Otherwise, we will likely miss some collisions.
443  distance_upper_bound = (std::max)(
444  0., (std::max)(request.distance_upper_bound, request.security_margin));
445  }
446 
448  GJKSolver(const GJKSolver& other) = default;
449 
452  bool operator==(const GJKSolver& other) const {
453  return epa_max_face_num == other.epa_max_face_num &&
454  epa_max_vertex_num == other.epa_max_vertex_num &&
455  epa_max_iterations == other.epa_max_iterations &&
456  epa_tolerance == other.epa_tolerance &&
457  gjk_max_iterations == other.gjk_max_iterations &&
458  enable_cached_guess ==
459  other.enable_cached_guess && // TODO: use gjk_initial_guess
460  // instead
461  cached_guess == other.cached_guess &&
462  support_func_cached_guess == other.support_func_cached_guess &&
463  distance_upper_bound == other.distance_upper_bound &&
464  gjk_initial_guess == other.gjk_initial_guess &&
465  gjk_variant == other.gjk_variant &&
466  gjk_convergence_criterion == other.gjk_convergence_criterion &&
467  gjk_convergence_criterion_type ==
469  }
471 
472  bool operator!=(const GJKSolver& other) const { return !(*this == other); }
473 
475  unsigned int epa_max_face_num;
476 
478  unsigned int epa_max_vertex_num;
479 
481  unsigned int epa_max_iterations;
482 
485 
488 
490  mutable size_t gjk_max_iterations;
491 
494  HPP_FCL_DEPRECATED_MESSAGE("Use gjk_initial_guess instead")
495  mutable bool enable_cached_guess;
496 
498  mutable Vec3f cached_guess;
499 
501  mutable GJKInitialGuess gjk_initial_guess;
502 
504  mutable GJKVariant gjk_variant;
505 
507  mutable GJKConvergenceCriterion gjk_convergence_criterion;
508 
510  mutable GJKConvergenceCriterionType gjk_convergence_criterion_type;
511 
513  mutable support_func_guess_t support_func_cached_guess;
514 
519  mutable FCL_REAL distance_upper_bound;
520 
521  public:
522  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
523 };
524 
525 template <>
526 HPP_FCL_DLLAPI bool GJKSolver::shapeTriangleInteraction(
527  const Sphere& s, const Transform3f& tf1, const Vec3f& P1, const Vec3f& P2,
528  const Vec3f& P3, const Transform3f& tf2, FCL_REAL& distance, Vec3f& p1,
529  Vec3f& p2, Vec3f& normal) const;
530 
531 template <>
532 HPP_FCL_DLLAPI bool GJKSolver::shapeTriangleInteraction(
533  const Halfspace& s, const Transform3f& tf1, const Vec3f& P1,
534  const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2,
535  FCL_REAL& distance, Vec3f& p1, Vec3f& p2, Vec3f& normal) const;
536 
537 template <>
538 HPP_FCL_DLLAPI bool GJKSolver::shapeTriangleInteraction(
539  const Plane& s, const Transform3f& tf1, const Vec3f& P1, const Vec3f& P2,
540  const Vec3f& P3, const Transform3f& tf2, FCL_REAL& distance, Vec3f& p1,
541  Vec3f& p2, Vec3f& normal) const;
542 
543 #define SHAPE_INTERSECT_SPECIALIZATION_BASE(S1, S2) \
544  template <> \
545  HPP_FCL_DLLAPI bool GJKSolver::shapeIntersect<S1, S2>( \
546  const S1& s1, const Transform3f& tf1, const S2& s2, \
547  const Transform3f& tf2, FCL_REAL& distance_lower_bound, bool, \
548  Vec3f* contact_points, Vec3f* normal) const
549 
550 #define SHAPE_INTERSECT_SPECIALIZATION(S1, S2) \
551  SHAPE_INTERSECT_SPECIALIZATION_BASE(S1, S2); \
552  SHAPE_INTERSECT_SPECIALIZATION_BASE(S2, S1)
553 
554 SHAPE_INTERSECT_SPECIALIZATION(Sphere, Capsule);
556 SHAPE_INTERSECT_SPECIALIZATION(Sphere, Box);
557 SHAPE_INTERSECT_SPECIALIZATION(Sphere, Halfspace);
558 SHAPE_INTERSECT_SPECIALIZATION(Sphere, Plane);
559 
560 SHAPE_INTERSECT_SPECIALIZATION(Halfspace, Box);
561 SHAPE_INTERSECT_SPECIALIZATION(Halfspace, Capsule);
562 SHAPE_INTERSECT_SPECIALIZATION(Halfspace, Cylinder);
563 SHAPE_INTERSECT_SPECIALIZATION(Halfspace, Cone);
564 SHAPE_INTERSECT_SPECIALIZATION(Halfspace, Plane);
565 
567 SHAPE_INTERSECT_SPECIALIZATION(Plane, Capsule);
568 SHAPE_INTERSECT_SPECIALIZATION(Plane, Cylinder);
569 SHAPE_INTERSECT_SPECIALIZATION(Plane, Cone);
570 
571 #undef SHAPE_INTERSECT_SPECIALIZATION
572 #undef SHAPE_INTERSECT_SPECIALIZATION_BASE
573 
574 #define SHAPE_DISTANCE_SPECIALIZATION_BASE(S1, S2) \
575  template <> \
576  HPP_FCL_DLLAPI bool GJKSolver::shapeDistance<S1, S2>( \
577  const S1& s1, const Transform3f& tf1, const S2& s2, \
578  const Transform3f& tf2, FCL_REAL& dist, Vec3f& p1, Vec3f& p2, \
579  Vec3f& normal) const
580 
581 #define SHAPE_DISTANCE_SPECIALIZATION(S1, S2) \
582  SHAPE_DISTANCE_SPECIALIZATION_BASE(S1, S2); \
583  SHAPE_DISTANCE_SPECIALIZATION_BASE(S2, S1)
584 
585 SHAPE_DISTANCE_SPECIALIZATION(Sphere, Capsule);
586 SHAPE_DISTANCE_SPECIALIZATION(Sphere, Box);
587 SHAPE_DISTANCE_SPECIALIZATION(Sphere, Cylinder);
588 SHAPE_DISTANCE_SPECIALIZATION_BASE(Sphere, Sphere);
589 SHAPE_DISTANCE_SPECIALIZATION_BASE(Capsule, Capsule);
590 SHAPE_DISTANCE_SPECIALIZATION_BASE(TriangleP, TriangleP);
591 
592 #undef SHAPE_DISTANCE_SPECIALIZATION
593 #undef SHAPE_DISTANCE_SPECIALIZATION_BASE
594 
595 #if !(__cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600))
596 #pragma GCC diagnostic push
597 #pragma GCC diagnostic ignored "-Wc99-extensions"
598 #endif
599 
602 // param doc is the doxygen detailled description (should be enclosed in /** */
603 // and contain no dot for some obscure reasons).
604 #define HPP_FCL_DECLARE_SHAPE_INTERSECT(Shape1, Shape2, doc) \
605  \
606  doc template <> \
607  HPP_FCL_DLLAPI bool GJKSolver::shapeIntersect<Shape1, Shape2>( \
608  const Shape1& s1, const Transform3f& tf1, const Shape2& s2, \
609  const Transform3f& tf2, FCL_REAL& distance_lower_bound, \
610  bool enable_penetration, Vec3f* contact_points, Vec3f* normal) const
611 #define HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF(Shape, doc) \
612  HPP_FCL_DECLARE_SHAPE_INTERSECT(Shape, Shape, doc)
613 #define HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Shape1, Shape2, doc) \
614  HPP_FCL_DECLARE_SHAPE_INTERSECT(Shape1, Shape2, doc); \
615  HPP_FCL_DECLARE_SHAPE_INTERSECT(Shape2, Shape1, doc)
616 
618 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Sphere, Capsule, );
619 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Sphere, Halfspace, );
620 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Sphere, Plane, );
621 
622 template <>
623 HPP_FCL_DLLAPI bool GJKSolver::shapeIntersect<Box, Sphere>(
624  const Box& s1, const Transform3f& tf1, const Sphere& s2,
625  const Transform3f& tf2, FCL_REAL& distance_lower_bound,
626  bool enable_penetration, Vec3f* contact_points, Vec3f* normal) const;
627 
628 #ifdef IS_DOXYGEN // for doxygen only
629 
632 template <>
633 HPP_FCL_DLLAPI bool GJKSolver::shapeIntersect<Box, Box>(
634  const Box& s1, const Transform3f& tf1, const Box& s2,
635  const Transform3f& tf2, FCL_REAL& distance_lower_bound,
636  bool enable_penetration, Vec3f* contact_points, Vec3f* normal) const;
637 #endif
638 // HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF(Box,);
639 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Box, Halfspace, );
641 
642 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Capsule, Halfspace, );
643 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Capsule, Plane, );
644 
645 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Cylinder, Halfspace, );
646 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Cylinder, Plane, );
647 
648 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Cone, Halfspace, );
650 
652 
654 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Plane, Halfspace, );
655 
656 #undef HPP_FCL_DECLARE_SHAPE_INTERSECT
657 #undef HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF
658 #undef HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR
659 
661 
664 
665 // param doc is the doxygen detailled description (should be enclosed in /** */
666 // and contain no dot for some obscure reasons).
667 #define HPP_FCL_DECLARE_SHAPE_TRIANGLE(Shape, doc) \
668  \
669  doc template <> \
670  HPP_FCL_DLLAPI bool GJKSolver::shapeTriangleInteraction<Shape>( \
671  const Shape& s, const Transform3f& tf1, const Vec3f& P1, \
672  const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2, \
673  FCL_REAL& distance, Vec3f& p1, Vec3f& p2, Vec3f& normal) const
674 
676 HPP_FCL_DECLARE_SHAPE_TRIANGLE(Halfspace, );
678 
679 #undef HPP_FCL_DECLARE_SHAPE_TRIANGLE
680 
682 
685 
686 // param doc is the doxygen detailled description (should be enclosed in /** */
687 // and contain no dot for some obscure reasons).
688 #define HPP_FCL_DECLARE_SHAPE_DISTANCE(Shape1, Shape2, doc) \
689  \
690  doc template <> \
691  bool HPP_FCL_DLLAPI GJKSolver::shapeDistance<Shape1, Shape2>( \
692  const Shape1& s1, const Transform3f& tf1, const Shape2& s2, \
693  const Transform3f& tf2, FCL_REAL& dist, Vec3f& p1, Vec3f& p2, \
694  Vec3f& normal) const
695 #define HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF(Shape, doc) \
696  HPP_FCL_DECLARE_SHAPE_DISTANCE(Shape, Shape, doc)
697 #define HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR(Shape1, Shape2, doc) \
698  HPP_FCL_DECLARE_SHAPE_DISTANCE(Shape1, Shape2, doc); \
699  HPP_FCL_DECLARE_SHAPE_DISTANCE(Shape2, Shape1, doc)
700 
702 HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR(Sphere, Capsule, );
703 HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR(Sphere, Cylinder, );
705 
707  Capsule,
709 );
710 
712  TriangleP,
715 );
716 
717 #undef HPP_FCL_DECLARE_SHAPE_DISTANCE
718 #undef HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF
719 #undef HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR
720 
722 #if !(__cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600))
723 #pragma GCC diagnostic pop
724 #endif
725 } // namespace fcl
726 
727 } // namespace hpp
728 
729 #endif
GJKConvergenceCriterionType gjk_convergence_criterion_type
Relative or absolute.
Definition: narrowphase.h:510
GJKVariant gjk_variant
Variant to use for the GJK algorithm.
Definition: narrowphase.h:504
void initialize_gjk(details::GJK &gjk, const details::MinkowskiDiff &shape, const S1 &s1, const S2 &s2, Vec3f &guess, support_func_guess_t &support_hint) const
initialize GJK
Definition: narrowphase.h:59
GJKConvergenceCriterionType
Wether the convergence criterion is scaled on the norm of the solution or not.
Definition: data_types.h:93
Definition: gjk.h:165
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
Definition: gjk.h:165
request to the distance computation
Definition: collision_data.h:392
Definition: data_types.h:83
Definition: data_types.h:89
unsigned int epa_max_iterations
maximum number of iterations used for EPA iterations
Definition: narrowphase.h:481
support_func_guess_t support_hint
Definition: gjk.h:172
#define HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
Definition: fwd.hh:84
Status
Definition: gjk.h:367
#define HPP_FCL_COMPILER_DIAGNOSTIC_PUSH
Definition: fwd.hh:82
Definition: data_types.h:80
GJKVariant
Variant to use for the GJK algorithm.
Definition: data_types.h:83
GJKSolver(const DistanceRequest &request)
Constructor from a DistanceRequest.
Definition: narrowphase.h:370
Main namespace.
Definition: broadphase_bruteforce.h:44
unsigned int epa_max_face_num
maximum number of simplex face used in EPA algorithm
Definition: narrowphase.h:475
GJKConvergenceCriterion gjk_convergence_criterion
Criterion used to stop GJK.
Definition: narrowphase.h:507
Definition: gjk.h:369
bool enable_cached_guess
Whether smart guess can be provided Use gjk_initial_guess instead.
Definition: narrowphase.h:495
#define HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF(Shape, doc)
Definition: narrowphase.h:695
Half Space: this is equivalent to the Plane in ODE. The separation plane is defined as n * x = d; Poi...
Definition: geometric_shapes.h:729
#define SHAPE_DISTANCE_SPECIALIZATION(S1, S2)
Definition: narrowphase.h:581
bool getClosestPoints(const MinkowskiDiff &shape, Vec3f &w0, Vec3f &w1)
GJKSolver()
Default constructor for GJK algorithm.
Definition: narrowphase.h:349
void set(const ShapeBase *shape0, const ShapeBase *shape1)
Infinite plane.
Definition: geometric_shapes.h:810
class for GJK algorithm
Definition: gjk.h:141
Vec3f ray
Definition: gjk.h:168
Minkowski difference class of two shapes.
Definition: gjk.h:59
class for EPA algorithm
Definition: gjk.h:312
Status evaluate(const MinkowskiDiff &shape, const Vec3f &guess, const support_func_guess_t &supportHint=support_func_guess_t::Zero())
GJK algorithm, given the initial value guess.
bool getClosestPoints(const MinkowskiDiff &shape, Vec3f &w0, Vec3f &w1)
Vec3f getGuessFromSimplex() const
get the guess from current simplex
request to the collision algorithm
Definition: collision_data.h:235
bool operator==(const GJKSolver &other) const
Definition: narrowphase.h:452
#define SHAPE_DISTANCE_SPECIALIZATION_BASE(S1, S2)
Definition: narrowphase.h:574
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.
Vec3f transform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the transform
Definition: transform.h:153
#define HPP_FCL_DEPRECATED_MESSAGE(message)
Definition: deprecated.hh:38
double FCL_REAL
Definition: data_types.h:65
Vec3f ot1
translation from shape1 to shape0 such that .
Definition: gjk.h:79
GJKInitialGuess
Initial guess to use for the GJK algorithm DefaultGuess: Vec3f(1, 0, 0) CachedGuess: previous vector ...
Definition: data_types.h:80
unsigned int epa_max_vertex_num
maximum number of simplex vertex used in EPA algorithm
Definition: narrowphase.h:478
Status
Status of the GJK algorithm: Valid: GJK converged and the shapes are not in collision. Inside: GJK converged and the shapes are in collision. Failed: GJK did not converge.
Definition: gjk.h:165
GJKVariant gjk_variant
Definition: gjk.h:169
Triangle stores the points instead of only indices of points.
Definition: geometric_shapes.h:71
Eigen::Vector2i support_func_guess_t
Definition: data_types.h:72
FCL_REAL depth
Definition: gjk.h:382
FCL_REAL distance
Definition: gjk.h:186
#define SHAPE_INTERSECT_SPECIALIZATION_BASE(S1, S2)
Definition: narrowphase.h:543
Transform3f inverseTimes(const Transform3f &other) const
inverse the transform and multiply with another
Definition: transform.h:170
bool shapeDistance(const S1 &s1, const Transform3f &tf1, const S2 &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
distance computation between two shapes
Definition: narrowphase.h:260
Center at zero point sphere.
Definition: geometric_shapes.h:196
Vec3f cached_guess
smart guess
Definition: narrowphase.h:498
Definition: data_types.h:93
bool shapeTriangleInteraction(const S &s, const Transform3f &tf1, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
intersection checking between one shape and a triangle with transformation
Definition: narrowphase.h:178
Status evaluate(GJK &gjk, const Vec3f &guess)
#define HPP_FCL_COMPILER_DIAGNOSTIC_POP
Definition: fwd.hh:83
#define HPP_FCL_THROW_PRETTY(message, exception)
Definition: fwd.hh:57
bool shapeIntersect(const S1 &s1, const Transform3f &tf1, const S2 &s2, const Transform3f &tf2, FCL_REAL &distance_lower_bound, bool enable_penetration, Vec3f *contact_points, Vec3f *normal) const
intersection checking between two shapes
Definition: narrowphase.h:104
GJKConvergenceCriterion convergence_criterion
Definition: gjk.h:170
#define HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF(Shape, doc)
Definition: narrowphase.h:611
bool operator!=(const GJKSolver &other) const
Definition: narrowphase.h:472
void setDistanceEarlyBreak(const FCL_REAL &dup)
Distance threshold for early break. GJK stops when it proved the distance is more than this threshold...
Definition: gjk.h:245
#define HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR(Shape1, Shape2, doc)
Definition: narrowphase.h:613
#define SHAPE_INTERSECT_SPECIALIZATION(S1, S2)
Definition: narrowphase.h:550
#define HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR(Shape1, Shape2, doc)
Definition: narrowphase.h:697
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Definition: narrowphase.h:54
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
GJKConvergenceCriterion
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision)...
Definition: data_types.h:89
FCL_REAL gjk_tolerance
the threshold used in GJK to stop iteration
Definition: narrowphase.h:487
Vec3f normal
Definition: gjk.h:381
Eigen::Array< FCL_REAL, 1, 2 > Array2d
Definition: narrowphase.h:55
GJKSolver(const CollisionRequest &request)
Constructor from a CollisionRequest.
Definition: narrowphase.h:408
support_func_guess_t support_func_cached_guess
smart guess for the support function
Definition: narrowphase.h:513
size_t gjk_max_iterations
maximum number of iterations used for GJK iterations
Definition: narrowphase.h:490
Matrix3f oR1
rotation from shape1 to shape0 such that .
Definition: gjk.h:75
Definition: data_types.h:80
const Matrix3f & getRotation() const
get rotation
Definition: transform.h:109
bool hasPenetrationInformation(const MinkowskiDiff &shape)
Definition: gjk.h:230
GJKInitialGuess gjk_initial_guess
which warm start to use for GJK
Definition: narrowphase.h:501
GJKConvergenceCriterionType convergence_criterion_type
Definition: gjk.h:171
FCL_REAL epa_tolerance
the threshold used in EPA to stop iteration
Definition: narrowphase.h:484
#define HPP_FCL_DECLARE_SHAPE_TRIANGLE(Shape, doc)
Definition: narrowphase.h:667
#define HPP_FCL_DLLAPI
Definition: config.hh:64
Definition: data_types.h:80
FCL_REAL distance_upper_bound
Distance above which the GJK solver stoppes its computations and processes to an early stopping...
Definition: narrowphase.h:519
Definition: gjk.h:165