hpp-fcl  3.0.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-2024, 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 
46 #include <hpp/fcl/collision_data.h>
48 #include <hpp/fcl/logging.h>
49 
50 namespace hpp {
51 namespace fcl {
52 
59  public:
60  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
61 
63  mutable details::GJK gjk;
64 
67 
70 
73 
76  HPP_FCL_DEPRECATED_MESSAGE(Use gjk_initial_guess instead)
77  bool enable_cached_guess;
78 
80  mutable Vec3f cached_guess;
81 
83  mutable support_func_guess_t support_func_cached_guess;
84 
87  FCL_REAL distance_upper_bound;
88 
90  GJKVariant gjk_variant;
91 
93  GJKConvergenceCriterion gjk_convergence_criterion;
94 
96  GJKConvergenceCriterionType gjk_convergence_criterion_type;
97 
99  mutable details::EPA epa;
100 
102  size_t epa_max_iterations;
103 
105  FCL_REAL epa_tolerance;
106 
108  mutable details::MinkowskiDiff minkowski_difference;
109 
110  private:
111  // Used internally for assertion checks.
112  static constexpr FCL_REAL m_dummy_precision = 1e-6;
113 
114  public:
126  gjk_max_iterations(GJK_DEFAULT_MAX_ITERATIONS),
127  gjk_tolerance(GJK_DEFAULT_TOLERANCE),
128  gjk_initial_guess(GJKInitialGuess::DefaultGuess),
129  enable_cached_guess(false), // Use gjk_initial_guess instead
130  cached_guess(Vec3f(1, 0, 0)),
131  support_func_cached_guess(support_func_guess_t::Zero()),
132  distance_upper_bound((std::numeric_limits<FCL_REAL>::max)()),
133  gjk_variant(GJKVariant::DefaultGJK),
134  gjk_convergence_criterion(GJKConvergenceCriterion::Default),
135  gjk_convergence_criterion_type(GJKConvergenceCriterionType::Absolute),
136  epa(0, EPA_DEFAULT_TOLERANCE),
137  epa_max_iterations(EPA_DEFAULT_MAX_ITERATIONS),
138  epa_tolerance(EPA_DEFAULT_TOLERANCE) {}
139 
149  explicit GJKSolver(const DistanceRequest& request)
150  : gjk(request.gjk_max_iterations, request.gjk_tolerance),
151  epa(0, request.epa_tolerance) {
152  this->cached_guess = Vec3f(1, 0, 0);
153  this->support_func_cached_guess = support_func_guess_t::Zero();
154 
155  set(request);
156  }
157 
162  void set(const DistanceRequest& request) {
163  // ---------------------
164  // GJK settings
165  this->gjk_initial_guess = request.gjk_initial_guess;
166  this->enable_cached_guess = request.enable_cached_gjk_guess;
167  if (this->gjk_initial_guess == GJKInitialGuess::CachedGuess ||
168  this->enable_cached_guess) {
169  this->cached_guess = request.cached_gjk_guess;
170  this->support_func_cached_guess = request.cached_support_func_guess;
171  }
172  this->gjk_max_iterations = request.gjk_max_iterations;
173  this->gjk_tolerance = request.gjk_tolerance;
174  // For distance computation, we don't want GJK to early stop
175  this->distance_upper_bound = (std::numeric_limits<FCL_REAL>::max)();
176  this->gjk_variant = request.gjk_variant;
177  this->gjk_convergence_criterion = request.gjk_convergence_criterion;
178  this->gjk_convergence_criterion_type =
180 
181  // ---------------------
182  // EPA settings
183  this->epa_max_iterations = request.epa_max_iterations;
184  this->epa_tolerance = request.epa_tolerance;
185 
186  // ---------------------
187  // Reset GJK and EPA status
188  this->epa.status = details::EPA::Status::DidNotRun;
189  this->gjk.status = details::GJK::Status::DidNotRun;
190  }
191 
201  explicit GJKSolver(const CollisionRequest& request)
202  : gjk(request.gjk_max_iterations, request.gjk_tolerance),
203  epa(0, request.epa_tolerance) {
204  this->cached_guess = Vec3f(1, 0, 0);
205  this->support_func_cached_guess = support_func_guess_t::Zero();
206 
207  set(request);
208  }
209 
214  void set(const CollisionRequest& request) {
215  // ---------------------
216  // GJK settings
217  this->gjk_initial_guess = request.gjk_initial_guess;
218  this->enable_cached_guess = request.enable_cached_gjk_guess;
219  if (this->gjk_initial_guess == GJKInitialGuess::CachedGuess ||
220  this->enable_cached_guess) {
221  this->cached_guess = request.cached_gjk_guess;
222  this->support_func_cached_guess = request.cached_support_func_guess;
223  }
224  this->gjk_tolerance = request.gjk_tolerance;
225  this->gjk_max_iterations = request.gjk_max_iterations;
226  // The distance upper bound should be at least greater to the requested
227  // security margin. Otherwise, we will likely miss some collisions.
228  this->distance_upper_bound = (std::max)(
229  0., (std::max)(request.distance_upper_bound, request.security_margin));
230  this->gjk_variant = request.gjk_variant;
231  this->gjk_convergence_criterion = request.gjk_convergence_criterion;
232  this->gjk_convergence_criterion_type =
234 
235  // ---------------------
236  // EPA settings
237  this->epa_max_iterations = request.epa_max_iterations;
238  this->epa_tolerance = request.epa_tolerance;
239 
240  // ---------------------
241  // Reset GJK and EPA status
242  this->gjk.status = details::GJK::Status::DidNotRun;
243  this->epa.status = details::EPA::Status::DidNotRun;
244  }
245 
247  GJKSolver(const GJKSolver& other) = default;
248 
251  bool operator==(const GJKSolver& other) const {
252  return this->enable_cached_guess ==
253  other.enable_cached_guess && // use gjk_initial_guess instead
254  this->cached_guess == other.cached_guess &&
255  this->support_func_cached_guess == other.support_func_cached_guess &&
256  this->gjk_max_iterations == other.gjk_max_iterations &&
257  this->gjk_tolerance == other.gjk_tolerance &&
258  this->distance_upper_bound == other.distance_upper_bound &&
259  this->gjk_variant == other.gjk_variant &&
260  this->gjk_convergence_criterion == other.gjk_convergence_criterion &&
261  this->gjk_convergence_criterion_type ==
263  this->gjk_initial_guess == other.gjk_initial_guess &&
264  this->epa_max_iterations == other.epa_max_iterations &&
265  this->epa_tolerance == other.epa_tolerance;
266  }
268 
269  bool operator!=(const GJKSolver& other) const { return !(*this == other); }
270 
273  FCL_REAL getDistancePrecision(const bool compute_penetration) const {
274  return compute_penetration
275  ? (std::max)(this->gjk_tolerance, this->epa_tolerance)
276  : this->gjk_tolerance;
277  }
278 
308  template <typename S1, typename S2>
309  FCL_REAL shapeDistance(const S1& s1, const Transform3f& tf1, const S2& s2,
310  const Transform3f& tf2, const bool compute_penetration,
311  Vec3f& p1, Vec3f& p2, Vec3f& normal) const {
312  constexpr bool relative_transformation_already_computed = false;
314  this->runGJKAndEPA(s1, tf1, s2, tf2, compute_penetration, distance, p1, p2,
315  normal, relative_transformation_already_computed);
316  return distance;
317  }
318 
322  template <typename S1>
323  FCL_REAL shapeDistance(const S1& s1, const Transform3f& tf1,
324  const TriangleP& s2, const Transform3f& tf2,
325  const bool compute_penetration, Vec3f& p1, Vec3f& p2,
326  Vec3f& normal) const {
327  const Transform3f tf_1M2(tf1.inverseTimes(tf2));
328  TriangleP tri(tf_1M2.transform(s2.a), tf_1M2.transform(s2.b),
329  tf_1M2.transform(s2.c));
330 
331  constexpr bool relative_transformation_already_computed = true;
333  this->runGJKAndEPA(s1, tf1, tri, tf_1M2, compute_penetration, distance, p1,
334  p2, normal, relative_transformation_already_computed);
335  return distance;
336  }
337 
339  template <typename S2>
341  const S2& s2, const Transform3f& tf2,
342  const bool compute_penetration, Vec3f& p1, Vec3f& p2,
343  Vec3f& normal) const {
344  FCL_REAL distance = this->shapeDistance<S2>(
345  s2, tf2, s1, tf1, compute_penetration, p2, p1, normal);
346  normal = -normal;
347  return distance;
348  }
349 
350  protected:
353  template <typename S1, typename S2>
354  void getGJKInitialGuess(const S1& s1, const S2& s2, Vec3f& guess,
355  support_func_guess_t& support_hint,
356  const Vec3f& default_guess = Vec3f(1, 0, 0)) const {
357  // There is no reason not to warm-start the support function, so we always
358  // do it.
359  support_hint = this->support_func_cached_guess;
360  // The following switch takes care of the GJK warm-start.
361  switch (gjk_initial_guess) {
363  guess = default_guess;
364  break;
366  guess = this->cached_guess;
367  break;
369  if (s1.aabb_local.volume() < 0 || s2.aabb_local.volume() < 0) {
371  "computeLocalAABB must have been called on the shapes before "
372  "using "
373  "GJKInitialGuess::BoundingVolumeGuess.",
374  std::logic_error);
375  }
376  guess.noalias() =
377  s1.aabb_local.center() -
378  (this->minkowski_difference.oR1 * s2.aabb_local.center() +
379  this->minkowski_difference.ot1);
380  break;
381  default:
382  HPP_FCL_THROW_PRETTY("Wrong initial guess for GJK.", std::logic_error);
383  }
384  // TODO: use gjk_initial_guess instead
387  if (this->enable_cached_guess) {
388  guess = this->cached_guess;
389  }
391  }
392 
420  template <typename S1, typename S2,
421  int _SupportOptions = details::SupportOptions::NoSweptSphere>
423  const S1& s1, const Transform3f& tf1, const S2& s2,
424  const Transform3f& tf2, const bool compute_penetration,
425  FCL_REAL& distance, Vec3f& p1, Vec3f& p2, Vec3f& normal,
426  const bool relative_transformation_already_computed = false) const {
427  // Reset internal state of GJK algorithm
428  if (relative_transformation_already_computed)
429  this->minkowski_difference.set<_SupportOptions>(&s1, &s2);
430  else
431  this->minkowski_difference.set<_SupportOptions>(&s1, &s2, tf1, tf2);
432  this->gjk.reset(this->gjk_max_iterations, this->gjk_tolerance);
433  this->gjk.setDistanceEarlyBreak(this->distance_upper_bound);
434  this->gjk.gjk_variant = this->gjk_variant;
435  this->gjk.convergence_criterion = this->gjk_convergence_criterion;
436  this->gjk.convergence_criterion_type = this->gjk_convergence_criterion_type;
437  this->epa.status = details::EPA::Status::DidNotRun;
438 
439  // Get initial guess for GJK: default, cached or bounding volume guess
440  Vec3f guess;
441  support_func_guess_t support_hint;
442  getGJKInitialGuess(*(this->minkowski_difference.shapes[0]),
443  *(this->minkowski_difference.shapes[1]), guess,
444  support_hint);
445 
446  this->gjk.evaluate(this->minkowski_difference, guess, support_hint);
447 
448  switch (this->gjk.status) {
450  HPP_FCL_ASSERT(false, "GJK did not run. It should have!",
451  std::logic_error);
452  this->cached_guess = Vec3f(1, 0, 0);
453  this->support_func_cached_guess.setZero();
454  distance = -(std::numeric_limits<FCL_REAL>::max)();
455  p1 = p2 = normal =
456  Vec3f::Constant(std::numeric_limits<FCL_REAL>::quiet_NaN());
457  break;
459  //
460  // GJK ran out of iterations.
461  HPP_FCL_LOG_WARNING("GJK ran out of iterations.");
462  GJKExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
463  break;
465  //
466  // Case where GJK early stopped because the distance was found to be
467  // above the `distance_upper_bound`.
468  // The two witness points have no meaning.
469  GJKEarlyStopExtractWitnessPointsAndNormal(tf1, distance, p1, p2,
470  normal);
472  this->m_dummy_precision,
473  "The distance should be bigger than GJK's "
474  "`distance_upper_bound`.",
475  std::logic_error);
476  break;
478  //
479  // Case where GJK converged and proved that the shapes are not in
480  // collision, i.e their distance is above GJK's tolerance (default
481  // 1e-6).
482  GJKExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
483  HPP_FCL_ASSERT(std::abs((p1 - p2).norm() - distance) <=
484  this->gjk.getTolerance() + this->m_dummy_precision,
485  "The distance found by GJK should coincide with the "
486  "distance between the closest points.",
487  std::logic_error);
488  break;
489  //
490  // Next are the cases where GJK found the shapes to be in collision, i.e.
491  // their distance is below GJK's tolerance (default 1e-6).
493  GJKExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
495  distance <= this->gjk.getTolerance() + this->m_dummy_precision,
496  "The distance found by GJK should be negative or at "
497  "least below GJK's tolerance.",
498  std::logic_error);
499  break;
501  if (!compute_penetration) {
502  // Skip EPA and set the witness points and the normal to nans.
503  GJKCollisionExtractWitnessPointsAndNormal(tf1, distance, p1, p2,
504  normal);
505  } else {
506  //
507  // GJK was not enough to recover the penetration information.
508  // We need to run the EPA algorithm to find the witness points,
509  // penetration depth and the normal.
510 
511  // Reset EPA algorithm. Potentially allocate memory if
512  // `epa_max_face_num` or `epa_max_vertex_num` are bigger than EPA's
513  // current storage.
514  this->epa.reset(this->epa_max_iterations, this->epa_tolerance);
515 
516  // TODO: understand why EPA's performance is so bad on cylinders and
517  // cones.
518  this->epa.evaluate(this->gjk, -guess);
519 
520  switch (epa.status) {
521  //
522  // In the following switch cases, until the "Valid" case,
523  // EPA either ran out of iterations, of faces or of vertices.
524  // The depth, witness points and the normal are still valid,
525  // simply not at the precision of EPA's tolerance.
526  // The flag `HPP_FCL_ENABLE_LOGGING` enables feebdack on these
527  // cases.
528  //
529  // TODO: Remove OutOfFaces and OutOfVertices statuses and simply
530  // compute the upper bound on max faces and max vertices as a
531  // function of the number of iterations.
533  HPP_FCL_LOG_WARNING("EPA ran out of faces.");
534  EPAExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
535  break;
537  HPP_FCL_LOG_WARNING("EPA ran out of vertices.");
538  EPAExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
539  break;
541  HPP_FCL_LOG_WARNING("EPA ran out of iterations.");
542  EPAExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
543  break;
544  case details::EPA::Valid:
547  -epa.depth <= epa.getTolerance() + this->m_dummy_precision,
548  "EPA's penetration distance should be negative (or "
549  "at least below EPA's tolerance).",
550  std::logic_error);
551  EPAExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
552  break;
555  "EPA warning: created a polytope with a degenerated face.");
556  EPAExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
557  break;
560  "EPA warning: EPA got called onto non-convex shapes.");
561  EPAExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
562  break;
564  HPP_FCL_LOG_WARNING("EPA warning: created an invalid polytope.");
565  EPAExtractWitnessPointsAndNormal(tf1, distance, p1, p2, normal);
566  break;
568  HPP_FCL_ASSERT(false, "EPA did not run. It should have!",
569  std::logic_error);
570  HPP_FCL_LOG_ERROR("EPA error: did not run. It should have.");
571  EPAFailedExtractWitnessPointsAndNormal(tf1, distance, p1, p2,
572  normal);
573  break;
576  false,
577  "EPA went into fallback mode. It should never do that.",
578  std::logic_error);
579  HPP_FCL_LOG_ERROR("EPA error: FallBack.");
580  EPAFailedExtractWitnessPointsAndNormal(tf1, distance, p1, p2,
581  normal);
582  break;
583  }
584  }
585  break; // End of case details::GJK::Collision
586  }
587  }
588 
590  FCL_REAL& distance, Vec3f& p1,
591  Vec3f& p2,
592  Vec3f& normal) const {
594  // Cache gjk result for potential future call to this GJKSolver.
595  this->cached_guess = this->gjk.ray;
596  this->support_func_cached_guess = this->gjk.support_hint;
597 
598  distance = this->gjk.distance;
599  p1 = p2 = normal =
600  Vec3f::Constant(std::numeric_limits<FCL_REAL>::quiet_NaN());
601  // If we absolutely want to return some witness points, we could use
602  // the following code (or simply merge the early stopped case with the
603  // valid case below):
604  // gjk.getWitnessPointsAndNormal(minkowski_difference, p1, p2, normal);
605  // p1 = tf1.transform(p1);
606  // p2 = tf1.transform(p2);
607  // normal = tf1.getRotation() * normal;
608  }
609 
611  FCL_REAL& distance, Vec3f& p1,
612  Vec3f& p2, Vec3f& normal) const {
613  // Apart from early stopping, there are two cases where GJK says there is no
614  // collision:
615  // 1. GJK proved the distance is above its tolerance (default 1e-6).
616  // 2. GJK ran out of iterations.
617  // In any case, `gjk.ray`'s norm is bigger than GJK's tolerance and thus
618  // it can safely be normalized.
620  this->gjk.ray.norm() >
621  this->gjk.getTolerance() - this->m_dummy_precision,
622  "The norm of GJK's ray should be bigger than GJK's tolerance.",
623  std::logic_error);
624  // Cache gjk result for potential future call to this GJKSolver.
625  this->cached_guess = this->gjk.ray;
626  this->support_func_cached_guess = this->gjk.support_hint;
627 
628  distance = this->gjk.distance;
629  // TODO: On degenerated case, the closest points may be non-unique.
630  // (i.e. an object face normal is colinear to `gjk.ray`)
631  gjk.getWitnessPointsAndNormal(this->minkowski_difference, p1, p2, normal);
632  Vec3f p = tf1.transform(0.5 * (p1 + p2));
633  normal = tf1.getRotation() * normal;
634  p1.noalias() = p - 0.5 * distance * normal;
635  p2.noalias() = p + 0.5 * distance * normal;
636  }
637 
639  FCL_REAL& distance, Vec3f& p1,
640  Vec3f& p2,
641  Vec3f& normal) const {
643  HPP_FCL_ASSERT(this->gjk.distance <=
644  this->gjk.getTolerance() + this->m_dummy_precision,
645  "The distance should be lower than GJK's tolerance.",
646  std::logic_error);
647  // Because GJK has returned the `Collision` status and EPA has not run,
648  // we purposefully do not cache the result of GJK, because ray is zero.
649  // However, we can cache the support function hint.
650  // this->cached_guess = this->gjk.ray;
651  this->support_func_cached_guess = this->gjk.support_hint;
652 
653  distance = this->gjk.distance;
654  p1 = p2 = normal =
655  Vec3f::Constant(std::numeric_limits<FCL_REAL>::quiet_NaN());
656  }
657 
659  FCL_REAL& distance, Vec3f& p1,
660  Vec3f& p2, Vec3f& normal) const {
661  // Cache EPA result for potential future call to this GJKSolver.
662  // This caching allows to warm-start the next GJK call.
663  this->cached_guess = -(this->epa.depth * this->epa.normal);
664  this->support_func_cached_guess = this->epa.support_hint;
665  distance = (std::min)(0., -this->epa.depth);
666  this->epa.getWitnessPointsAndNormal(this->minkowski_difference, p1, p2,
667  normal);
668  // The following is very important to understand why EPA can sometimes
669  // return a normal that is not colinear to the vector $p_1 - p_2$ when
670  // working with tolerances like $\epsilon = 10^{-3}$.
671  // It can be resumed with a simple idea:
672  // EPA is an algorithm meant to find the penetration depth and the
673  // normal. It is not meant to find the closest points.
674  // Again, the issue here is **not** the normal, it's $p_1$ and $p_2$.
675  //
676  // More details:
677  // We'll denote $S_1$ and $S_2$ the two shapes, $n$ the normal and $p_1$ and
678  // $p_2$ the witness points. In theory, when EPA converges to $\epsilon =
679  // 0$, the normal and witness points verify the following property (P):
680  // - $p_1 \in \partial \sigma_{S_1}(n)$,
681  // - $p_2 \in \partial \sigma_{S_2}(-n),
682  // where $\sigma_{S_1}$ and $\sigma_{S_2}$ are the support functions of
683  // $S_1$ and $S_2$. The $\partial \sigma(n)$ simply denotes the support set
684  // of the support function in the direction $n$. (Note: I am leaving out the
685  // details of frame choice for the support function, to avoid making the
686  // mathematical notation too heavy.)
687  // --> In practice, EPA converges to $\epsilon > 0$.
688  // On polytopes and the likes, this does not change much and the property
689  // given above is still valid.
690  // --> However, this is very different on curved surfaces, such as
691  // ellipsoids, cylinders, cones, capsules etc. For these shapes, converging
692  // at $\epsilon = 10^{-6}$ or to $\epsilon = 10^{-3}$ does not change the
693  // normal much, but the property (P) given above is no longer valid, which
694  // means that the points $p_1$ and $p_2$ do not necessarily belong to the
695  // support sets in the direction of $n$ and thus $n$ and $p_1 - p_2$ are not
696  // colinear.
697  //
698  // Do not panic! This is fine.
699  // Although the property above is not verified, it's almost verified,
700  // meaning that $p_1$ and $p_2$ belong to support sets in directions that
701  // are very close to $n$.
702  //
703  // Solution to compute better $p_1$ and $p_2$:
704  // We compute the middle points of the current $p_1$ and $p_2$ and we use
705  // the normal and the distance given by EPA to compute the new $p_1$ and
706  // $p_2$.
707  Vec3f p = tf1.transform(0.5 * (p1 + p2));
708  normal = tf1.getRotation() * normal;
709  p1.noalias() = p - 0.5 * distance * normal;
710  p2.noalias() = p + 0.5 * distance * normal;
711  }
712 
714  FCL_REAL& distance, Vec3f& p1,
715  Vec3f& p2, Vec3f& normal) const {
716  this->cached_guess = Vec3f(1, 0, 0);
717  this->support_func_cached_guess.setZero();
718 
720  distance = -(std::numeric_limits<FCL_REAL>::max)();
721  p1 = p2 = normal =
722  Vec3f::Constant(std::numeric_limits<FCL_REAL>::quiet_NaN());
723  }
724 };
725 
726 } // namespace fcl
727 } // namespace hpp
728 
729 #endif
Simple transform class used locally by InterpMotion.
Definition: transform.h:56
const Matrix3f & getRotation() const
get rotation
Definition: transform.h:111
Transform3f inverseTimes(const Transform3f &other) const
inverse the transform and multiply with another
Definition: transform.h:176
Vec3f transform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the transform
Definition: transform.h:153
Triangle stores the points instead of only indices of points.
Definition: geometric_shapes.h:109
#define HPP_FCL_DLLAPI
Definition: config.hh:88
#define HPP_FCL_DEPRECATED_MESSAGE(message)
Definition: deprecated.hh:38
#define HPP_FCL_ASSERT(check, message, exception)
Definition: fwd.hh:82
#define HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
Definition: fwd.hh:122
#define HPP_FCL_COMPILER_DIAGNOSTIC_PUSH
Definition: fwd.hh:120
#define HPP_FCL_COMPILER_DIAGNOSTIC_POP
Definition: fwd.hh:121
#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.
Vec3f c
Definition: geometric_shapes.h:147
Vec3f a
Definition: geometric_shapes.h:147
Vec3f b
Definition: geometric_shapes.h:147
#define HPP_FCL_LOG_WARNING(message)
Definition: logging.h:50
#define HPP_FCL_LOG_ERROR(message)
Definition: logging.h:51
@ NoSweptSphere
Definition: support_functions.h:60
GJKVariant
Variant to use for the GJK algorithm.
Definition: data_types.h:88
@ DefaultGJK
Definition: data_types.h:88
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:67
GJKConvergenceCriterionType
Wether the convergence criterion is scaled on the norm of the solution or not.
Definition: data_types.h:98
@ Absolute
Definition: data_types.h:98
GJKConvergenceCriterion
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision)....
Definition: data_types.h:94
@ Default
Definition: data_types.h:94
GJKInitialGuess
Initial guess to use for the GJK algorithm DefaultGuess: Vec3f(1, 0, 0) CachedGuess: previous vector ...
Definition: data_types.h:85
@ BoundingVolumeGuess
Definition: data_types.h:85
@ CachedGuess
Definition: data_types.h:85
@ DefaultGuess
Definition: data_types.h:85
constexpr size_t GJK_DEFAULT_MAX_ITERATIONS
GJK.
Definition: narrowphase_defaults.h:47
constexpr size_t EPA_DEFAULT_MAX_ITERATIONS
Definition: narrowphase_defaults.h:60
constexpr FCL_REAL EPA_DEFAULT_TOLERANCE
Definition: narrowphase_defaults.h:61
constexpr FCL_REAL GJK_DEFAULT_TOLERANCE
Definition: narrowphase_defaults.h:48
double FCL_REAL
Definition: data_types.h:66
Eigen::Vector2i support_func_guess_t
Definition: data_types.h:77
Main namespace.
Definition: broadphase_bruteforce.h:44
request to the collision algorithm
Definition: collision_data.h:312
FCL_REAL distance_upper_bound
Distance above which GJK solver makes an early stopping. GJK stops searching for the closest points w...
Definition: collision_data.h:341
FCL_REAL security_margin
Distance below which objects are considered in collision. See Collision.
Definition: collision_data.h:329
request to the distance computation
Definition: collision_data.h:987
collision and distance solver based on the GJK and EPA algorithms. Originally, GJK and EPA were imple...
Definition: narrowphase.h:58
void GJKExtractWitnessPointsAndNormal(const Transform3f &tf1, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
Definition: narrowphase.h:610
GJKConvergenceCriterion gjk_convergence_criterion
Convergence criterion for GJK.
Definition: narrowphase.h:93
FCL_REAL shapeDistance(const S1 &s1, const Transform3f &tf1, const TriangleP &s2, const Transform3f &tf2, const bool compute_penetration, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
Partial specialization of shapeDistance for the case where the second shape is a triangle....
Definition: narrowphase.h:323
void EPAFailedExtractWitnessPointsAndNormal(const Transform3f &tf1, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
Definition: narrowphase.h:713
void set(const DistanceRequest &request)
setter from a DistanceRequest
Definition: narrowphase.h:162
GJKVariant gjk_variant
Variant of the GJK algorithm (Default, Nesterov or Polyak).
Definition: narrowphase.h:90
GJKSolver(const GJKSolver &other)=default
Copy constructor.
GJKInitialGuess gjk_initial_guess
which warm start to use for GJK
Definition: narrowphase.h:72
void runGJKAndEPA(const S1 &s1, const Transform3f &tf1, const S2 &s2, const Transform3f &tf2, const bool compute_penetration, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal, const bool relative_transformation_already_computed=false) const
Runs the GJK algorithm.
Definition: narrowphase.h:422
void GJKEarlyStopExtractWitnessPointsAndNormal(const Transform3f &tf1, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
Definition: narrowphase.h:589
FCL_REAL shapeDistance(const TriangleP &s1, const Transform3f &tf1, const S2 &s2, const Transform3f &tf2, const bool compute_penetration, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
See other partial template specialization of shapeDistance above.
Definition: narrowphase.h:340
bool operator!=(const GJKSolver &other) const
Definition: narrowphase.h:269
bool operator==(const GJKSolver &other) const
Definition: narrowphase.h:251
FCL_REAL distance_upper_bound
If GJK can guarantee that the distance between the shapes is greater than this value,...
Definition: narrowphase.h:87
GJKSolver(const CollisionRequest &request)
Constructor from a CollisionRequest.
Definition: narrowphase.h:201
FCL_REAL gjk_tolerance
tolerance of GJK
Definition: narrowphase.h:69
FCL_REAL getDistancePrecision(const bool compute_penetration) const
Helper to return the precision of the solver on the distance estimate, depending on whether or not co...
Definition: narrowphase.h:273
void EPAExtractWitnessPointsAndNormal(const Transform3f &tf1, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
Definition: narrowphase.h:658
void getGJKInitialGuess(const S1 &s1, const S2 &s2, Vec3f &guess, support_func_guess_t &support_hint, const Vec3f &default_guess=Vec3f(1, 0, 0)) const
initialize GJK. This method assumes minkowski_difference has been set.
Definition: narrowphase.h:354
Vec3f cached_guess
smart guess
Definition: narrowphase.h:80
GJKConvergenceCriterionType gjk_convergence_criterion_type
Absolute or relative convergence criterion for GJK.
Definition: narrowphase.h:96
bool enable_cached_guess
Whether smart guess can be provided @Deprecated Use gjk_initial_guess instead.
Definition: narrowphase.h:77
GJKSolver(const DistanceRequest &request)
Constructor from a DistanceRequest.
Definition: narrowphase.h:149
FCL_REAL epa_tolerance
tolerance of EPA
Definition: narrowphase.h:105
void set(const CollisionRequest &request)
setter from a CollisionRequest
Definition: narrowphase.h:214
size_t gjk_max_iterations
maximum number of iterations of GJK
Definition: narrowphase.h:66
void GJKCollisionExtractWitnessPointsAndNormal(const Transform3f &tf1, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
Definition: narrowphase.h:638
size_t epa_max_iterations
maximum number of iterations of EPA
Definition: narrowphase.h:102
FCL_REAL shapeDistance(const S1 &s1, const Transform3f &tf1, const S2 &s2, const Transform3f &tf2, const bool compute_penetration, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
Uses GJK and EPA to compute the distance between two shapes.
Definition: narrowphase.h:309
support_func_guess_t support_func_cached_guess
smart guess for the support function
Definition: narrowphase.h:83
EIGEN_MAKE_ALIGNED_OPERATOR_NEW details::GJK gjk
GJK algorithm.
Definition: narrowphase.h:63
GJKVariant gjk_variant
whether to enable the Nesterov accleration of GJK
Definition: collision_data.h:196
Vec3f cached_gjk_guess
the gjk initial guess set by user
Definition: collision_data.h:181
GJKInitialGuess gjk_initial_guess
Definition: collision_data.h:173
GJKConvergenceCriterion gjk_convergence_criterion
convergence criterion used to stop GJK
Definition: collision_data.h:199
size_t gjk_max_iterations
maximum iteration for the GJK algorithm
Definition: collision_data.h:187
support_func_guess_t cached_support_func_guess
the support function initial guess set by user
Definition: collision_data.h:184
FCL_REAL gjk_tolerance
tolerance for the GJK algorithm. Note: This tolerance determines the precision on the estimated dista...
Definition: collision_data.h:193
size_t epa_max_iterations
max number of iterations for EPA
Definition: collision_data.h:205
FCL_REAL epa_tolerance
tolerance for EPA. Note: This tolerance determines the precision on the estimated distance between tw...
Definition: collision_data.h:212
bool enable_cached_gjk_guess
whether enable gjk initial guess @Deprecated Use gjk_initial_guess instead
Definition: collision_data.h:178
GJKConvergenceCriterionType gjk_convergence_criterion_type
convergence criterion used to stop GJK
Definition: collision_data.h:202
@ NonConvex
Definition: gjk.h:336
@ Degenerated
Definition: gjk.h:335
@ Valid
Definition: gjk.h:333
@ DidNotRun
Definition: gjk.h:331
@ FallBack
Definition: gjk.h:340
@ Failed
Definition: gjk.h:332
@ AccuracyReached
Definition: gjk.h:334
@ InvalidHull
Definition: gjk.h:337
@ OutOfVertices
Definition: gjk.h:339
@ OutOfFaces
Definition: gjk.h:338
class for GJK algorithm
Definition: gjk.h:54
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:195
support_func_guess_t support_hint
Definition: gjk.h:113
FCL_REAL distance_upper_bound
Definition: gjk.h:105
void getWitnessPointsAndNormal(const MinkowskiDiff &shape, Vec3f &w0, Vec3f &w1, Vec3f &normal) const
FCL_REAL getTolerance() const
Get the tolerance of GJK.
Definition: gjk.h:208
@ CollisionWithPenetrationInformation
Definition: gjk.h:100
@ DidNotRun
Definition: gjk.h:96
@ Collision
Definition: gjk.h:101
@ NoCollisionEarlyStopped
Definition: gjk.h:98
@ Failed
Definition: gjk.h:97
@ NoCollision
Definition: gjk.h:99
GJKConvergenceCriterion convergence_criterion
Definition: gjk.h:108
void reset(size_t max_iterations_, FCL_REAL tolerance_)
resets the GJK algorithm, preparing it for a new run. Other than the maximum number of iterations and...
GJKConvergenceCriterionType convergence_criterion_type
Definition: gjk.h:109
FCL_REAL distance
The distance between the two shapes, computed by GJK. If the distance is below GJK's threshold,...
Definition: gjk.h:119
Vec3f ray
Definition: gjk.h:112
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.
GJKVariant gjk_variant
Definition: gjk.h:107
Status status
Definition: gjk.h:106