Public Types | Public Member Functions | Public Attributes | List of all members
hpp::fcl::GJKSolver Struct Reference

collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the GJK in bullet) More...

#include <narrowphase.h>

Public Types

typedef Eigen::Array< FCL_REAL, 1, 2 > Array2d
 

Public Member Functions

HPP_FCL_COMPILER_DIAGNOSTIC_PUSH HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GJKSolver ()
 Default constructor for GJK algorithm. More...
 
 GJKSolver (const CollisionRequest &request)
 Constructor from a CollisionRequest. More...
 
 GJKSolver (const DistanceRequest &request)
 Constructor from a DistanceRequest. More...
 
 GJKSolver (const GJKSolver &other)=default
 Copy constructor. More...
 
template<typename S1 , typename S2 >
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 More...
 
HPP_FCL_COMPILER_DIAGNOSTIC_POP bool operator!= (const GJKSolver &other) const
 
HPP_FCL_COMPILER_DIAGNOSTIC_PUSH HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS bool operator== (const GJKSolver &other) const
 
void set (const CollisionRequest &request)
 setter from a CollisionRequest More...
 
void set (const DistanceRequest &request)
 setter from a DistanceRequest More...
 
template<>
bool shapeDistance (const Box &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
 
template<>
bool shapeDistance (const Capsule &, const Transform3f &, const Capsule &, const Transform3f &, FCL_REAL &, Vec3f &, Vec3f &, Vec3f &) const
 
template<>
bool shapeDistance (const Capsule &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
 
template<>
bool shapeDistance (const Cylinder &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
 
template<typename S1 , typename S2 >
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 More...
 
template<>
bool shapeDistance (const Sphere &s1, const Transform3f &tf1, const Box &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
 
template<>
bool shapeDistance (const Sphere &s1, const Transform3f &tf1, const Capsule &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
 
template<>
bool shapeDistance (const Sphere &s1, const Transform3f &tf1, const Cylinder &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
 
template<>
bool shapeDistance (const Sphere &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
 
template<>
bool shapeDistance (const TriangleP &s1, const Transform3f &tf1, const TriangleP &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
 
template<>
bool shapeIntersect (const Box &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Box &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Box &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Capsule &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Capsule &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Cone &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Cone &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Cylinder &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Cylinder &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Halfspace &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *, Vec3f *) const
 
template<>
bool shapeIntersect (const Plane &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *, Vec3f *) const
 
template<>
bool shapeIntersect (const Plane &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<typename S1 , typename S2 >
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 More...
 
template<>
bool shapeIntersect (const Sphere &s1, const Transform3f &tf1, const Capsule &s2, const Transform3f &tf2, FCL_REAL &distance_lower_bound, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Sphere &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Sphere &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
bool shapeIntersect (const Sphere &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL &distance_lower_bound, bool, Vec3f *contact_points, Vec3f *normal) const
 
template<>
HPP_FCL_DLLAPI bool shapeTriangleInteraction (const Halfspace &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
 
template<>
HPP_FCL_DLLAPI bool shapeTriangleInteraction (const Plane &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
 
template<typename S >
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 More...
 
template<>
HPP_FCL_DLLAPI bool shapeTriangleInteraction (const Sphere &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
 
Shape intersection specializations
template<>
HPP_FCL_DLLAPI bool shapeIntersect (const Box &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL &distance_lower_bound, bool enable_penetration, Vec3f *contact_points, Vec3f *normal) const
 

Public Attributes

Vec3f cached_guess
 smart guess More...
 
FCL_REAL distance_upper_bound
 Distance above which the GJK solver stoppes its computations and processes to an early stopping. The two witness points are incorrect, but with the guaranty that the two shapes have a distance greather than distance_upper_bound. More...
 
bool enable_cached_guess
 Whether smart guess can be provided @Deprecated Use gjk_initial_guess instead. More...
 
unsigned int epa_max_face_num
 maximum number of simplex face used in EPA algorithm More...
 
unsigned int epa_max_iterations
 maximum number of iterations used for EPA iterations More...
 
unsigned int epa_max_vertex_num
 maximum number of simplex vertex used in EPA algorithm More...
 
FCL_REAL epa_tolerance
 the threshold used in EPA to stop iteration More...
 
GJKConvergenceCriterion gjk_convergence_criterion
 Criterion used to stop GJK. More...
 
GJKConvergenceCriterionType gjk_convergence_criterion_type
 Relative or absolute. More...
 
GJKInitialGuess gjk_initial_guess
 which warm start to use for GJK More...
 
size_t gjk_max_iterations
 maximum number of iterations used for GJK iterations More...
 
FCL_REAL gjk_tolerance
 the threshold used in GJK to stop iteration More...
 
GJKVariant gjk_variant
 Variant to use for the GJK algorithm. More...
 
support_func_guess_t support_func_cached_guess
 smart guess for the support function More...
 

Detailed Description

collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the GJK in bullet)

Definition at line 54 of file narrowphase.h.

Member Typedef Documentation

◆ Array2d

typedef Eigen::Array<FCL_REAL, 1, 2> hpp::fcl::GJKSolver::Array2d

Definition at line 55 of file narrowphase.h.

Constructor & Destructor Documentation

◆ GJKSolver() [1/4]

Default constructor for GJK algorithm.

Definition at line 350 of file narrowphase.h.

◆ GJKSolver() [2/4]

hpp::fcl::GJKSolver::GJKSolver ( const DistanceRequest request)
inline

Constructor from a DistanceRequest.

Parameters
[in]requestDistanceRequest input

Definition at line 371 of file narrowphase.h.

◆ GJKSolver() [3/4]

hpp::fcl::GJKSolver::GJKSolver ( const CollisionRequest request)
inline

Constructor from a CollisionRequest.

Parameters
[in]requestCollisionRequest input

Definition at line 409 of file narrowphase.h.

◆ GJKSolver() [4/4]

hpp::fcl::GJKSolver::GJKSolver ( const GJKSolver other)
default

Copy constructor.

Member Function Documentation

◆ initialize_gjk()

template<typename S1 , typename S2 >
void hpp::fcl::GJKSolver::initialize_gjk ( details::GJK gjk,
const details::MinkowskiDiff shape,
const S1 &  s1,
const S2 &  s2,
Vec3f guess,
support_func_guess_t support_hint 
) const
inline

initialize GJK

Definition at line 59 of file narrowphase.h.

◆ operator!=()

HPP_FCL_COMPILER_DIAGNOSTIC_POP bool hpp::fcl::GJKSolver::operator!= ( const GJKSolver other) const
inline

Definition at line 473 of file narrowphase.h.

◆ operator==()

HPP_FCL_COMPILER_DIAGNOSTIC_PUSH HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS bool hpp::fcl::GJKSolver::operator== ( const GJKSolver other) const
inline

Definition at line 453 of file narrowphase.h.

◆ set() [1/2]

void hpp::fcl::GJKSolver::set ( const CollisionRequest request)
inline

setter from a CollisionRequest

Parameters
[in]requestCollisionRequest input

Definition at line 427 of file narrowphase.h.

◆ set() [2/2]

void hpp::fcl::GJKSolver::set ( const DistanceRequest request)
inline

setter from a DistanceRequest

Parameters
[in]requestDistanceRequest input

Definition at line 389 of file narrowphase.h.

◆ shapeDistance() [1/10]

template<>
bool hpp::fcl::GJKSolver::shapeDistance ( const Box s1,
const Transform3f tf1,
const Sphere s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
) const

Definition at line 404 of file narrowphase.cpp.

◆ shapeDistance() [2/10]

template<>
bool hpp::fcl::GJKSolver::shapeDistance ( const Capsule ,
const Transform3f ,
const Capsule ,
const Transform3f ,
FCL_REAL ,
Vec3f ,
Vec3f ,
Vec3f  
) const

Definition at line 455 of file narrowphase.cpp.

◆ shapeDistance() [3/10]

template<>
bool hpp::fcl::GJKSolver::shapeDistance ( const Capsule s1,
const Transform3f tf1,
const Sphere s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
) const

Definition at line 394 of file narrowphase.cpp.

◆ shapeDistance() [4/10]

template<>
bool hpp::fcl::GJKSolver::shapeDistance ( const Cylinder s1,
const Transform3f tf1,
const Sphere s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
) const

Definition at line 436 of file narrowphase.cpp.

◆ shapeDistance() [5/10]

template<typename S1 , typename S2 >
bool hpp::fcl::GJKSolver::shapeDistance ( const S1 &  s1,
const Transform3f tf1,
const S2 &  s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
) const
inline

distance computation between two shapes

Definition at line 261 of file narrowphase.h.

◆ shapeDistance() [6/10]

template<>
bool hpp::fcl::GJKSolver::shapeDistance ( const Sphere s1,
const Transform3f tf1,
const Box s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
) const

Definition at line 414 of file narrowphase.cpp.

◆ shapeDistance() [7/10]

template<>
bool hpp::fcl::GJKSolver::shapeDistance ( const Sphere s1,
const Transform3f tf1,
const Capsule s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
) const

Definition at line 384 of file narrowphase.cpp.

◆ shapeDistance() [8/10]

template<>
bool hpp::fcl::GJKSolver::shapeDistance ( const Sphere s1,
const Transform3f tf1,
const Cylinder s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
) const

Definition at line 427 of file narrowphase.cpp.

◆ shapeDistance() [9/10]

template<>
bool hpp::fcl::GJKSolver::shapeDistance ( const Sphere s1,
const Transform3f tf1,
const Sphere s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
) const

Definition at line 445 of file narrowphase.cpp.

◆ shapeDistance() [10/10]

template<>
bool hpp::fcl::GJKSolver::shapeDistance ( const TriangleP s1,
const Transform3f tf1,
const TriangleP s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
) const

Definition at line 463 of file narrowphase.cpp.

◆ shapeIntersect() [1/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Box s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 157 of file narrowphase.cpp.

◆ shapeIntersect() [2/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Box s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 263 of file narrowphase.cpp.

◆ shapeIntersect() [3/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Box s1,
const Transform3f tf1,
const Sphere s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 114 of file narrowphase.cpp.

◆ shapeIntersect() [4/18]

template<>
HPP_FCL_DLLAPI bool hpp::fcl::GJKSolver::shapeIntersect ( const Box s1,
const Transform3f tf1,
const Sphere s2,
const Transform3f tf2,
FCL_REAL distance_lower_bound,
bool  enable_penetration,
Vec3f contact_points,
Vec3f normal 
) const

◆ shapeIntersect() [5/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Capsule s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 172 of file narrowphase.cpp.

◆ shapeIntersect() [6/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Capsule s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 277 of file narrowphase.cpp.

◆ shapeIntersect() [7/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Cone s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 202 of file narrowphase.cpp.

◆ shapeIntersect() [8/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Cone s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 307 of file narrowphase.cpp.

◆ shapeIntersect() [9/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Cylinder s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 187 of file narrowphase.cpp.

◆ shapeIntersect() [10/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Cylinder s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 292 of file narrowphase.cpp.

◆ shapeIntersect() [11/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Halfspace s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f ,
Vec3f  
) const

Definition at line 217 of file narrowphase.cpp.

◆ shapeIntersect() [12/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Plane s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f ,
Vec3f  
) const

Definition at line 231 of file narrowphase.cpp.

◆ shapeIntersect() [13/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Plane s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 321 of file narrowphase.cpp.

◆ shapeIntersect() [14/18]

template<typename S1 , typename S2 >
bool hpp::fcl::GJKSolver::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
inline

intersection checking between two shapes

Definition at line 104 of file narrowphase.h.

◆ shapeIntersect() [15/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Sphere s1,
const Transform3f tf1,
const Capsule s2,
const Transform3f tf2,
FCL_REAL distance_lower_bound,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 94 of file narrowphase.cpp.

◆ shapeIntersect() [16/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Sphere s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 142 of file narrowphase.cpp.

◆ shapeIntersect() [17/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Sphere s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 248 of file narrowphase.cpp.

◆ shapeIntersect() [18/18]

template<>
bool hpp::fcl::GJKSolver::shapeIntersect ( const Sphere s1,
const Transform3f tf1,
const Sphere s2,
const Transform3f tf2,
FCL_REAL distance_lower_bound,
bool  ,
Vec3f contact_points,
Vec3f normal 
) const

Definition at line 105 of file narrowphase.cpp.

◆ shapeTriangleInteraction() [1/4]

template<>
bool hpp::fcl::GJKSolver::shapeTriangleInteraction ( const Halfspace 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

Definition at line 340 of file narrowphase.cpp.

◆ shapeTriangleInteraction() [2/4]

template<>
bool hpp::fcl::GJKSolver::shapeTriangleInteraction ( const Plane 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

Definition at line 349 of file narrowphase.cpp.

◆ shapeTriangleInteraction() [3/4]

template<typename S >
bool hpp::fcl::GJKSolver::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
inline

intersection checking between one shape and a triangle with transformation

Returns
true if the shape are colliding.

Definition at line 178 of file narrowphase.h.

◆ shapeTriangleInteraction() [4/4]

template<>
bool hpp::fcl::GJKSolver::shapeTriangleInteraction ( const Sphere 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

Definition at line 330 of file narrowphase.cpp.

Member Data Documentation

◆ cached_guess

Vec3f hpp::fcl::GJKSolver::cached_guess
mutable

smart guess

Definition at line 499 of file narrowphase.h.

◆ distance_upper_bound

FCL_REAL hpp::fcl::GJKSolver::distance_upper_bound
mutable

Distance above which the GJK solver stoppes its computations and processes to an early stopping. The two witness points are incorrect, but with the guaranty that the two shapes have a distance greather than distance_upper_bound.

Definition at line 520 of file narrowphase.h.

◆ enable_cached_guess

bool hpp::fcl::GJKSolver::enable_cached_guess
mutable

Whether smart guess can be provided @Deprecated Use gjk_initial_guess instead.

Definition at line 496 of file narrowphase.h.

◆ epa_max_face_num

unsigned int hpp::fcl::GJKSolver::epa_max_face_num

maximum number of simplex face used in EPA algorithm

Definition at line 476 of file narrowphase.h.

◆ epa_max_iterations

unsigned int hpp::fcl::GJKSolver::epa_max_iterations

maximum number of iterations used for EPA iterations

Definition at line 482 of file narrowphase.h.

◆ epa_max_vertex_num

unsigned int hpp::fcl::GJKSolver::epa_max_vertex_num

maximum number of simplex vertex used in EPA algorithm

Definition at line 479 of file narrowphase.h.

◆ epa_tolerance

FCL_REAL hpp::fcl::GJKSolver::epa_tolerance

the threshold used in EPA to stop iteration

Definition at line 485 of file narrowphase.h.

◆ gjk_convergence_criterion

GJKConvergenceCriterion hpp::fcl::GJKSolver::gjk_convergence_criterion
mutable

Criterion used to stop GJK.

Definition at line 508 of file narrowphase.h.

◆ gjk_convergence_criterion_type

GJKConvergenceCriterionType hpp::fcl::GJKSolver::gjk_convergence_criterion_type
mutable

Relative or absolute.

Definition at line 511 of file narrowphase.h.

◆ gjk_initial_guess

GJKInitialGuess hpp::fcl::GJKSolver::gjk_initial_guess
mutable

which warm start to use for GJK

Definition at line 502 of file narrowphase.h.

◆ gjk_max_iterations

size_t hpp::fcl::GJKSolver::gjk_max_iterations
mutable

maximum number of iterations used for GJK iterations

Definition at line 491 of file narrowphase.h.

◆ gjk_tolerance

FCL_REAL hpp::fcl::GJKSolver::gjk_tolerance
mutable

the threshold used in GJK to stop iteration

Definition at line 488 of file narrowphase.h.

◆ gjk_variant

GJKVariant hpp::fcl::GJKSolver::gjk_variant
mutable

Variant to use for the GJK algorithm.

Definition at line 505 of file narrowphase.h.

◆ support_func_cached_guess

support_func_guess_t hpp::fcl::GJKSolver::support_func_cached_guess
mutable

smart guess for the support function

Definition at line 514 of file narrowphase.h.


The documentation for this struct was generated from the following files:


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:17