Go to the documentation of this file.
38 #ifndef FCL_NARROWPHASE_GJKSOLVERLIBCCD_INL_H
39 #define FCL_NARROWPHASE_GJKSOLVERLIBCCD_INL_H
67 struct GJKSolver_libccd<double>;
71 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>
130 res = detail::GJKCollide<S>(
141 contacts->emplace_back(normal,
point, depth);
145 res = detail::GJKCollide<S>(
168 template<
typename Shape1,
typename Shape2>
175 *
this, s1, tf1, s2, tf2, contacts);
204 #define FCL_GJK_LIBCCD_SHAPE_SHAPE_INTERSECT_REG(SHAPE1, SHAPE2, ALG)\
205 template <typename S>\
206 struct ShapeIntersectLibccdImpl<S, SHAPE1<S>, SHAPE2<S>>\
209 const GJKSolver_libccd<S>& ,\
210 const SHAPE1<S>& s1,\
211 const Transform3<S>& tf1,\
212 const SHAPE2<S>& s2,\
213 const Transform3<S>& tf2,\
214 std::vector<ContactPoint<S>>* contacts)\
216 return ALG(s1, tf1, s2, tf2, contacts);\
220 #define FCL_GJK_LIBCCD_SHAPE_SHAPE_INTERSECT_INV(SHAPE1, SHAPE2, ALG)\
221 template <typename S>\
222 struct ShapeIntersectLibccdImpl<S, SHAPE2<S>, SHAPE1<S>>\
225 const GJKSolver_libccd<S>& ,\
226 const SHAPE2<S>& s1,\
227 const Transform3<S>& tf1,\
228 const SHAPE1<S>& s2,\
229 const Transform3<S>& tf2,\
230 std::vector<ContactPoint<S>>* contacts)\
232 const bool res = ALG(s2, tf2, s1, tf1, contacts);\
233 if (contacts) flipNormal(*contacts);\
238 #define FCL_GJK_LIBCCD_SHAPE_INTERSECT(SHAPE, ALG)\
239 FCL_GJK_LIBCCD_SHAPE_SHAPE_INTERSECT_REG(SHAPE, SHAPE, ALG)
241 #define FCL_GJK_LIBCCD_SHAPE_SHAPE_INTERSECT(SHAPE1, SHAPE2, ALG)\
242 FCL_GJK_LIBCCD_SHAPE_SHAPE_INTERSECT_REG(SHAPE1, SHAPE2, ALG)\
243 FCL_GJK_LIBCCD_SHAPE_SHAPE_INTERSECT_INV(SHAPE1, SHAPE2, ALG)
269 template <
typename S>
290 template <
typename S>
305 template <
typename S>
326 template <
typename S>
348 template<
typename S,
typename Shape>
359 S* penetration_depth,
365 bool res = detail::GJKCollide<S>(
386 template<
typename Shape>
394 S* penetration_depth,
398 *
this, s, tf, P1, P2, P3, contact_points, penetration_depth, normal);
413 S* penetration_depth,
417 s, tf, P1, P2, P3, contact_points, penetration_depth, normal);
422 template<
typename S,
typename Shape>
434 S* penetration_depth,
440 bool res = detail::GJKCollide<S>(
461 template<
typename Shape>
470 S* penetration_depth,
474 *
this, s, tf1, P1, P2, P3, tf2,
475 contact_points, penetration_depth, normal);
491 S* penetration_depth,
495 s, tf1, tf2 * P1, tf2 * P2, tf2 * P3,
496 contact_points, penetration_depth, normal);
513 S* penetration_depth,
517 s, tf1, P1, P2, P3, tf2,
518 contact_points, penetration_depth, normal);
535 S* penetration_depth,
539 s, tf1, P1, P2, P3, tf2,
540 contact_points, penetration_depth, normal);
547 template<
typename S,
typename Shape1,
typename Shape2>
582 template<
typename Shape1,
typename Shape2>
595 *
this, s1, tf1, s2, tf2, dist, p1, p2);
604 template<
typename S,
typename Shape1,
typename Shape2>
639 template<
typename Shape1,
typename Shape2>
650 *
this, s1, tf1, s2, tf2, dist, p1, p2);
822 template<
typename S,
typename Shape>
859 template<
typename Shape>
871 *
this, s, tf, P1, P2, P3, dist, p1, p2);
894 template<
typename S,
typename Shape>
932 template<
typename Shape>
945 *
this, s, tf1, P1, P2, P3, tf2, dist, p1, p2);
965 s, tf1, P1, P2, P3, tf2, dist, p1, p2);
973 max_collision_iterations = 500;
974 max_distance_iterations = 1000;
976 distance_tolerance = 1e-6;
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)
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)
static bool run(const GJKSolver_libccd< S > &, const Halfspace< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
static bool run(const GJKSolver_libccd< S > &, const Plane< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
template bool capsulePlaneIntersect(const Capsule< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2)
static bool run(const GJKSolver_libccd< 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)
static bool run(const GJKSolver_libccd< 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)
template bool cylinderHalfspaceIntersect(const Cylinder< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
collision and distance solver based on libccd library.
static bool run(const GJKSolver_libccd< S > &gjkSolver, const Shape &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)
template bool sphereHalfspaceIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
S collision_tolerance
the threshold used in GJK algorithm to stop collision iteration
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
bool shapeTriangleDistance(const Shape &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *dist=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between one shape and a triangle
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)
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
void triDeleteGJKObject(void *o_)
GJKSupportFunction triGetSupportFunction()
initialize GJK Triangle
static bool run(const GJKSolver_libccd< 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)
unsigned int max_collision_iterations
maximum number of iterations used in GJK algorithm for collision
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_libccd< 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)
static bool run(const GJKSolver_libccd< S > &, const Halfspace< 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)
static bool run(const GJKSolver_libccd< 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 bool planeIntersect(const Plane< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *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
static bool run(const GJKSolver_libccd< 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 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)
static bool run(const GJKSolver_libccd< 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)
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)
static bool run(const GJKSolver_libccd< S > &gjkSolver, const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
static bool run(const GJKSolver_libccd< 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 bool sphereTriangleDistance(const Sphere< double > &sp, const Transform3< double > &tf, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, double *dist)
static bool run(const GJKSolver_libccd< S > &gjkSolver, const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
template bool ellipsoidPlaneIntersect(const Ellipsoid< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
static bool run(const GJKSolver_libccd< 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)
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 distance_tolerance
the threshold used in GJK algorithm to stop distance iteration
template void * triCreateGJKObject(const Vector3d &P1, const Vector3d &P2, const Vector3d &P3)
template bool conePlaneIntersect(const Cone< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
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....
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 void deleteGJKObject(void *o)
Delete GJK object.
std::chrono::system_clock::time_point point
Representation of a point in time.
Vector3< S > getCachedGuess() const
static Real gjk_default_tolerance()
template bool boxHalfspaceIntersect(const Box< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2)
static bool run(const GJKSolver_libccd< 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 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_libccd< S > &gjkSolver, const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Center at zero point, axis aligned box.
Center at zero point sphere.
void enableCachedGuess(bool if_enable) const
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)
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_libccd< 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)
bool shapeDistance(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *dist=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between two shapes
template bool GJKDistance(void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, double tolerance, double *dist, Vector3d *p1, Vector3d *p2)
#define FCL_GJK_LIBCCD_SHAPE_INTERSECT(SHAPE, ALG)
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)
GJKCenterFunction triGetCenterFunction()
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)
void setCachedGuess(const Vector3< S > &guess) const
bool shapeSignedDistance(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *dist=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
template bool GJKSignedDistance(void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, double tolerance, double *dist, Vector3d *p1, Vector3d *p2)
static bool run(const GJKSolver_libccd< S > &, const Plane< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
#define FCL_GJK_LIBCCD_SHAPE_SHAPE_INTERSECT(SHAPE1, SHAPE2, ALG)
template bool cylinderPlaneIntersect(const Cylinder< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2)
unsigned int max_distance_iterations
maximum number of iterations used in GJK algorithm for distance
GJKSolver_libccd()
default setting for GJK algorithm
template bool ellipsoidHalfspaceIntersect(const Ellipsoid< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
Center at zero point capsule.
static void * createGJKObject(const T &, const Transform3< S > &)
Get GJK object from a shape Notice that only local transformation is applied. Gloal transformation ar...
fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:48