Go to the documentation of this file.
   38 #ifndef FCL_NARROWPHASE_GJKSOLVERINDEP_INL_H 
   39 #define FCL_NARROWPHASE_GJKSOLVERINDEP_INL_H 
   70 struct GJKSolver_indep<double>;
 
   74 template<
typename Shape1, 
typename Shape2>
 
   81   if (contact_points || penetration_depth || normal)
 
   83     std::vector<ContactPoint<S>> contacts;
 
   85     res = shapeIntersect(s1, tf1, s2, tf2, &contacts);
 
   87     if (!contacts.empty())
 
   90       const ContactPoint<S>& maxDepthContact = *std::max_element(contacts.begin(), contacts.end(), comparePenDepth<S>);
 
   93         *contact_points = maxDepthContact.
pos;
 
   95       if (penetration_depth)
 
   99         *normal = maxDepthContact.
normal;
 
  104     res = shapeIntersect(s1, tf1, s2, tf2, 
nullptr);
 
  111 template<
typename S, 
typename Shape1, 
typename Shape2>
 
  128     shape.
toshape1.noalias() = tf2.linear().transpose() * tf1.linear();
 
  129     shape.
toshape0 = tf1.inverse(Eigen::Isometry) * tf2;
 
  144           for(
size_t i = 0; i < epa.
result.rank; ++i)
 
  152             S depth = -epa.
depth;
 
  153             contacts->emplace_back(normal, 
point, depth);
 
  170 template<
typename Shape1, 
typename Shape2>
 
  179         *
this, s1, tf1, s2, tf2, contacts);
 
  208 #define FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_REG(SHAPE1, SHAPE2, ALG)\ 
  209   template <typename S>\ 
  210   struct ShapeIntersectIndepImpl<S, SHAPE1<S>, SHAPE2<S>>\ 
  213         const GJKSolver_indep<S>& ,\ 
  214         const SHAPE1<S>& s1,\ 
  215         const Transform3<S>& tf1,\ 
  216         const SHAPE2<S>& s2,\ 
  217         const Transform3<S>& tf2,\ 
  218         std::vector<ContactPoint<S>>* contacts)\ 
  220       return ALG(s1, tf1, s2, tf2, contacts);\ 
  224 #define FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_INV(SHAPE1, SHAPE2, ALG)\ 
  225   template <typename S>\ 
  226   struct ShapeIntersectIndepImpl<S, SHAPE2<S>, SHAPE1<S>>\ 
  229         const GJKSolver_indep<S>& ,\ 
  230         const SHAPE2<S>& s1,\ 
  231         const Transform3<S>& tf1,\ 
  232         const SHAPE1<S>& s2,\ 
  233         const Transform3<S>& tf2,\ 
  234         std::vector<ContactPoint<S>>* contacts)\ 
  236       const bool res = ALG(s2, tf2, s1, tf1, contacts);\ 
  237       if (contacts) flipNormal(*contacts);\ 
  242 #define FCL_GJK_INDEP_SHAPE_INTERSECT(SHAPE, ALG)\ 
  243   FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_REG(SHAPE, SHAPE, ALG) 
  245 #define FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT(SHAPE1, SHAPE2, ALG)\ 
  246   FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_REG(SHAPE1, SHAPE2, ALG)\ 
  247   FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_INV(SHAPE1, SHAPE2, ALG) 
  273 template <
typename S>
 
  294 template <
typename S>
 
  309 template <
typename S>
 
  330 template <
typename S>
 
  352 template<
typename S, 
typename Shape>
 
  363       S* penetration_depth,
 
  375     shape.
toshape0 = tf.inverse(Eigen::Isometry);
 
  390           for(
size_t i = 0; i < epa.
result.rank; ++i)
 
  394           if(penetration_depth) *penetration_depth = -epa.
depth;
 
  395           if(normal) *normal = -epa.
normal;
 
  396           if(contact_points) (*contact_points).noalias() = tf * (w0 - epa.
normal*(epa.
depth *0.5));
 
  411 template<
typename Shape>
 
  419     S* penetration_depth,
 
  423         *
this, s, tf, P1, P2, P3, contact_points, penetration_depth, normal);
 
  438       S* penetration_depth,
 
  442           s, tf, P1, P2, P3, contact_points, penetration_depth, normal);
 
  448 template<
typename S, 
typename Shape>
 
  460       S* penetration_depth,
 
  471     shape.
toshape1.noalias() = tf2.linear().transpose() * tf1.linear();
 
  472     shape.
toshape0 = tf1.inverse(Eigen::Isometry) * tf2;
 
  487           for(
size_t i = 0; i < epa.
result.rank; ++i)
 
  491           if(penetration_depth) *penetration_depth = -epa.
depth;
 
  492           if(normal) *normal = -epa.
normal;
 
  493           if(contact_points) (*contact_points).noalias() = tf1 * (w0 - epa.
normal*(epa.
depth *0.5));
 
  508 template<
typename Shape>
 
  517     S* penetration_depth,
 
  521         *
