Struct GJKSolver
Defined in File narrowphase.h
Struct Documentation
-
struct GJKSolver
collision and distance solver based on the GJK and EPA algorithms. Originally, GJK and EPA were implemented in fcl which itself took inspiration from the code of the GJK in bullet. Since then, both GJK and EPA have been largely modified to be faster and more robust to numerical accuracy and edge cases.
Public Functions
- inline COAL_COMPILER_DIAGNOSTIC_PUSH COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GJKSolver ()
Default constructor for GJK algorithm By default, we don’t want EPA to allocate memory because certain functions of the
GJKSolver
class have specializations which don’t use EPA (and/or GJK). So we give EPA’s constructor a max number of iterations of zero. Only the functions that need EPA will reset the algorithm and allocate memory if needed.
-
inline explicit GJKSolver(const DistanceRequest &request)
Constructor from a DistanceRequest.
See the default constructor; by default, we don’t want EPA to allocate memory so we call EPA’s constructor with 0 max number of iterations. However, the
set
method stores the actual values of the request. EPA will thus allocate memory only if needed.- Parameters:
request – [in] DistanceRequest input
-
inline void set(const DistanceRequest &request)
setter from a DistanceRequest
- Parameters:
request – [in] DistanceRequest input
-
inline explicit GJKSolver(const CollisionRequest &request)
Constructor from a CollisionRequest.
See the default constructor; by default, we don’t want EPA to allocate memory so we call EPA’s constructor with 0 max number of iterations. However, the
set
method stores the actual values of the request. EPA will thus allocate memory only if needed.- Parameters:
request – [in] CollisionRequest input
-
inline void set(const CollisionRequest &request)
setter from a CollisionRequest
- Parameters:
request – [in] CollisionRequest input
- inline COAL_COMPILER_DIAGNOSTIC_PUSH COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS bool operator== (const GJKSolver &other) const
- inline COAL_COMPILER_DIAGNOSTIC_POP bool operator!= (const GJKSolver &other) const
-
inline CoalScalar getDistancePrecision(const bool compute_penetration) const
Helper to return the precision of the solver on the distance estimate, depending on whether or not
compute_penetration
is true.
-
template<typename S1, typename S2>
inline CoalScalar shapeDistance(const S1 &s1, const Transform3s &tf1, const S2 &s2, const Transform3s &tf2, const bool compute_penetration, Vec3s &p1, Vec3s &p2, Vec3s &normal) const Uses GJK and EPA to compute the distance between two shapes.
Note
: if
this->distance_upper_bound
is set to a positive value, GJK will early stop if it finds the distance to be above this value. The distance returned bythis->shapeDistance
will be a lower bound on the distance between the two shapes.Note
: the variables
this->gjk.status
andthis->epa.status
can be used to examine the status of GJK and EPA.Note
: GJK and EPA give an estimate of the distance between the two shapes. This estimate is precise up to the tolerance of the algorithms:
If
compute_penetration
is false, the distance is precise up togjk_tolerance
.If
compute_penetration
is true, the distance is precise up tostd::max(gjk_tolerance, epa_tolerance)
It’s up to the user to decide whether the shapes are in collision or not, based on that estimate.
- Parameters:
`s1` – the first shape.
`tf1` – the transformation of the first shape.
`s2` – the second shape.
`tf2` – the transformation of the second shape.
`compute_penetration` – if true and GJK finds the shape in collision, the EPA algorithm is also ran to compute penetration information.
`p1` – [out] the witness point on the first shape.
`p2` – [out] the witness point on the second shape.
`normal` – [out] the normal of the collision, pointing from the first to the second shape.
- Returns:
the estimate of the distance between the two shapes.
-
template<typename S1>
inline CoalScalar shapeDistance(const S1 &s1, const Transform3s &tf1, const TriangleP &s2, const Transform3s &tf2, const bool compute_penetration, Vec3s &p1, Vec3s &p2, Vec3s &normal) const Partial specialization of
shapeDistance
for the case where the second shape is a triangle. It is more efficient to pre-compute the relative transformation between the two shapes before calling GJK/EPA.
-
template<typename S2>
inline CoalScalar shapeDistance(const TriangleP &s1, const Transform3s &tf1, const S2 &s2, const Transform3s &tf2, const bool compute_penetration, Vec3s &p1, Vec3s &p2, Vec3s &normal) const See other partial template specialization of shapeDistance above.
Public Members
- mutable EIGEN_MAKE_ALIGNED_OPERATOR_NEW details::GJK gjk
GJK algorithm.
-
size_t gjk_max_iterations
maximum number of iterations of GJK
-
CoalScalar gjk_tolerance
tolerance of GJK
-
GJKInitialGuess gjk_initial_guess
which warm start to use for GJK
-
bool enable_cached_guess
Whether smart guess can be provided @Deprecated Use gjk_initial_guess instead.
-
mutable support_func_guess_t support_func_cached_guess
smart guess for the support function
-
CoalScalar distance_upper_bound
If GJK can guarantee that the distance between the shapes is greater than this value, it will early stop.
-
GJKVariant gjk_variant
Variant of the GJK algorithm (Default, Nesterov or Polyak).
-
GJKConvergenceCriterion gjk_convergence_criterion
Convergence criterion for GJK.
-
GJKConvergenceCriterionType gjk_convergence_criterion_type
Absolute or relative convergence criterion for GJK.
-
size_t epa_max_iterations
maximum number of iterations of EPA
-
CoalScalar epa_tolerance
tolerance of EPA
-
mutable details::MinkowskiDiff minkowski_difference
Minkowski difference used by GJK and EPA algorithms.
Protected Functions
-
template<typename S1, typename S2>
inline void getGJKInitialGuess(const S1 &s1, const S2 &s2, Vec3s &guess, support_func_guess_t &support_hint, const Vec3s &default_guess = Vec3s(1, 0, 0)) const initialize GJK. This method assumes
minkowski_difference
has been set.
-
template<typename S1, typename S2, int _SupportOptions = details::SupportOptions::NoSweptSphere>
inline void runGJKAndEPA(const S1 &s1, const Transform3s &tf1, const S2 &s2, const Transform3s &tf2, const bool compute_penetration, CoalScalar &distance, Vec3s &p1, Vec3s &p2, Vec3s &normal, const bool relative_transformation_already_computed = false) const Runs the GJK algorithm.
Note
: The variables
this->gjk.status
andthis->epa.status
can be used to examine the status of GJK and EPA.- Parameters:
`s1` – the first shape.
`tf1` – the transformation of the first shape.
`s2` – the second shape.
`tf2` – the transformation of the second shape.
`compute_penetration` – if true and if the shapes are in found in collision, the EPA algorithm is also ran to compute penetration information.
`distance` – [out] the distance between the two shapes.
`p1` – [out] the witness point on the first shape.
`p2` – [out] the witness point on the second shape.
`normal` – [out] the normal of the collision, pointing from the first to the second shape.
`relative_transformation_already_computed` – whether the relative transformation between the two shapes has already been computed.
- Template Parameters:
SupportOptions, see –
MinkowskiDiff::set
. Whether the support computations should take into account the shapes’ swept-sphere radii during the iterations of GJK and EPA. Please leave this default value tofalse
unless you know what you are doing. This template parameter is only used for debugging/testing purposes. In short, there is no need to take into account the swept sphere radius when computing supports in the iterations of GJK and EPA. GJK and EPA will correct the solution once they have converged.- Returns:
the estimate of the distance between the two shapes.
-
inline void GJKEarlyStopExtractWitnessPointsAndNormal(const Transform3s &tf1, CoalScalar &distance, Vec3s &p1, Vec3s &p2, Vec3s &normal) const
-
inline void GJKExtractWitnessPointsAndNormal(const Transform3s &tf1, CoalScalar &distance, Vec3s &p1, Vec3s &p2, Vec3s &normal) const
-
inline void GJKCollisionExtractWitnessPointsAndNormal(const Transform3s &tf1, CoalScalar &distance, Vec3s &p1, Vec3s &p2, Vec3s &normal) const
-
inline void EPAExtractWitnessPointsAndNormal(const Transform3s &tf1, CoalScalar &distance, Vec3s &p1, Vec3s &p2, Vec3s &normal) const
-
inline void EPAFailedExtractWitnessPointsAndNormal(const Transform3s &tf1, CoalScalar &distance, Vec3s &p1, Vec3s &p2, Vec3s &normal) const