Go to the documentation of this file.
   53 struct COAL_DLLAPI 
GJK {
 
   81       for (
size_t i = 0; i < 4; ++i) vertex[i] = 
nullptr;
 
  144       : max_iterations(max_iterations_), tolerance(tolerance_) {
 
  145     COAL_ASSERT(tolerance_ > 0, 
"Tolerance must be positive.",
 
  146                 std::invalid_argument);
 
  153   void reset(
size_t max_iterations_, 
CoalScalar tolerance_);
 
  165     sv.
w = sv.
w0 - sv.
w1;
 
  169   bool encloseOrigin();
 
  188   Vec3s getGuessFromSimplex() 
const;
 
  195     distance_upper_bound = dup;
 
  215     return iterations_momentum_stop;
 
  225   inline void removeVertex(Simplex& simplex);
 
  228   inline void appendVertex(Simplex& simplex, 
const Vec3s& 
v,
 
  246   bool projectLineOrigin(
const Simplex& current, Simplex& next);
 
  250   bool projectTriangleOrigin(
const Simplex& current, Simplex& next);
 
  254   bool projectTetrahedraOrigin(
const Simplex& current, Simplex& next);
 
  269     size_t adjacent_edge[3];         
 
  294       if (root != 
nullptr) root->
prev_face = face;
 
  304       if (face == root) root = face->
next_face;
 
  313     assert(ea == 0 || ea == 1 || ea == 2);
 
  314     assert(eb == 0 || eb == 1 || eb == 2);
 
  333     AccuracyReached = 1 << 1 | Valid,
 
  334     Degenerated = 1 << 1 | Failed,
 
  335     NonConvex = 2 << 1 | Failed,
 
  336     InvalidHull = 3 << 1 | Failed,
 
  337     OutOfFaces = 4 << 1 | Failed,
 
  338     OutOfVertices = 5 << 1 | Failed,
 
  339     FallBack = 6 << 1 | Failed
 
  364       : max_iterations(max_iterations_), tolerance(tolerance_) {
 
  371       : max_iterations(other.max_iterations),
 
  372         tolerance(other.tolerance),
 
  373         sv_store(other.sv_store),
 
  374         fc_store(other.fc_store) {
 
  407   void reset(
size_t max_iterations, 
CoalScalar tolerance);
 
  430   bool getEdgeDist(SimplexFace* face, 
const SimplexVertex& a,
 
  436   SimplexFace* newFace(
size_t id_a, 
size_t id_b, 
size_t id_vertex,
 
  440   SimplexFace* findClosestFace();
 
  443   bool expand(
size_t pass, 
const SimplexVertex& w, SimplexFace* f, 
size_t e,
 
  444               SimplexHorizon& horizon);
 
  
GJKConvergenceCriterion
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision)....
SimplexFace * current_face
size_t getNumMaxIterations() const
Get the max number of iterations of GJK.
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
std::vector< SimplexFace > fc_store
EPA(size_t max_iterations_, CoalScalar tolerance_)
size_t getNumIterations() const
Get the number of iterations of the last run of EPA.
MinkowskiDiff const  * shape
bool hasClosestPoints() const
Tells whether the closest points are available.
size_t iterations_momentum_stop
size_t getNumMaxIterations() const
Get the max number of iterations of EPA.
Minkowski difference class of two shapes.
Status
Status of the GJK algorithm: DidNotRun: GJK has not been run. Failed: GJK did not converge (it exceed...
#define COAL_ASSERT(check, message, exception)
GJKConvergenceCriterionType
Wether the convergence criterion is scaled on the norm of the solution or not.
@ NoCollisionEarlyStopped
size_t getNumIterations() const
Get the number of iterations of the last run of GJK.
void setDistanceEarlyBreak(const CoalScalar &dup)
Distance threshold for early break. GJK stops when it proved the distance is more than this threshold...
void support(const Vec3s &dir, Vec3s &supp0, Vec3s &supp1, support_func_guess_t &hint) const
Support function for the pair of shapes. This method assumes set has already been called.
GJKConvergenceCriterion convergence_criterion
A simplex is a set of up to 4 vertices. Its rank is the number of vertices it contains.
CoalScalar distance_upper_bound
COAL_DLLAPI CoalScalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
GJKVariant
Variant to use for the GJK algorithm.
Vec3s w
support vector (i.e., the furthest point on the shape along the support direction)
Simplex * getSimplex() const
get the underlying simplex using in GJK, can be used for cache in next iteration
size_t getNumMaxVertices() const
Get the max number of vertices of EPA.
GJK(size_t max_iterations_, CoalScalar tolerance_)
Eigen::Vector2i support_func_guess_t
SimplexFace * closest_face
static void bind(SimplexFace *fa, size_t ea, SimplexFace *fb, size_t eb)
We bind the face fa along its edge ea to the face fb along its edge fb.
size_t getNumMaxFaces() const
Get the max number of faces of EPA.
GJK::SimplexV SimplexVertex
CoalScalar distance
The distance between the two shapes, computed by GJK. If the distance is below GJK's threshold,...
vertex_id_t rank
size of simplex (number of vertices)
GJKConvergenceCriterionType convergence_criterion_type
void remove(SimplexFace *face)
void getSupport(const Vec3s &d, SimplexV &sv, support_func_guess_t &hint) const
apply the support function along a direction, the result is return in sv
@ CollisionWithPenetrationInformation
void append(SimplexFace *face)
size_t getNumIterationsMomentumStopped() const
Get GJK number of iterations before momentum stops. Only usefull if the Nesterov or Polyak accelerati...
size_t getNumVertices() const
Get the number of vertices in the polytope of the last run of EPA.
SimplexFace * adjacent_faces[3]
EPA(const EPA &other)
Copy constructor of EPA. Mostly needed for the copy constructor of GJKSolver.
Vec3s w0
support vector for shape 0 and 1.
size_t getNumFaces() const
Get the number of faces in the polytope of the last run of EPA.
CoalScalar getTolerance() const
Get the tolerance of EPA.
CoalScalar getTolerance() const
Get the tolerance of GJK.
unsigned char vertex_id_t
std::vector< SimplexVertex > sv_store
support_func_guess_t support_hint
support_func_guess_t support_hint
bool initialize(MeshCollisionTraversalNode< BV, RelativeTransformationIsIdentity > &node, BVHModel< BV > &model1, Transform3s &tf1, BVHModel< BV > &model2, Transform3s &tf2, CollisionResult &result, bool use_refit=false, bool refit_bottomup=false)
Initialize traversal node for collision between two meshes, given the current transforms.
The simplex list of EPA is a linked list of faces. Note: EPA's linked list does not own any memory....
hpp-fcl
Author(s): 
autogenerated on Fri Feb 14 2025 03:45:50