this, s, tf1, P1, P2, P3, tf2,
 
  522         contact_points, penetration_depth, normal);
 
  538       S* penetration_depth,
 
  542           s, tf1, tf2 * P1, tf2 * P2, tf2 * P3,
 
  543           contact_points, penetration_depth, normal);
 
  560       S* penetration_depth,
 
  564           s, tf1, P1, P2, P3, tf2,
 
  565           contact_points, penetration_depth, normal);
 
  582       S* penetration_depth,
 
  586           s, tf1, P1, P2, P3, tf2,
 
  587           contact_points, penetration_depth, normal);
 
  593 template<
typename S, 
typename Shape1, 
typename Shape2>
 
  612     shape.
toshape1.noalias() = tf2.linear().transpose() * tf1.linear();
 
  613     shape.
toshape0 = tf1.inverse(Eigen::Isometry) * tf2;
 
  623       for(
size_t i = 0; i < gjk.
getSimplex()->rank; ++i)
 
  634       if(p1) p1->noalias() = tf1 * w0;
 
  635       if(p2) p2->noalias() = tf1 * w1;
 
  648 template<
typename Shape1, 
typename Shape2>
 
  659         *
this, s1, tf1, s2, tf2, dist, p1, p2);
 
  665 template<
typename Shape1, 
typename Shape2>
 
  679         *
this, s1, tf1, s2, tf2, dist, p1, p2);
 
  855 template<
typename S, 
typename Shape>
 
  877     shape.
toshape0 = tf.inverse(Eigen::Isometry);
 
  887       for(
size_t i = 0; i < gjk.
getSimplex()->rank; ++i)
 
  910 template<
typename Shape>
 
  922         *
this, s, tf, P1, P2, P3, dist, p1, p2);
 
  945 template<
typename S, 
typename Shape>
 
  967     shape.
toshape1.noalias() = tf2.linear().transpose() * tf1.linear();
 
  968     shape.
toshape0 = tf1.inverse(Eigen::Isometry) * tf2;
 
  978       for(
size_t i = 0; i < gjk.
getSimplex()->rank; ++i)
 
  986       if(p1) p1->noalias() = tf1 * w0;
 
  987       if(p2) p2->noalias() = tf1 * w1;
 
 1000 template<
typename Shape>
 
 1013         *
this, s, tf1, P1, P2, P3, tf2, dist, p1, p2);
 
 1017 template<
typename S>
 
 1033           s, tf1, P1, P2, P3, tf2, dist, p1, p2);
 
 1038 template <
typename S>
 
 1041   gjk_max_iterations = 128;
 
 1043   epa_max_face_num = 128;
 
 1044   epa_max_vertex_num = 64;
 
 1045   epa_max_iterations = 255;
 
 1047   enable_cached_guess = 
false;
 
 1052 template <
typename S>
 
 1055   enable_cached_guess = if_enable;
 
 1059 template <
typename S>
 
 1062   cached_guess = guess;
 
 1066 template <
typename S>
 
 1069   return cached_guess;
 
  
