|
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...
|
|
CollisionGeometry * | extractBVH (const CollisionGeometry *model, const Transform3f &pose, const AABB &aabb) |
|
template<typename NT > |
CollisionGeometry * | extractBVHtpl (const CollisionGeometry *model, const Transform3f &pose, const AABB &aabb) |
|
std::vector< Vec3f > | getBoundVertices (const Box &box, const Transform3f &tf) |
|
std::vector< Vec3f > | getBoundVertices (const Capsule &capsule, const Transform3f &tf) |
|
std::vector< Vec3f > | getBoundVertices (const Cone &cone, const Transform3f &tf) |
|
std::vector< Vec3f > | getBoundVertices (const ConvexBase &convex, const Transform3f &tf) |
|
std::vector< Vec3f > | getBoundVertices (const Cylinder &cylinder, const Transform3f &tf) |
|
std::vector< Vec3f > | getBoundVertices (const Ellipsoid &ellipsoid, const Transform3f &tf) |
|
std::vector< Vec3f > | getBoundVertices (const Sphere &sphere, const Transform3f &tf) |
|
std::vector< Vec3f > | getBoundVertices (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 > |
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 ¤t, GJK::vertex_id_t a, const Vec3f &A, GJK::Simplex &next, Vec3f &ray) |
|
void | originToSegment (const GJK::Simplex ¤t, 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 ¤t, 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 > |
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_) |
|