Go to the documentation of this file.
   38 #ifndef FCL_NARROWPHASE_DETAIL_GJK_INL_H 
   39 #define FCL_NARROWPHASE_DETAIL_GJK_INL_H 
   56   : max_iterations(max_iterations_), 
tolerance(tolerance_)
 
   84   size_t iterations = 0;
 
   89   free_v[0] = &store_v[0];
 
   90   free_v[1] = &store_v[1];
 
   91   free_v[2] = &store_v[2];
 
   92   free_v[3] = &store_v[3];
 
   99   simplices[0].rank = 0;
 
  102   appendVertex(simplices[0], (ray.squaredNorm() > 0) ? (-ray).eval() : 
Vector3<S>::UnitX());
 
  103   simplices[0].p[0] = 1;
 
  104   ray = simplices[0].c[0]->w;
 
  105   lastw[0] = lastw[1] = lastw[2] = lastw[3] = ray; 
 
  109     size_t next = 1 - current;
 
  110     Simplex& curr_simplex = simplices[current];
 
  121     appendVertex(curr_simplex, -ray); 
 
  126     for(
size_t i = 0; i < 4; ++i)
 
  128       if((w - lastw[i]).squaredNorm() < 
tolerance)
 
  136       removeVertex(simplices[current]);
 
  141       lastw[clastw = (clastw+1)&3] = w;
 
  145     S omega = ray.dot(w) / rl;
 
  149       removeVertex(simplices[current]);
 
  154     switch(curr_simplex.
rank)
 
  166       next_simplex.
rank = 0;
 
  169       for(
size_t i = 0; i < curr_simplex.
rank; ++i)
 
  171         if(project_res.
encode & (1 << i))
 
  173           next_simplex.
c[next_simplex.
rank] = curr_simplex.
c[i];
 
  178           free_v[nfree++] = curr_simplex.
c[i];
 
  180       if(project_res.
encode == 15) status = Inside; 
 
  184       removeVertex(simplices[current]);
 
  188     status = ((++iterations) < max_iterations) ? status : Failed;
 
  190   } 
while(status == Valid);
 
  192   simplex = &simplices[current];
 
  195   case Valid: 
distance = ray.norm(); 
break;
 
  203 template <
typename S>
 
  206   sv.
d = d.normalized();
 
  207   sv.
w = shape.support(sv.
d);
 
  211 template <
typename S>
 
  214   sv.
d = d.normalized();
 
  215   sv.
w = shape.support(sv.
d, v);
 
  219 template <
typename S>
 
  222   free_v[nfree++] = simplex.
c[--simplex.
rank];
 
  226 template <
typename S>
 
  229   simplex.
p[simplex.
rank] = 0; 
 
  230   simplex.
c[simplex.
rank] = free_v[--nfree]; 
 
  235 template <
typename S>
 
  238   switch(simplex->rank)
 
  242       for(
size_t i = 0; i < 3; ++i)
 
  246         appendVertex(*simplex, axis);
 
  247         if(encloseOrigin()) 
return true;
 
  248         removeVertex(*simplex);
 
  249         appendVertex(*simplex, -axis);
 
  250         if(encloseOrigin()) 
return true;
 
  251         removeVertex(*simplex);
 
  257       Vector3<S> d = simplex->c[1]->w - simplex->c[0]->w;
 
  258       for(
size_t i = 0; i < 3; ++i)
 
  263         if(p.squaredNorm() > 0)
 
  265           appendVertex(*simplex, p);
 
  266           if(encloseOrigin()) 
return true;
 
  267           removeVertex(*simplex);
 
  268           appendVertex(*simplex, -p);
 
  269           if(encloseOrigin()) 
return true;
 
  270           removeVertex(*simplex);
 
  277       Vector3<S> n = (simplex->c[1]->w - simplex->c[0]->w).cross(simplex->c[2]->w - simplex->c[0]->w);
 
  278       if(n.squaredNorm() > 0)
 
  280         appendVertex(*simplex, n);
 
  281         if(encloseOrigin()) 
return true;
 
  282         removeVertex(*simplex);
 
  283         appendVertex(*simplex, -n);
 
  284         if(encloseOrigin()) 
return true;
 
  285         removeVertex(*simplex);
 
  291       if(std::abs(
triple(simplex->c[0]->w - simplex->c[3]->w, simplex->c[1]->w - simplex->c[3]->w, simplex->c[2]->w - simplex->c[3]->w)) > 0)
 
  301 template <
typename S>
 
  308 template <
typename S>
 
  
void removeVertex(Simplex &simplex)
discard one vertex from the simplex
Simplex * getSimplex() const
get the underlying simplex using in GJK, can be used for cache in next iteration
unsigned int encode
the code of the projection type
size_t rank
size of simplex (number of vertices)
Vector3< S > d
support direction
Status evaluate(const MinkowskiDiff< S > &shape_, const Vector3< S > &guess)
GJK algorithm, given the initial value guess.
GJK(unsigned int max_iterations_, S tolerance_)
Eigen::Matrix< S, 3, 1 > Vector3
static ProjectResult projectTriangleOrigin(const Vector3< S > &a, const Vector3< S > &b, const Vector3< S > &c)
Project origin (0) onto triangle a-b-c.
EndPoint * next[3]
the next end point in the end point list
Vector3< S > getGuessFromSimplex() const
get the guess from current simplex
S parameterization[4]
Parameterization of the projected point (based on the simplex to be projected, use 2 or 3 or 4 of the...
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
void appendVertex(Simplex &simplex, const Vector3< S > &v)
append one vertex to the simplex
bool encloseOrigin()
whether the simplex enclose the origin
SimplexV * c[4]
simplex vertex
void getSupport(const Vector3< S > &d, SimplexV &sv) const
apply the support function along a direction, the result is return in sv
S sqr_distance
square distance from the query point to the projected simplex
static ProjectResult projectTetrahedraOrigin(const Vector3< S > &a, const Vector3< S > &b, const Vector3< S > &c, const Vector3< S > &d)
Project origin (0) onto tetrahedran a-b-c-d.
Vector3< S > w
@brieg support vector (i.e., the furthest point on the shape along the support direction)
FCL_EXPORT Vector3< S > getSupport(const ShapeBase< S > *shape, const Eigen::MatrixBase< Derived > &dir)
the support function for shape
FCL_EXPORT Derived::RealScalar triple(const Eigen::MatrixBase< Derived > &x, const Eigen::MatrixBase< Derived > &y, const Eigen::MatrixBase< Derived > &z)
Minkowski difference class of two shapes.
static ProjectResult projectLineOrigin(const Vector3< S > &a, const Vector3< S > &b)
Project origin (0) onto line a-b.
fcl
Author(s): 
autogenerated on Fri Mar 14 2025 02:38:17