template bool sphereCapsuleIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
template bool halfspaceTriangleIntersect(const Halfspace< double > &s1, const Transform3< double > &tf1, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal)
static bool run(const GJKSolver_indep< S > &, const Capsule< S > &s1, const Transform3< S > &tf1, const Capsule< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
template FCL_EXPORT bool sphereBoxDistance(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Box< double > &box, const Transform3< double > &X_FB, double *distance, Vector3< double > *p_FSb, Vector3< double > *p_FBs)
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
void enableCachedGuess(bool if_enable) const
Simplex * getSimplex() const
get the underlying simplex using in GJK, can be used for cache in next iteration
Matrix3< S > toshape1
rotation from shape0 to shape1
template bool capsulePlaneIntersect(const Capsule< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2)
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal)
const ShapeBase< S > * shapes[2]
points to two shapes
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s1, const Transform3< S > &tf1, const Capsule< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
template bool cylinderHalfspaceIntersect(const Cylinder< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
bool shapeDistance(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *distance=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between two shapes
template bool sphereHalfspaceIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
template bool planeTriangleIntersect(const Plane< double > &s1, const Transform3< double > &tf1, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal)
template bool planeHalfspaceIntersect(const Plane< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Plane< double > &pl, Vector3< double > &p, Vector3< double > &d, double &penetration_depth, int &ret)
template bool capsuleHalfspaceIntersect(const Capsule< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
template bool boxBoxIntersect(const Box< double > &s1, const Transform3< double > &tf1, const Box< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts_)
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *distance, Vector3< S > *p1, Vector3< S > *p2)
#define FCL_GJK_INDEP_SHAPE_INTERSECT(SHAPE, ALG)
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s1, const Transform3< S > &tf1, const Cylinder< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
S epa_tolerance
the threshold used in EPA to stop iteration
static bool run(const GJKSolver_indep< S > &, const Capsule< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
static bool run(const GJKSolver_indep< S > &, const Plane< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
template FCL_EXPORT bool sphereSphereIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Sphere< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
Transform3< S > toshape0
transform from shape1 to shape0
bool shapeTriangleIntersect(const Shape &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, Vector3< S > *contact_points=nullptr, S *penetration_depth=nullptr, Vector3< S > *normal=nullptr) const
intersection checking between one shape and a triangle
Vector3< S > support(const Vector3< S > &d) const
support function for the pair of shapes
Status evaluate(const MinkowskiDiff< S > &shape_, const Vector3< S > &guess)
GJK algorithm, given the initial value guess.
template bool planeIntersect(const Plane< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
static bool run(const GJKSolver_indep< S > &, const Halfspace< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
template bool sphereTriangleIntersect(const Sphere< double > &s, const Transform3< double > &tf, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal_)
Eigen::Matrix< S, 3, 1 > Vector3
void setCachedGuess(const Vector3< S > &guess) const
template bool convexHalfspaceIntersect(const Convex< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal)
unsigned int epa_max_vertex_num
maximum number of simplex vertex used in EPA algorithm
static bool run(const GJKSolver_indep< S > &, const Halfspace< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
template bool coneHalfspaceIntersect(const Cone< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
template bool spherePlaneIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
bool shapeSignedDistance(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *distance=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between two shapes
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
template bool sphereTriangleDistance(const Sphere< double > &sp, const Transform3< double > &tf, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, double *dist)
template bool ellipsoidPlaneIntersect(const Ellipsoid< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
template bool boxPlaneIntersect(const Box< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
S gjk_tolerance
the threshold used in GJK to stop iteration
template bool conePlaneIntersect(const Cone< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
GJKSolver_indep()
default setting for GJK algorithm
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Triangle stores the points instead of only indices of points.
template bool halfspaceIntersect(const Halfspace< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Vector3< double > &p, Vector3< double > &d, Halfspace< double > &s, double &penetration_depth, int &ret)
template FCL_EXPORT bool sphereSphereDistance(const Sphere< double > &s1, const Transform3< double > &tf1, const Sphere< double > &s2, const Transform3< double > &tf2, double *dist, Vector3< double > *p1, Vector3< double > *p2)
template FCL_EXPORT bool sphereBoxIntersect(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Box< double > &box, const Transform3< double > &X_FB, std::vector< ContactPoint< double >> *contacts)
Half Space: this is equivalent to the Planed in ODE. The separation plane is defined as n * x = d....
Vector3< S > getGuessFromSimplex() const
get the guess from current simplex
template bool halfspacePlaneIntersect(const Halfspace< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, Plane< double > &pl, Vector3< double > &p, Vector3< double > &d, double &penetration_depth, int &ret)
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s1, const Transform3< S > &tf1, const Box< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
std::chrono::system_clock::time_point point
Representation of a point in time.
static Real gjk_default_tolerance()
template bool boxHalfspaceIntersect(const Box< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2)
template bool capsuleCapsuleDistance(const Capsule< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, double *dist, Vector3d *p1_res, Vector3d *p2_res)
static bool run(const GJKSolver_indep< S > &, const Box< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Status evaluate(GJK< S > &gjk, const Vector3< S > &guess)
Center at zero point, axis aligned box.
Vector3< S > getCachedGuess() const
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Center at zero point sphere.
bool enable_cached_guess
Whether smart guess can be provided.
S gjk_max_iterations
maximum number of iterations used for GJK iterations
template FCL_EXPORT bool sphereCylinderDistance(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Cylinder< double > &cylinder, const Transform3< double > &X_FC, double *distance, Vector3< double > *p_FSc, Vector3< double > *p_FCs)
FCL_DEPRECATED bool shapeIntersect(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) const
intersection checking between two shapes
#define FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT(SHAPE1, SHAPE2, ALG)
void ThrowDetailedConfiguration(const Shape1 &s1, const Transform3< S > &X_FS1, const Shape2 &s2, const Transform3< S > &X_FS2, const Solver &solver, const std::exception &e)
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *distance, Vector3< S > *p1, Vector3< S > *p2)
static bool run(const GJKSolver_indep< S > &, const Cylinder< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
template FCL_EXPORT bool sphereCylinderIntersect(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Cylinder< double > &cylinder, const Transform3< double > &X_FC, std::vector< ContactPoint< double >> *contacts)
template bool sphereCapsuleDistance(const Sphere< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, double *dist, Vector3< double > *p1, Vector3< double > *p2)
Vector3< S > cached_guess
smart guess
bool shapeTriangleDistance(const Shape &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *distance=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between one shape and a triangle
unsigned int epa_max_face_num
maximum number of simplex face used in EPA algorithm
template bool cylinderPlaneIntersect(const Cylinder< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2)
unsigned int epa_max_iterations
maximum number of iterations used for EPA iterations
Minkowski difference class of two shapes.
template bool ellipsoidHalfspaceIntersect(const Ellipsoid< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
Center at zero point capsule.
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal)
static bool run(const GJKSolver_indep< S > &, const Plane< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
fcl
Author(s): 
autogenerated on Fri Mar 14 2025 02:38:17