Namespaces | Classes | Functions | Variables
hpp::fcl::details Namespace Reference

Namespaces

 details
 

Classes

struct  bvh_shape_traits
 
struct  ContactPoint
 
struct  EPA
 class for EPA algorithm More...
 
struct  GJK
 class for GJK algorithm More...
 
struct  LargeConvex
 
struct  MinkowskiDiff
 Minkowski difference class of two shapes. More...
 
struct  SmallConvex
 
struct  UpdateBoundingVolume
 
struct  UpdateBoundingVolume< AABB >
 

Functions

unsigned int boxBox2 (const Vec3f &halfSide1, const Matrix3f &R1, const Vec3f &T1, const Vec3f &halfSide2, const Matrix3f &R2, const Vec3f &T2, Vec3f &normal, FCL_REAL *depth, int *return_code, unsigned int maxc, std::vector< ContactPoint > &contacts)
 
bool boxBoxIntersect (const Box &s1, const Transform3f &tf1, const Box &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth_, Vec3f *normal_)
 
bool boxHalfspaceIntersect (const Box &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2)
 box half space, a, b, c = +/- edge size n^T * (R(o + a v1 + b v2 + c v3) + T) <= d so (R^T n) (a v1 + b v2 + c v3) + n * T <= d check whether d - n * T - (R^T n) (a v1 + b v2 + c v3) >= 0 for some a, b, c the max value of left side is d - n * T + |(R^T n) (a v1 + b v2 + c v3)|, check that is enough More...
 
bool boxHalfspaceIntersect (const Box &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool boxPlaneIntersect (const Box &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 box half space, a, b, c = +/- edge size n^T * (R(o + a v1 + b v2 + c v3) + T) ~ d so (R^T n) (a v1 + b v2 + c v3) + n * T ~ d check whether d - n * T - (R^T n) (a v1 + b v2 + c v3) >= 0 for some a, b, c and <=0 for some a, b, c so need to check whether |d - n * T| <= |(R^T n)(a v1 + b v2 + c v3)|, the reason is as follows: (R^T n) (a v1 + b v2 + c v3) can get |(R^T n) (a v1 + b v2 + c v3)| for one a, b, c. if |d - n * T| <= |(R^T n)(a v1 + b v2 + c v3)| then can get both positive and negative value on the right side. More...
 
bool boxSphereDistance (const Box &b, const Transform3f &tfb, const Sphere &s, const Transform3f &tfs, FCL_REAL &dist, Vec3f &pb, Vec3f &ps, Vec3f &normal)
 
 BVH_SHAPE_DEFAULT_TO_ORIENTED (kIOS)
 
 BVH_SHAPE_DEFAULT_TO_ORIENTED (OBB)
 
 BVH_SHAPE_DEFAULT_TO_ORIENTED (OBBRSS)
 
 BVH_SHAPE_DEFAULT_TO_ORIENTED (RSS)
 
template<typename BV >
BVHModel< BV > * BVHExtract (const BVHModel< BV > &model, const Transform3f &pose, const AABB &_aabb)
 Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is considered inside. More...
 
bool capsuleHalfspaceIntersect (const Capsule &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool capsulePlaneIntersect (const Capsule &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool compareContactPoints (const ContactPoint &c1, const ContactPoint &c2)
 
FCL_REAL computePenetration (const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Vec3f &Q1, const Vec3f &Q2, const Vec3f &Q3, const Transform3f &tf1, const Transform3f &tf2, Vec3f &normal)
 
FCL_REAL computePenetration (const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Vec3f &Q1, const Vec3f &Q2, const Vec3f &Q3, Vec3f &normal)
 See the prototype below. More...
 
bool coneHalfspaceIntersect (const Cone &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool conePlaneIntersect (const Cone &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool convexHalfspaceIntersect (const ConvexBase &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal)
 
bool convexPlaneIntersect (const ConvexBase &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal)
 
static void cullPoints2 (unsigned int n, FCL_REAL p[], unsigned int m, unsigned int i0, unsigned int iret[])
 
bool cylinderHalfspaceIntersect (const Cylinder &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool cylinderPlaneIntersect (const Cylinder &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 cylinder-plane intersect n^T (R (r * cosa * v1 + r * sina * v2 + h * v3) + T) ~ d need one point to be positive and one to be negative (n^T * v3) * h + n * T -d + r * (cosa * (n^T * R * v1) + sina * (n^T * R * v2)) ~ 0 (n^T * v3) * h + r * (cosa * (n^T * R * v1) + sina * (n^T * R * v2)) + n * T - d ~ 0 More...
 
CollisionGeometryextractBVH (const CollisionGeometry *model, const Transform3f &pose, const AABB &aabb)
 
template<typename NT >
CollisionGeometryextractBVHtpl (const CollisionGeometry *model, const Transform3f &pose, const AABB &aabb)
 
std::vector< Vec3fgetBoundVertices (const Box &box, const Transform3f &tf)
 
std::vector< Vec3fgetBoundVertices (const Capsule &capsule, const Transform3f &tf)
 
std::vector< Vec3fgetBoundVertices (const Cone &cone, const Transform3f &tf)
 
std::vector< Vec3fgetBoundVertices (const ConvexBase &convex, const Transform3f &tf)
 
std::vector< Vec3fgetBoundVertices (const Cylinder &cylinder, const Transform3f &tf)
 
std::vector< Vec3fgetBoundVertices (const Ellipsoid &ellipsoid, const Transform3f &tf)
 
std::vector< Vec3fgetBoundVertices (const Sphere &sphere, const Transform3f &tf)
 
std::vector< Vec3fgetBoundVertices (const TriangleP &triangle, const Transform3f &tf)
 
bool getNormalizeSupportDirection (const ShapeBase *shape)
 
void getNormalizeSupportDirectionFromShapes (const ShapeBase *shape0, const ShapeBase *shape1, bool &normalize_support_direction)
 
void getShapeSupport (const Box *box, const Vec3f &dir, Vec3f &support, int &, MinkowskiDiff::ShapeData *)
 
void getShapeSupport (const Capsule *capsule, const Vec3f &dir, Vec3f &support, int &, MinkowskiDiff::ShapeData *)
 
void getShapeSupport (const Cone *cone, const Vec3f &dir, Vec3f &support, int &, MinkowskiDiff::ShapeData *)
 
void getShapeSupport (const ConvexBase *convex, const Vec3f &dir, Vec3f &support, int &hint, MinkowskiDiff::ShapeData *)
 
void getShapeSupport (const Cylinder *cylinder, const Vec3f &dir, Vec3f &support, int &, MinkowskiDiff::ShapeData *)
 
void getShapeSupport (const Ellipsoid *ellipsoid, const Vec3f &dir, Vec3f &support, int &, MinkowskiDiff::ShapeData *)
 
void getShapeSupport (const LargeConvex *convex, const Vec3f &dir, Vec3f &support, int &hint, MinkowskiDiff::ShapeData *data)
 
void getShapeSupport (const SmallConvex *convex, const Vec3f &dir, Vec3f &support, int &hint, MinkowskiDiff::ShapeData *data)
 
void getShapeSupport (const Sphere *, const Vec3f &, Vec3f &support, int &, MinkowskiDiff::ShapeData *)
 
void getShapeSupport (const TriangleP *triangle, const Vec3f &dir, Vec3f &support, int &, MinkowskiDiff::ShapeData *)
 
void getShapeSupportLinear (const ConvexBase *convex, const Vec3f &dir, Vec3f &support, int &hint, MinkowskiDiff::ShapeData *)
 
void getShapeSupportLog (const ConvexBase *convex, const Vec3f &dir, Vec3f &support, int &hint, MinkowskiDiff::ShapeData *data)
 
Vec3f getSupport (const ShapeBase *shape, const Vec3f &dir, bool dirIsNormalized, int &hint)
 the support function for shape More...
 
template<typename Shape0 , typename Shape1 , bool TransformIsIdentity>
void getSupportFuncTpl (const MinkowskiDiff &md, const Vec3f &dir, bool dirIsNormalized, Vec3f &support0, Vec3f &support1, support_func_guess_t &hint, MinkowskiDiff::ShapeData data[2])
 
template<typename Shape0 , typename Shape1 , bool TransformIsIdentity>
void getSupportTpl (const Shape0 *s0, const Shape1 *s1, const Matrix3f &oR1, const Vec3f &ot1, const Vec3f &dir, Vec3f &support0, Vec3f &support1, support_func_guess_t &hint, MinkowskiDiff::ShapeData data[2])
 
bool halfspaceDistance (const Halfspace &h, const Transform3f &tf1, const ShapeBase &s, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool halfspaceIntersect (const Halfspace &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, Vec3f &p, Vec3f &d, Halfspace &s, FCL_REAL &penetration_depth, int &ret)
 
template<typename T >
halfspaceIntersectTolerance ()
 
template<>
float halfspaceIntersectTolerance ()
 
bool halfspacePlaneIntersect (const Halfspace &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Plane &pl, Vec3f &p, Vec3f &d, FCL_REAL &penetration_depth, int &ret)
 
bool halfspaceTriangleIntersect (const Halfspace &s1, const Transform3f &tf1, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
static unsigned int intersectRectQuad2 (FCL_REAL h[2], FCL_REAL p[8], FCL_REAL ret[16])
 
static void lineClosestApproach (const Vec3f &pa, const Vec3f &ua, const Vec3f &pb, const Vec3f &ub, FCL_REAL *alpha, FCL_REAL *beta)
 
static void lineSegmentPointClosestToPoint (const Vec3f &p, const Vec3f &s1, const Vec3f &s2, Vec3f &sp)
 
MinkowskiDiff::GetSupportFunction makeGetSupportFunction0 (const ShapeBase *s0, const ShapeBase *s1, bool identity, Eigen::Array< FCL_REAL, 1, 2 > &inflation, int linear_log_convex_threshold)
 
template<typename Shape0 >
MinkowskiDiff::GetSupportFunction makeGetSupportFunction1 (const ShapeBase *s1, bool identity, Eigen::Array< FCL_REAL, 1, 2 > &inflation, int linear_log_convex_threshold)
 
template<typename OrientedMeshShapeDistanceTraversalNode , typename T_BVH , typename T_SH >
FCL_REAL orientedBVHShapeDistance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 
template<typename OrientedMeshCollisionTraversalNode , typename T_BVH >
std::size_t orientedMeshCollide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 
template<typename OrientedMeshDistanceTraversalNode , typename T_BVH >
FCL_REAL orientedMeshDistance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 
void originToPoint (const GJK::Simplex &current, GJK::vertex_id_t a, const Vec3f &A, GJK::Simplex &next, Vec3f &ray)
 
void originToSegment (const GJK::Simplex &current, GJK::vertex_id_t a, GJK::vertex_id_t b, const Vec3f &A, const Vec3f &B, const Vec3f &AB, const FCL_REAL &ABdotAO, GJK::Simplex &next, Vec3f &ray)
 
bool originToTriangle (const GJK::Simplex &current, GJK::vertex_id_t a, GJK::vertex_id_t b, GJK::vertex_id_t c, const Vec3f &ABC, const FCL_REAL &ABCdotAO, GJK::Simplex &next, Vec3f &ray)
 
bool planeHalfspaceIntersect (const Plane &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, Plane &pl, Vec3f &p, Vec3f &d, FCL_REAL &penetration_depth, int &ret)
 return whether plane collides with halfspace if the separation plane of the halfspace is parallel with the plane return code 1, if the plane's normal is the same with halfspace's normal and plane is inside halfspace, also return plane in pl return code 2, if the plane's normal is oppositie to the halfspace's normal and plane is inside halfspace, also return plane in pl plane is outside halfspace, collision-free if not parallel return the intersection ray, return code 3. ray origin is p and direction is d More...
 
bool planeIntersect (const Plane &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Vec3f *, FCL_REAL *, Vec3f *)
 
template<typename T >
planeIntersectTolerance ()
 
template<>
double planeIntersectTolerance< double > ()
 
template<>
float planeIntersectTolerance< float > ()
 
bool planeTriangleIntersect (const Plane &s1, const Transform3f &tf1, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool projectInTriangle (const Vec3f &p1, const Vec3f &p2, const Vec3f &p3, const Vec3f &normal, const Vec3f &p)
 Whether a point's projection is in a triangle. More...
 
FCL_REAL segmentSqrDistance (const Vec3f &from, const Vec3f &to, const Vec3f &p, Vec3f &nearest)
 the minimum distance from a point to a line More...
 
bool sphereCapsuleDistance (const Sphere &s1, const Transform3f &tf1, const Capsule &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool sphereCapsuleIntersect (const Sphere &s1, const Transform3f &tf1, const Capsule &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f *contact_points, Vec3f *normal_)
 
bool sphereCylinderDistance (const Sphere &s1, const Transform3f &tf1, const Cylinder &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool sphereHalfspaceIntersect (const Sphere &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool spherePlaneIntersect (const Sphere &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool sphereSphereDistance (const Sphere &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL &dist, Vec3f &p1, Vec3f &p2, Vec3f &normal)
 
bool sphereSphereIntersect (const Sphere &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL &distance, Vec3f *contact_points, Vec3f *normal)
 
bool sphereTriangleDistance (const Sphere &sp, const Transform3f &tf, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, FCL_REAL *dist)
 
bool sphereTriangleDistance (const Sphere &sp, const Transform3f &tf, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, FCL_REAL *dist, Vec3f *p1, Vec3f *p2)
 
bool sphereTriangleDistance (const Sphere &sp, const Transform3f &tf1, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Transform3f &tf2, FCL_REAL *dist, Vec3f *p1, Vec3f *p2)
 
bool sphereTriangleIntersect (const Sphere &s, const Transform3f &tf1, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal_)
 

Variables

static const FCL_REAL EPA_EPS = 0.000001
 
static const size_t EPA_MAX_FACES = 128
 
static const size_t EPA_MAX_ITERATIONS = 255
 
static const size_t EPA_MAX_VERTICES = 64
 

Function Documentation

◆ boxBox2()

unsigned int hpp::fcl::details::boxBox2 ( const Vec3f halfSide1,
const Matrix3f R1,
const Vec3f T1,
const Vec3f halfSide2,
const Matrix3f R2,
const Vec3f T2,
Vec3f normal,
FCL_REAL depth,
int *  return_code,
unsigned int  maxc,
std::vector< ContactPoint > &  contacts 
)
inline

Definition at line 762 of file details.h.

◆ boxBoxIntersect()

bool hpp::fcl::details::boxBoxIntersect ( const Box s1,
const Transform3f tf1,
const Box s2,
const Transform3f tf2,
Vec3f contact_points,
FCL_REAL penetration_depth_,
Vec3f normal_ 
)
inline

Definition at line 1339 of file details.h.

◆ boxHalfspaceIntersect() [1/2]

bool hpp::fcl::details::boxHalfspaceIntersect ( const Box s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2 
)
inline

box half space, a, b, c = +/- edge size n^T * (R(o + a v1 + b v2 + c v3) + T) <= d so (R^T n) (a v1 + b v2 + c v3) + n * T <= d check whether d - n * T - (R^T n) (a v1 + b v2 + c v3) >= 0 for some a, b, c the max value of left side is d - n * T + |(R^T n) (a v1 + b v2 + c v3)|, check that is enough

Definition at line 1404 of file details.h.

◆ boxHalfspaceIntersect() [2/2]

bool hpp::fcl::details::boxHalfspaceIntersect ( const Box s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

find deepest point

compute the contact point from the deepest point

Definition at line 1418 of file details.h.

◆ boxPlaneIntersect()

bool hpp::fcl::details::boxPlaneIntersect ( const Box s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

box half space, a, b, c = +/- edge size n^T * (R(o + a v1 + b v2 + c v3) + T) ~ d so (R^T n) (a v1 + b v2 + c v3) + n * T ~ d check whether d - n * T - (R^T n) (a v1 + b v2 + c v3) >= 0 for some a, b, c and <=0 for some a, b, c so need to check whether |d - n * T| <= |(R^T n)(a v1 + b v2 + c v3)|, the reason is as follows: (R^T n) (a v1 + b v2 + c v3) can get |(R^T n) (a v1 + b v2 + c v3)| for one a, b, c. if |d - n * T| <= |(R^T n)(a v1 + b v2 + c v3)| then can get both positive and negative value on the right side.

Definition at line 1879 of file details.h.

◆ boxSphereDistance()

bool hpp::fcl::details::boxSphereDistance ( const Box b,
const Transform3f tfb,
const Sphere s,
const Transform3f tfs,
FCL_REAL dist,
Vec3f pb,
Vec3f ps,
Vec3f normal 
)
inline

Taken from book Real Time Collision Detection, from Christer Ericson

Parameters
pbthe closest point to the sphere center on the box surface
pswhen colliding, matches pb, which is inside the sphere. when not colliding, the closest point on the sphere
normaldirection of motion of the box
Returns
true if the distance is negative (the shape overlaps).

Definition at line 1957 of file details.h.

◆ BVH_SHAPE_DEFAULT_TO_ORIENTED() [1/4]

hpp::fcl::details::BVH_SHAPE_DEFAULT_TO_ORIENTED ( kIOS  )

◆ BVH_SHAPE_DEFAULT_TO_ORIENTED() [2/4]

hpp::fcl::details::BVH_SHAPE_DEFAULT_TO_ORIENTED ( OBB  )

◆ BVH_SHAPE_DEFAULT_TO_ORIENTED() [3/4]

hpp::fcl::details::BVH_SHAPE_DEFAULT_TO_ORIENTED ( OBBRSS  )

◆ BVH_SHAPE_DEFAULT_TO_ORIENTED() [4/4]

hpp::fcl::details::BVH_SHAPE_DEFAULT_TO_ORIENTED ( RSS  )

◆ BVHExtract()

template<typename BV >
BVHModel<BV>* hpp::fcl::details::BVHExtract ( const BVHModel< BV > &  model,
const Transform3f pose,
const AABB _aabb 
)

Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is considered inside.

Definition at line 47 of file BVH_utility.cpp.

◆ capsuleHalfspaceIntersect()

bool hpp::fcl::details::capsuleHalfspaceIntersect ( const Capsule s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 1466 of file details.h.

◆ capsulePlaneIntersect()

bool hpp::fcl::details::capsulePlaneIntersect ( const Capsule s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 2009 of file details.h.

◆ compareContactPoints()

bool hpp::fcl::details::compareContactPoints ( const ContactPoint c1,
const ContactPoint c2 
)
inline

Definition at line 1334 of file details.h.

◆ computePenetration() [1/2]

FCL_REAL hpp::fcl::details::computePenetration ( const Vec3f P1,
const Vec3f P2,
const Vec3f P3,
const Vec3f Q1,
const Vec3f Q2,
const Vec3f Q3,
const Transform3f tf1,
const Transform3f tf2,
Vec3f normal 
)
inline

Definition at line 2496 of file details.h.

◆ computePenetration() [2/2]

FCL_REAL hpp::fcl::details::computePenetration ( const Vec3f P1,
const Vec3f P2,
const Vec3f P3,
const Vec3f Q1,
const Vec3f Q2,
const Vec3f Q3,
Vec3f normal 
)
inline

See the prototype below.

Definition at line 2477 of file details.h.

◆ coneHalfspaceIntersect()

bool hpp::fcl::details::coneHalfspaceIntersect ( const Cone s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 1566 of file details.h.

◆ conePlaneIntersect()

bool hpp::fcl::details::conePlaneIntersect ( const Cone s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 2185 of file details.h.

◆ convexHalfspaceIntersect()

bool hpp::fcl::details::convexHalfspaceIntersect ( const ConvexBase s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
Vec3f contact_points,
FCL_REAL penetration_depth,
Vec3f normal 
)
inline

Definition at line 1618 of file details.h.

◆ convexPlaneIntersect()

bool hpp::fcl::details::convexPlaneIntersect ( const ConvexBase s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
Vec3f contact_points,
FCL_REAL penetration_depth,
Vec3f normal 
)
inline

Definition at line 2298 of file details.h.

◆ cullPoints2()

static void hpp::fcl::details::cullPoints2 ( unsigned int  n,
FCL_REAL  p[],
unsigned int  m,
unsigned int  i0,
unsigned int  iret[] 
)
inlinestatic

Definition at line 695 of file details.h.

◆ cylinderHalfspaceIntersect()

bool hpp::fcl::details::cylinderHalfspaceIntersect ( const Cylinder s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 1513 of file details.h.

◆ cylinderPlaneIntersect()

bool hpp::fcl::details::cylinderPlaneIntersect ( const Cylinder s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

cylinder-plane intersect n^T (R (r * cosa * v1 + r * sina * v2 + h * v3) + T) ~ d need one point to be positive and one to be negative (n^T * v3) * h + n * T -d + r * (cosa * (n^T * R * v1) + sina * (n^T * R * v2)) ~ 0 (n^T * v3) * h + r * (cosa * (n^T * R * v1) + sina * (n^T * R * v2)) + n * T - d ~ 0

Definition at line 2109 of file details.h.

◆ extractBVH()

CollisionGeometry* hpp::fcl::details::extractBVH ( const CollisionGeometry model,
const Transform3f pose,
const AABB aabb 
)

Definition at line 43 of file collision_utility.cpp.

◆ extractBVHtpl()

template<typename NT >
CollisionGeometry* hpp::fcl::details::extractBVHtpl ( const CollisionGeometry model,
const Transform3f pose,
const AABB aabb 
)
inline

Definition at line 26 of file collision_utility.cpp.

◆ getBoundVertices() [1/8]

std::vector<Vec3f> hpp::fcl::details::getBoundVertices ( const Box box,
const Transform3f tf 
)

Definition at line 47 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [2/8]

std::vector<Vec3f> hpp::fcl::details::getBoundVertices ( const Capsule capsule,
const Transform3f tf 
)

Definition at line 124 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [3/8]

std::vector<Vec3f> hpp::fcl::details::getBoundVertices ( const Cone cone,
const Transform3f tf 
)

Definition at line 180 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [4/8]

std::vector<Vec3f> hpp::fcl::details::getBoundVertices ( const ConvexBase convex,
const Transform3f tf 
)

Definition at line 226 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [5/8]

std::vector<Vec3f> hpp::fcl::details::getBoundVertices ( const Cylinder cylinder,
const Transform3f tf 
)

Definition at line 200 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [6/8]

std::vector<Vec3f> hpp::fcl::details::getBoundVertices ( const Ellipsoid ellipsoid,
const Transform3f tf 
)

Definition at line 90 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [7/8]

std::vector<Vec3f> hpp::fcl::details::getBoundVertices ( const Sphere sphere,
const Transform3f tf 
)

Definition at line 65 of file geometric_shapes_utility.cpp.

◆ getBoundVertices() [8/8]

std::vector<Vec3f> hpp::fcl::details::getBoundVertices ( const TriangleP triangle,
const Transform3f tf 
)

Definition at line 236 of file geometric_shapes_utility.cpp.

◆ getNormalizeSupportDirection()

bool hpp::fcl::details::getNormalizeSupportDirection ( const ShapeBase shape)

Definition at line 450 of file src/narrowphase/gjk.cpp.

◆ getNormalizeSupportDirectionFromShapes()

void hpp::fcl::details::getNormalizeSupportDirectionFromShapes ( const ShapeBase shape0,
const ShapeBase shape1,
bool &  normalize_support_direction 
)

Definition at line 481 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [1/10]

void hpp::fcl::details::getShapeSupport ( const Box box,
const Vec3f dir,
Vec3f support,
int &  ,
MinkowskiDiff::ShapeData  
)
inline

Definition at line 66 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [2/10]

void hpp::fcl::details::getShapeSupport ( const Capsule capsule,
const Vec3f dir,
Vec3f support,
int &  ,
MinkowskiDiff::ShapeData  
)
inline

Definition at line 92 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [3/10]

void hpp::fcl::details::getShapeSupport ( const Cone cone,
const Vec3f dir,
Vec3f support,
int &  ,
MinkowskiDiff::ShapeData  
)

Definition at line 101 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [4/10]

void hpp::fcl::details::getShapeSupport ( const ConvexBase convex,
const Vec3f dir,
Vec3f support,
int &  hint,
MinkowskiDiff::ShapeData  
)

Definition at line 227 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [5/10]

void hpp::fcl::details::getShapeSupport ( const Cylinder cylinder,
const Vec3f dir,
Vec3f support,
int &  ,
MinkowskiDiff::ShapeData  
)

Definition at line 139 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [6/10]

void hpp::fcl::details::getShapeSupport ( const Ellipsoid ellipsoid,
const Vec3f dir,
Vec3f support,
int &  ,
MinkowskiDiff::ShapeData  
)
inline

Definition at line 79 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [7/10]

void hpp::fcl::details::getShapeSupport ( const LargeConvex convex,
const Vec3f dir,
Vec3f support,
int &  hint,
MinkowskiDiff::ShapeData data 
)
inline

Definition at line 245 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [8/10]

void hpp::fcl::details::getShapeSupport ( const SmallConvex convex,
const Vec3f dir,
Vec3f support,
int &  hint,
MinkowskiDiff::ShapeData data 
)
inline

Definition at line 238 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [9/10]

void hpp::fcl::details::getShapeSupport ( const Sphere ,
const Vec3f ,
Vec3f support,
int &  ,
MinkowskiDiff::ShapeData  
)
inline

Definition at line 74 of file src/narrowphase/gjk.cpp.

◆ getShapeSupport() [10/10]

void hpp::fcl::details::getShapeSupport ( const TriangleP triangle,
const Vec3f dir,
Vec3f support,
int &  ,
MinkowskiDiff::ShapeData  
)

Definition at line 48 of file src/narrowphase/gjk.cpp.

◆ getShapeSupportLinear()

void hpp::fcl::details::getShapeSupportLinear ( const ConvexBase convex,
const Vec3f dir,
Vec3f support,
int &  hint,
MinkowskiDiff::ShapeData  
)

Definition at line 210 of file src/narrowphase/gjk.cpp.

◆ getShapeSupportLog()

void hpp::fcl::details::getShapeSupportLog ( const ConvexBase convex,
const Vec3f dir,
Vec3f support,
int &  hint,
MinkowskiDiff::ShapeData data 
)

Definition at line 169 of file src/narrowphase/gjk.cpp.

◆ getSupport()

Vec3f hpp::fcl::details::getSupport ( const ShapeBase shape,
const Vec3f dir,
bool  dirIsNormalized,
int &  hint 
)

the support function for shape

Parameters
hintuse to initialize the search when shape is a ConvexBase object.

Definition at line 260 of file src/narrowphase/gjk.cpp.

◆ getSupportFuncTpl()

template<typename Shape0 , typename Shape1 , bool TransformIsIdentity>
void hpp::fcl::details::getSupportFuncTpl ( const MinkowskiDiff md,
const Vec3f dir,
bool  dirIsNormalized,
Vec3f support0,
Vec3f support1,
support_func_guess_t hint,
MinkowskiDiff::ShapeData  data[2] 
)

Definition at line 315 of file src/narrowphase/gjk.cpp.

◆ getSupportTpl()

template<typename Shape0 , typename Shape1 , bool TransformIsIdentity>
void hpp::fcl::details::getSupportTpl ( const Shape0 *  s0,
const Shape1 *  s1,
const Matrix3f oR1,
const Vec3f ot1,
const Vec3f dir,
Vec3f support0,
Vec3f support1,
support_func_guess_t hint,
MinkowskiDiff::ShapeData  data[2] 
)

Definition at line 301 of file src/narrowphase/gjk.cpp.

◆ halfspaceDistance()

bool hpp::fcl::details::halfspaceDistance ( const Halfspace h,
const Transform3f tf1,
const ShapeBase s,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline
Parameters
p1closest (or most penetrating) point on the Halfspace,
p2closest (or most penetrating) point on the shape,
normalthe halfspace normal.
Returns
true if the distance is negative (the shape overlaps).

Definition at line 1808 of file details.h.

◆ halfspaceIntersect()

bool hpp::fcl::details::halfspaceIntersect ( const Halfspace s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
Vec3f p,
Vec3f d,
Halfspace s,
FCL_REAL penetration_depth,
int &  ret 
)
inline

@ brief return whether two halfspace intersect if the separation planes of the two halfspaces are parallel return code 1, if two halfspaces' normal are same and s1 is in s2, also return s1 in s; return code 2, if two halfspaces' normal are same and s2 is in s1, also return s2 in s; return code 3, if two halfspaces' normal are opposite and s1 and s2 are into each other; collision free, if two halfspaces' are separate; if the separation planes of the two halfspaces are not parallel, return intersection ray, return code 4. ray origin is p and direction is d collision free return code 0

Definition at line 1756 of file details.h.

◆ halfspaceIntersectTolerance() [1/2]

template<typename T >
T hpp::fcl::details::halfspaceIntersectTolerance ( )
inline

Definition at line 1366 of file details.h.

◆ halfspaceIntersectTolerance() [2/2]

template<>
double hpp::fcl::details::halfspaceIntersectTolerance ( )
inline

Definition at line 1371 of file details.h.

◆ halfspacePlaneIntersect()

bool hpp::fcl::details::halfspacePlaneIntersect ( const Halfspace s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
Plane pl,
Vec3f p,
Vec3f d,
FCL_REAL penetration_depth,
int &  ret 
)
inline

Definition at line 2454 of file details.h.

◆ halfspaceTriangleIntersect()

bool hpp::fcl::details::halfspaceTriangleIntersect ( const Halfspace s1,
const Transform3f tf1,
const Vec3f P1,
const Vec3f P2,
const Vec3f P3,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 1652 of file details.h.

◆ intersectRectQuad2()

static unsigned int hpp::fcl::details::intersectRectQuad2 ( FCL_REAL  h[2],
FCL_REAL  p[8],
FCL_REAL  ret[16] 
)
static

Definition at line 633 of file details.h.

◆ lineClosestApproach()

static void hpp::fcl::details::lineClosestApproach ( const Vec3f pa,
const Vec3f ua,
const Vec3f pb,
const Vec3f ub,
FCL_REAL alpha,
FCL_REAL beta 
)
inlinestatic

Definition at line 608 of file details.h.

◆ lineSegmentPointClosestToPoint()

static void hpp::fcl::details::lineSegmentPointClosestToPoint ( const Vec3f p,
const Vec3f s1,
const Vec3f s2,
Vec3f sp 
)
inlinestatic

Definition at line 51 of file details.h.

◆ makeGetSupportFunction0()

MinkowskiDiff::GetSupportFunction hpp::fcl::details::makeGetSupportFunction0 ( const ShapeBase s0,
const ShapeBase s1,
bool  identity,
Eigen::Array< FCL_REAL, 1, 2 > &  inflation,
int  linear_log_convex_threshold 
)

Definition at line 401 of file src/narrowphase/gjk.cpp.

◆ makeGetSupportFunction1()

template<typename Shape0 >
MinkowskiDiff::GetSupportFunction hpp::fcl::details::makeGetSupportFunction1 ( const ShapeBase s1,
bool  identity,
Eigen::Array< FCL_REAL, 1, 2 > &  inflation,
int  linear_log_convex_threshold 
)

Definition at line 341 of file src/narrowphase/gjk.cpp.

◆ orientedBVHShapeDistance()

template<typename OrientedMeshShapeDistanceTraversalNode , typename T_BVH , typename T_SH >
FCL_REAL hpp::fcl::details::orientedBVHShapeDistance ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver nsolver,
const DistanceRequest request,
DistanceResult result 
)

Definition at line 112 of file distance_func_matrix.cpp.

◆ orientedMeshCollide()

template<typename OrientedMeshCollisionTraversalNode , typename T_BVH >
std::size_t hpp::fcl::details::orientedMeshCollide ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const CollisionRequest request,
CollisionResult result 
)

Definition at line 193 of file collision_func_matrix.cpp.

◆ orientedMeshDistance()

template<typename OrientedMeshDistanceTraversalNode , typename T_BVH >
FCL_REAL hpp::fcl::details::orientedMeshDistance ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const DistanceRequest request,
DistanceResult result 
)

Definition at line 224 of file distance_func_matrix.cpp.

◆ originToPoint()

void hpp::fcl::details::originToPoint ( const GJK::Simplex current,
GJK::vertex_id_t  a,
const Vec3f A,
GJK::Simplex next,
Vec3f ray 
)
inline

Definition at line 925 of file src/narrowphase/gjk.cpp.

◆ originToSegment()

void hpp::fcl::details::originToSegment ( const GJK::Simplex current,
GJK::vertex_id_t  a,
GJK::vertex_id_t  b,
const Vec3f A,
const Vec3f B,
const Vec3f AB,
const FCL_REAL ABdotAO,
GJK::Simplex next,
Vec3f ray 
)
inline

Definition at line 933 of file src/narrowphase/gjk.cpp.

◆ originToTriangle()

bool hpp::fcl::details::originToTriangle ( const GJK::Simplex current,
GJK::vertex_id_t  a,
GJK::vertex_id_t  b,
GJK::vertex_id_t  c,
const Vec3f ABC,
const FCL_REAL ABCdotAO,
GJK::Simplex next,
Vec3f ray 
)
inline

Definition at line 948 of file src/narrowphase/gjk.cpp.

◆ planeHalfspaceIntersect()

bool hpp::fcl::details::planeHalfspaceIntersect ( const Plane s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
Plane pl,
Vec3f p,
Vec3f d,
FCL_REAL penetration_depth,
int &  ret 
)
inline

return whether plane collides with halfspace if the separation plane of the halfspace is parallel with the plane return code 1, if the plane's normal is the same with halfspace's normal and plane is inside halfspace, also return plane in pl return code 2, if the plane's normal is oppositie to the halfspace's normal and plane is inside halfspace, also return plane in pl plane is outside halfspace, collision-free if not parallel return the intersection ray, return code 3. ray origin is p and direction is d

Definition at line 1700 of file details.h.

◆ planeIntersect()

bool hpp::fcl::details::planeIntersect ( const Plane s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
Vec3f ,
FCL_REAL ,
Vec3f  
)
inline

Definition at line 2462 of file details.h.

◆ planeIntersectTolerance()

template<typename T >
T hpp::fcl::details::planeIntersectTolerance ( )
inline

Definition at line 1826 of file details.h.

◆ planeIntersectTolerance< double >()

template<>
double hpp::fcl::details::planeIntersectTolerance< double > ( )
inline

Definition at line 1831 of file details.h.

◆ planeIntersectTolerance< float >()

template<>
float hpp::fcl::details::planeIntersectTolerance< float > ( )
inline

Definition at line 1836 of file details.h.

◆ planeTriangleIntersect()

bool hpp::fcl::details::planeTriangleIntersect ( const Plane s1,
const Transform3f tf1,
const Vec3f P1,
const Vec3f P2,
const Vec3f P3,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 2339 of file details.h.

◆ projectInTriangle()

bool hpp::fcl::details::projectInTriangle ( const Vec3f p1,
const Vec3f p2,
const Vec3f p3,
const Vec3f normal,
const Vec3f p 
)
inline

Whether a point's projection is in a triangle.

Definition at line 299 of file details.h.

◆ segmentSqrDistance()

FCL_REAL hpp::fcl::details::segmentSqrDistance ( const Vec3f from,
const Vec3f to,
const Vec3f p,
Vec3f nearest 
)
inline

the minimum distance from a point to a line

Definition at line 276 of file details.h.

◆ sphereCapsuleDistance()

bool hpp::fcl::details::sphereCapsuleDistance ( const Sphere s1,
const Transform3f tf1,
const Capsule s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 101 of file details.h.

◆ sphereCapsuleIntersect()

bool hpp::fcl::details::sphereCapsuleIntersect ( const Sphere s1,
const Transform3f tf1,
const Capsule s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f contact_points,
Vec3f normal_ 
)
inline

Definition at line 71 of file details.h.

◆ sphereCylinderDistance()

bool hpp::fcl::details::sphereCylinderDistance ( const Sphere s1,
const Transform3f tf1,
const Cylinder s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline
Todo:
a tiny performance improvement could be achieved using the abscissa with S as the origin

Definition at line 132 of file details.h.

◆ sphereHalfspaceIntersect()

bool hpp::fcl::details::sphereHalfspaceIntersect ( const Sphere s1,
const Transform3f tf1,
const Halfspace s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 1380 of file details.h.

◆ spherePlaneIntersect()

bool hpp::fcl::details::spherePlaneIntersect ( const Sphere s1,
const Transform3f tf1,
const Plane s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 1840 of file details.h.

◆ sphereSphereDistance()

bool hpp::fcl::details::sphereSphereDistance ( const Sphere s1,
const Transform3f tf1,
const Sphere s2,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2,
Vec3f normal 
)
inline

Definition at line 258 of file details.h.

◆ sphereSphereIntersect()

bool hpp::fcl::details::sphereSphereIntersect ( const Sphere s1,
const Transform3f tf1,
const Sphere s2,
const Transform3f tf2,
FCL_REAL distance,
Vec3f contact_points,
Vec3f normal 
)
inline

Definition at line 232 of file details.h.

◆ sphereTriangleDistance() [1/3]

bool hpp::fcl::details::sphereTriangleDistance ( const Sphere sp,
const Transform3f tf,
const Vec3f P1,
const Vec3f P2,
const Vec3f P3,
FCL_REAL dist 
)
inline

Definition at line 381 of file details.h.

◆ sphereTriangleDistance() [2/3]

bool hpp::fcl::details::sphereTriangleDistance ( const Sphere sp,
const Transform3f tf,
const Vec3f P1,
const Vec3f P2,
const Vec3f P3,
FCL_REAL dist,
Vec3f p1,
Vec3f p2 
)
inline

Definition at line 563 of file details.h.

◆ sphereTriangleDistance() [3/3]

bool hpp::fcl::details::sphereTriangleDistance ( const Sphere sp,
const Transform3f tf1,
const Vec3f P1,
const Vec3f P2,
const Vec3f P3,
const Transform3f tf2,
FCL_REAL dist,
Vec3f p1,
Vec3f p2 
)
inline

Definition at line 590 of file details.h.

◆ sphereTriangleIntersect()

bool hpp::fcl::details::sphereTriangleIntersect ( const Sphere s,
const Transform3f tf1,
const Vec3f P1,
const Vec3f P2,
const Vec3f P3,
FCL_REAL distance,
Vec3f p1,
Vec3f p2,
Vec3f normal_ 
)
inline

Definition at line 324 of file details.h.

Variable Documentation

◆ EPA_EPS

const FCL_REAL hpp::fcl::details::EPA_EPS = 0.000001
static

Definition at line 308 of file gjk.h.

◆ EPA_MAX_FACES

const size_t hpp::fcl::details::EPA_MAX_FACES = 128
static

Definition at line 306 of file gjk.h.

◆ EPA_MAX_ITERATIONS

const size_t hpp::fcl::details::EPA_MAX_ITERATIONS = 255
static

Definition at line 309 of file gjk.h.

◆ EPA_MAX_VERTICES

const size_t hpp::fcl::details::EPA_MAX_VERTICES = 64
static

Definition at line 307 of file gjk.h.



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