FCL internals. Ignore this :) unless you are God. More...
Namespaces | |
namespace | dynamic_AABB_tree |
namespace | dynamic_AABB_tree_array |
Classes | |
struct | ccd_box_t |
struct | ccd_cap_t |
struct | ccd_cone_t |
struct | ccd_convex_t |
struct | ccd_cyl_t |
struct | ccd_obj_t |
struct | ccd_sphere_t |
struct | ccd_triangle_t |
struct | ContactPoint |
struct | EPA |
class for EPA algorithm More... | |
struct | GJK |
class for GJK algorithm More... | |
class | GJKInitializer |
initialize GJK stuffs More... | |
class | GJKInitializer< Box > |
initialize GJK Box More... | |
class | GJKInitializer< Capsule > |
initialize GJK Capsule More... | |
class | GJKInitializer< Cone > |
initialize GJK Cone More... | |
class | GJKInitializer< Convex > |
initialize GJK Convex More... | |
class | GJKInitializer< Cylinder > |
initialize GJK Cylinder More... | |
class | GJKInitializer< Sphere > |
initialize GJK Sphere More... | |
struct | Matrix3Data |
struct | MinkowskiDiff |
Minkowski difference class of two shapes. More... | |
struct | sse_meta_d4 |
struct | sse_meta_f12 |
struct | sse_meta_f16 |
struct | sse_meta_f4 |
struct | Vec3Data |
Typedefs | |
typedef void(* | GJKCenterFunction )(const void *obj, ccd_vec3_t *c) |
typedef void(* | GJKSupportFunction )(const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) |
callback function used by GJK algorithm | |
Functions | |
struct fcl::details::sse_meta_f4 | __attribute__ ((aligned(16))) |
static ccd_real_t | __ccdGJKDist (const void *obj1, const void *obj2, const ccd_t *ccd, ccd_simplex_t *simplex, ccd_real_t tolerance) |
template<typename T > | |
static Vec3Data< T > | abs (const Vec3Data< T > &x) |
static sse_meta_f4 | abs (const sse_meta_f4 &x) |
static sse_meta_d4 | abs (const sse_meta_d4 &x) |
template<typename T > | |
Matrix3Data< T > | abs (const Matrix3Data< T > &m) |
static sse_meta_f12 | abs (const sse_meta_f12 &mat) |
static sse_meta_f16 | abs (const sse_meta_f16 &mat) |
int | boxBox2 (const Vec3f &side1, const Matrix3f &R1, const Vec3f &T1, const Vec3f &side2, const Matrix3f &R2, const Vec3f &T2, Vec3f &normal, FCL_REAL *depth, int *return_code, 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 | |
bool | boxHalfspaceIntersect (const Box &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
bool | boxPlaneIntersect (const Box &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, 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. | |
static void | boxToGJK (const Box &s, const Transform3f &tf, ccd_box_t *box) |
bool | capsuleHalfspaceIntersect (const Capsule &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
bool | capsulePlaneIntersect (const Capsule &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2) |
bool | capsulePlaneIntersect (const Capsule &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
static void | capToGJK (const Capsule &s, const Transform3f &tf, ccd_cap_t *cap) |
static void | centerConvex (const void *obj, ccd_vec3_t *c) |
static void | centerShape (const void *obj, ccd_vec3_t *c) |
static void | centerTriangle (const void *obj, ccd_vec3_t *c) |
bool | coneHalfspaceIntersect (const Cone &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
bool | conePlaneIntersect (const Cone &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
static void | coneToGJK (const Cone &s, const Transform3f &tf, ccd_cone_t *cone) |
bool | convexHalfspaceIntersect (const Convex &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
bool | convexPlaneIntersect (const Convex &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
static void | convexToGJK (const Convex &s, const Transform3f &tf, ccd_convex_t *conv) |
template<typename T > | |
static Vec3Data< T > | cross_prod (const Vec3Data< T > &l, const Vec3Data< T > &r) |
static __m128 | cross_prod (__m128 x, __m128 y) |
static sse_meta_f4 | cross_prod (const sse_meta_f4 &x, const sse_meta_f4 &y) |
static void | cross_prod (__m128d x0, __m128d x1, __m128d y0, __m128d y1, __m128d *z0, __m128d *z1) |
static sse_meta_d4 | cross_prod (const sse_meta_d4 &x, const sse_meta_d4 &y) |
static void | cullPoints2 (int n, FCL_REAL p[], int m, int i0, int iret[]) |
bool | cylinderHalfspaceIntersect (const Cylinder &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
bool | cylinderPlaneIntersect (const Cylinder &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2) |
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 | |
bool | cylinderPlaneIntersect (const Cylinder &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
static void | cylToGJK (const Cylinder &s, const Transform3f &tf, ccd_cyl_t *cyl) |
template<typename BV > | |
static void | distancePostprocessOrientedNode (const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Transform3f &tf1, const DistanceRequest &request, DistanceResult &result) |
template<typename BV > | |
static void | distancePreprocessOrientedNode (const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, int init_tri_id1, int init_tri_id2, const Matrix3f &R, const Vec3f &T, const DistanceRequest &request, DistanceResult &result) |
static int | doSimplex2Dist (ccd_simplex_t *simplex, ccd_vec3_t *dir, ccd_real_t *dist) |
static int | doSimplex3Dist (ccd_simplex_t *simplex, ccd_vec3_t *dir, ccd_real_t *dist) |
static int | doSimplex4Dist (ccd_simplex_t *simplex, ccd_vec3_t *dir, ccd_real_t *dist) |
static int | doSimplexDist (ccd_simplex_t *simplex, ccd_vec3_t *dir, ccd_real_t *dist) |
template<typename T > | |
static T | dot_prod3 (const Vec3Data< T > &l, const Vec3Data< T > &r) |
static __m128 | dot_prod3 (__m128 x, __m128 y) |
static float | dot_prod3 (const sse_meta_f4 &x, const sse_meta_f4 &y) |
static __m128d | dot_prod3 (__m128d x0, __m128d x1, __m128d y0, __m128d y1) |
static double | dot_prod3 (const sse_meta_d4 &x, const sse_meta_d4 &y) |
static __m128 | dot_prod4 (__m128 x, __m128 y) |
static float | dot_prod4 (const sse_meta_f4 &x, const sse_meta_f4 &y) |
static __m128d | dot_prod4 (__m128d x0, __m128d x1, __m128d y0, __m128d y1) |
static double | dot_prod4 (const sse_meta_d4 &x, const sse_meta_d4 &y) |
template<typename T > | |
static bool | equal (const Vec3Data< T > &x, const Vec3Data< T > &y, T epsilon) |
static bool | equal (const sse_meta_f4 &x, const sse_meta_f4 &y, float epsilon) |
static bool | equal (const sse_meta_d4 &x, const sse_meta_d4 &y, double epsilon) |
std::vector< Vec3f > | getBoundVertices (const Box &box, const Transform3f &tf) |
std::vector< Vec3f > | getBoundVertices (const Sphere &sphere, 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 Cylinder &cylinder, const Transform3f &tf) |
std::vector< Vec3f > | getBoundVertices (const Convex &convex, const Transform3f &tf) |
std::vector< Vec3f > | getBoundVertices (const Triangle2 &triangle, const Transform3f &tf) |
Vec3f | getSupport (const ShapeBase *shape, const Vec3f &dir) |
the support function for shape | |
bool | GJKCollide (void *obj1, ccd_support_fn supp1, ccd_center_fn cen1, void *obj2, ccd_support_fn supp2, ccd_center_fn cen2, unsigned int max_iterations, FCL_REAL tolerance, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
GJK collision algorithm. | |
bool | GJKDistance (void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, FCL_REAL tolerance, FCL_REAL *dist) |
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, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
static int | intersectRectQuad2 (FCL_REAL h[2], FCL_REAL p[8], FCL_REAL ret[16]) |
static void | inverse (__m128 c0, __m128 c1, __m128 c2, __m128 *i0, __m128 *i1, __m128 *i2) |
template<typename T > | |
Matrix3Data< T > | inverse (const Matrix3Data< T > &m) |
static sse_meta_f12 | inverse (const sse_meta_f12 &mat) |
static void | inverse (__m128 c0, __m128 c1, __m128 c2, __m128 c3, __m128 *res0, __m128 *res1, __m128 *res2, __m128 *res3) |
static sse_meta_f16 | inverse (const sse_meta_f16 &mat) |
static void | lineClosestApproach (const Vec3f &pa, const Vec3f &ua, const Vec3f &pb, const Vec3f &ub, FCL_REAL *alpha, FCL_REAL *beta) |
template<typename T > | |
static Vec3Data< T > | max (const Vec3Data< T > &x, const Vec3Data< T > &y) |
static sse_meta_f4 | max (const sse_meta_f4 &x, const sse_meta_f4 &y) |
static sse_meta_d4 | max (const sse_meta_d4 &x, const sse_meta_d4 &y) |
template<typename BV > | |
static void | meshCollisionOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Matrix3f &R, const Vec3f &T, const Transform3f &tf1, const Transform3f &tf2, bool enable_statistics, FCL_REAL cost_density, int &num_leaf_tests, const CollisionRequest &request, CollisionResult &result) |
template<typename BV > | |
static void | meshDistanceOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Matrix3f &R, const Vec3f &T, bool enable_statistics, int &num_leaf_tests, const DistanceRequest &request, DistanceResult &result) |
template<typename T > | |
static Vec3Data< T > | min (const Vec3Data< T > &x, const Vec3Data< T > &y) |
static sse_meta_f4 | min (const sse_meta_f4 &x, const sse_meta_f4 &y) |
static sse_meta_d4 | min (const sse_meta_d4 &x, const sse_meta_d4 &y) |
static __m128 | newtonraphson_rsqrt4 (const __m128 v) |
static sse_meta_f4 | normalize3 (const sse_meta_f4 &x) |
static sse_meta_f4 | normalize3_approx (const sse_meta_f4 &x) |
template<typename OrientMeshShapeCollisionTraveralNode , typename T_BVH , typename T_SH , typename NarrowPhaseSolver > | |
std::size_t | orientedBVHShapeCollide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result) |
template<typename OrientedMeshShapeDistanceTraversalNode , typename T_BVH , typename T_SH , typename NarrowPhaseSolver > | |
FCL_REAL | orientedBVHShapeDistance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const NarrowPhaseSolver *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) |
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 | |
bool | planeIntersect (const Plane &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
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, Vec3f *contact_points, FCL_REAL *penetration_depth, 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. | |
FCL_REAL | projectOrigin (const Vec3f &a, const Vec3f &b, FCL_REAL *w, size_t &m) |
project origin on to a line (a, b). w[0:1] return the (0, 1) parameterization of the projected point. m is a encode about the result case: 0x10--> project is larger than b; 0x01--> project is smaller than a; 0x11-> within the line; return value is distance between the origin and its projection. | |
FCL_REAL | projectOrigin (const Vec3f &a, const Vec3f &b, const Vec3f &c, FCL_REAL *w, size_t &m) |
project origin on to a triangle (a, b, c). w[0:2] return the (0, 1) parameterization of the projected point. m is a encode about the result case. return value is distance between the origin and its projection. | |
FCL_REAL | projectOrigin (const Vec3f &a, const Vec3f &b, const Vec3f &c, const Vec3f &d, FCL_REAL *w, size_t &m) |
project origin on to a tetrahedra (a, b, c, d). w[0:3] return the (0, 1) parameterization of the projected point. m is a encode about the result case. return value is distance between the origin and its projection. | |
FCL_REAL | segmentSqrDistance (const Vec3f &from, const Vec3f &to, const Vec3f &p, Vec3f &nearest) |
the minimum distance from a point to a line | |
template<typename BV , typename OrientedNode > | |
static bool | setupMeshCollisionOrientedNode (OrientedNode &node, const BVHModel< BV > &model1, const Transform3f &tf1, const BVHModel< BV > &model2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result) |
template<typename BV , typename OrientedNode > | |
static bool | setupMeshDistanceOrientedNode (OrientedNode &node, const BVHModel< BV > &model1, const Transform3f &tf1, const BVHModel< BV > &model2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result) |
template<typename S , typename BV , typename NarrowPhaseSolver , template< typename, typename > class OrientedNode> | |
static bool | setupShapeMeshDistanceOrientedNode (OrientedNode< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< BV > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result) |
static void | shapeToGJK (const ShapeBase &s, const Transform3f &tf, ccd_obj_t *o) |
bool | sphereHalfspaceIntersect (const Sphere &s1, const Transform3f &tf1, const Halfspace &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
bool | spherePlaneIntersect (const Sphere &s1, const Transform3f &tf1, const Plane &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
bool | sphereSphereDistance (const Sphere &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, FCL_REAL *dist) |
bool | sphereSphereIntersect (const Sphere &s1, const Transform3f &tf1, const Sphere &s2, const Transform3f &tf2, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal) |
static void | sphereToGJK (const Sphere &s, const Transform3f &tf, ccd_sphere_t *sph) |
bool | sphereTriangleDistance (const Sphere &sp, const Transform3f &tf, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, FCL_REAL *dist) |
bool | sphereTriangleIntersect (const Sphere &s, const Transform3f &tf, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, Vec3f *contact_points, FCL_REAL *penetration_depth, Vec3f *normal_) |
static void | supportBox (const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) |
static void | supportCap (const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) |
static void | supportCone (const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) |
static void | supportConvex (const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) |
static void | supportCyl (const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) |
static void | supportSphere (const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) |
static void | supportTriangle (const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) |
static void | transpose (__m128 c0, __m128 c1, __m128 c2, __m128 *r0, __m128 *r1, __m128 *r2) |
template<typename T > | |
Matrix3Data< T > | transpose (const Matrix3Data< T > &m) |
static sse_meta_f12 | transpose (const sse_meta_f12 &mat) |
static void | transpose (__m128 c0, __m128 c1, __m128 c2, __m128 c3, __m128 *r0, __m128 *r1, __m128 *r2, __m128 *r3) |
static sse_meta_f16 | transpose (const sse_meta_f16 &mat) |
void * | triCreateGJKObject (const Vec3f &P1, const Vec3f &P2, const Vec3f &P3) |
void * | triCreateGJKObject (const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Transform3f &tf) |
void | triDeleteGJKObject (void *o) |
GJKCenterFunction | triGetCenterFunction () |
GJKSupportFunction | triGetSupportFunction () |
initialize GJK Triangle | |
static void | tripleCross (const ccd_vec3_t *a, const ccd_vec3_t *b, const ccd_vec3_t *c, ccd_vec3_t *d) |
static __m128 | vec_sel (__m128 a, __m128 b, __m128 mask) |
static __m128 | vec_sel (__m128 a, __m128 b, const unsigned int *mask) |
static __m128 | vec_sel (__m128 a, __m128 b, unsigned int mask) |
Variables | |
struct fcl::details::sse_meta_f12 | __attribute__ |
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 |
const __m128d | xmmd_0 = {0, 0} |
const __m128 | xmms_0 = {0.f, 0.f, 0.f, 0.f} |
FCL internals. Ignore this :) unless you are God.
typedef void(* fcl::details::GJKCenterFunction)(const void *obj, ccd_vec3_t *c) |
Definition at line 55 of file gjk_libccd.h.
typedef void(* fcl::details::GJKSupportFunction)(const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) |
callback function used by GJK algorithm
Definition at line 54 of file gjk_libccd.h.
struct fcl::details::sse_meta_f4 fcl::details::__attribute__ | ( | (aligned(16)) | ) |
static ccd_real_t fcl::details::__ccdGJKDist | ( | const void * | obj1, |
const void * | obj2, | ||
const ccd_t * | ccd, | ||
ccd_simplex_t * | simplex, | ||
ccd_real_t | tolerance | ||
) | [static] |
Definition at line 363 of file gjk_libccd.cpp.
static Vec3Data<T> fcl::details::abs | ( | const Vec3Data< T > & | x | ) | [inline, static] |
Definition at line 154 of file math_details.h.
static sse_meta_f4 fcl::details::abs | ( | const sse_meta_f4 & | x | ) | [inline, static] |
Definition at line 395 of file math_simd_details.h.
static sse_meta_d4 fcl::details::abs | ( | const sse_meta_d4 & | x | ) | [inline, static] |
Definition at line 401 of file math_simd_details.h.
Matrix3Data<T> fcl::details::abs | ( | const Matrix3Data< T > & | m | ) |
Definition at line 467 of file math_details.h.
static sse_meta_f12 fcl::details::abs | ( | const sse_meta_f12 & | mat | ) | [inline, static] |
Definition at line 711 of file math_simd_details.h.
static sse_meta_f16 fcl::details::abs | ( | const sse_meta_f16 & | mat | ) | [inline, static] |
Definition at line 1122 of file math_simd_details.h.
int fcl::details::boxBox2 | ( | const Vec3f & | side1, |
const Matrix3f & | R1, | ||
const Vec3f & | T1, | ||
const Vec3f & | side2, | ||
const Matrix3f & | R2, | ||
const Vec3f & | T2, | ||
Vec3f & | normal, | ||
FCL_REAL * | depth, | ||
int * | return_code, | ||
int | maxc, | ||
std::vector< ContactPoint > & | contacts | ||
) |
Definition at line 653 of file narrowphase.cpp.
bool fcl::details::boxBoxIntersect | ( | const Box & | s1, |
const Transform3f & | tf1, | ||
const Box & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth_, | ||
Vec3f * | normal_ | ||
) |
Definition at line 1212 of file narrowphase.cpp.
bool fcl::details::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
Definition at line 1285 of file narrowphase.cpp.
bool fcl::details::boxHalfspaceIntersect | ( | const Box & | s1, |
const Transform3f & | tf1, | ||
const Halfspace & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
find deepest point
compute the contact point from the deepest point
Definition at line 1302 of file narrowphase.cpp.
bool fcl::details::boxPlaneIntersect | ( | const Box & | s1, |
const Transform3f & | tf1, | ||
const Plane & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
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.
Definition at line 1759 of file narrowphase.cpp.
static void fcl::details::boxToGJK | ( | const Box & | s, |
const Transform3f & | tf, | ||
ccd_box_t * | box | ||
) | [static] |
Definition at line 450 of file gjk_libccd.cpp.
bool fcl::details::capsuleHalfspaceIntersect | ( | const Capsule & | s1, |
const Transform3f & | tf1, | ||
const Halfspace & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 1364 of file narrowphase.cpp.
bool fcl::details::capsulePlaneIntersect | ( | const Capsule & | s1, |
const Transform3f & | tf1, | ||
const Plane & | s2, | ||
const Transform3f & | tf2 | ||
) |
Definition at line 1825 of file narrowphase.cpp.
bool fcl::details::capsulePlaneIntersect | ( | const Capsule & | s1, |
const Transform3f & | tf1, | ||
const Plane & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 1848 of file narrowphase.cpp.
static void fcl::details::capToGJK | ( | const Capsule & | s, |
const Transform3f & | tf, | ||
ccd_cap_t * | cap | ||
) | [static] |
Definition at line 458 of file gjk_libccd.cpp.
static void fcl::details::centerConvex | ( | const void * | obj, |
ccd_vec3_t * | c | ||
) | [static] |
Definition at line 671 of file gjk_libccd.cpp.
static void fcl::details::centerShape | ( | const void * | obj, |
ccd_vec3_t * | c | ||
) | [static] |
Definition at line 665 of file gjk_libccd.cpp.
static void fcl::details::centerTriangle | ( | const void * | obj, |
ccd_vec3_t * | c | ||
) | [static] |
Definition at line 679 of file gjk_libccd.cpp.
bool fcl::details::coneHalfspaceIntersect | ( | const Cone & | s1, |
const Transform3f & | tf1, | ||
const Halfspace & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 1463 of file narrowphase.cpp.
bool fcl::details::conePlaneIntersect | ( | const Cone & | s1, |
const Transform3f & | tf1, | ||
const Plane & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 2037 of file narrowphase.cpp.
static void fcl::details::coneToGJK | ( | const Cone & | s, |
const Transform3f & | tf, | ||
ccd_cone_t * | cone | ||
) | [static] |
Definition at line 472 of file gjk_libccd.cpp.
bool fcl::details::convexHalfspaceIntersect | ( | const Convex & | s1, |
const Transform3f & | tf1, | ||
const Halfspace & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 1518 of file narrowphase.cpp.
bool fcl::details::convexPlaneIntersect | ( | const Convex & | s1, |
const Transform3f & | tf1, | ||
const Plane & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 2147 of file narrowphase.cpp.
static void fcl::details::convexToGJK | ( | const Convex & | s, |
const Transform3f & | tf, | ||
ccd_convex_t * | conv | ||
) | [static] |
Definition at line 485 of file gjk_libccd.cpp.
static Vec3Data<T> fcl::details::cross_prod | ( | const Vec3Data< T > & | l, |
const Vec3Data< T > & | r | ||
) | [inline, static] |
Definition at line 127 of file math_details.h.
static __m128 fcl::details::cross_prod | ( | __m128 | x, |
__m128 | y | ||
) | [inline, static] |
Definition at line 255 of file math_simd_details.h.
static sse_meta_f4 fcl::details::cross_prod | ( | const sse_meta_f4 & | x, |
const sse_meta_f4 & | y | ||
) | [inline, static] |
Definition at line 271 of file math_simd_details.h.
static void fcl::details::cross_prod | ( | __m128d | x0, |
__m128d | x1, | ||
__m128d | y0, | ||
__m128d | y1, | ||
__m128d * | z0, | ||
__m128d * | z1 | ||
) | [inline, static] |
Definition at line 276 of file math_simd_details.h.
static sse_meta_d4 fcl::details::cross_prod | ( | const sse_meta_d4 & | x, |
const sse_meta_d4 & | y | ||
) | [inline, static] |
Definition at line 292 of file math_simd_details.h.
static void fcl::details::cullPoints2 | ( | int | n, |
FCL_REAL | p[], | ||
int | m, | ||
int | i0, | ||
int | iret[] | ||
) | [inline, static] |
Definition at line 578 of file narrowphase.cpp.
bool fcl::details::cylinderHalfspaceIntersect | ( | const Cylinder & | s1, |
const Transform3f & | tf1, | ||
const Halfspace & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 1411 of file narrowphase.cpp.
bool fcl::details::cylinderPlaneIntersect | ( | const Cylinder & | s1, |
const Transform3f & | tf1, | ||
const Plane & | s2, | ||
const Transform3f & | tf2 | ||
) |
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 1933 of file narrowphase.cpp.
bool fcl::details::cylinderPlaneIntersect | ( | const Cylinder & | s1, |
const Transform3f & | tf1, | ||
const Plane & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 1953 of file narrowphase.cpp.
static void fcl::details::cylToGJK | ( | const Cylinder & | s, |
const Transform3f & | tf, | ||
ccd_cyl_t * | cyl | ||
) | [static] |
Definition at line 465 of file gjk_libccd.cpp.
static void fcl::details::distancePostprocessOrientedNode | ( | const BVHModel< BV > * | model1, |
const BVHModel< BV > * | model2, | ||
const Transform3f & | tf1, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) | [inline, static] |
the points obtained by triDistance are not in world space: both are in object1's local coordinate system, so we need to convert them into the world space.
Definition at line 333 of file traversal_node_bvhs.cpp.
static void fcl::details::distancePreprocessOrientedNode | ( | const BVHModel< BV > * | model1, |
const BVHModel< BV > * | model2, | ||
const Vec3f * | vertices1, | ||
Vec3f * | vertices2, | ||
Triangle * | tri_indices1, | ||
Triangle * | tri_indices2, | ||
int | init_tri_id1, | ||
int | init_tri_id2, | ||
const Matrix3f & | R, | ||
const Vec3f & | T, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) | [inline, static] |
Definition at line 299 of file traversal_node_bvhs.cpp.
static int fcl::details::doSimplex2Dist | ( | ccd_simplex_t * | simplex, |
ccd_vec3_t * | dir, | ||
ccd_real_t * | dist | ||
) | [static] |
Definition at line 98 of file gjk_libccd.cpp.
static int fcl::details::doSimplex3Dist | ( | ccd_simplex_t * | simplex, |
ccd_vec3_t * | dir, | ||
ccd_real_t * | dist | ||
) | [static] |
Definition at line 146 of file gjk_libccd.cpp.
static int fcl::details::doSimplex4Dist | ( | ccd_simplex_t * | simplex, |
ccd_vec3_t * | dir, | ||
ccd_real_t * | dist | ||
) | [static] |
Definition at line 244 of file gjk_libccd.cpp.
static int fcl::details::doSimplexDist | ( | ccd_simplex_t * | simplex, |
ccd_vec3_t * | dir, | ||
ccd_real_t * | dist | ||
) | [static] |
Definition at line 341 of file gjk_libccd.cpp.
static T fcl::details::dot_prod3 | ( | const Vec3Data< T > & | l, |
const Vec3Data< T > & | r | ||
) | [inline, static] |
Definition at line 135 of file math_details.h.
static __m128 fcl::details::dot_prod3 | ( | __m128 | x, |
__m128 | y | ||
) | [inline, static] |
Definition at line 300 of file math_simd_details.h.
static float fcl::details::dot_prod3 | ( | const sse_meta_f4 & | x, |
const sse_meta_f4 & | y | ||
) | [inline, static] |
Definition at line 307 of file math_simd_details.h.
static __m128d fcl::details::dot_prod3 | ( | __m128d | x0, |
__m128d | x1, | ||
__m128d | y0, | ||
__m128d | y1 | ||
) | [inline, static] |
Definition at line 313 of file math_simd_details.h.
static double fcl::details::dot_prod3 | ( | const sse_meta_d4 & | x, |
const sse_meta_d4 & | y | ||
) | [inline, static] |
Definition at line 320 of file math_simd_details.h.
static __m128 fcl::details::dot_prod4 | ( | __m128 | x, |
__m128 | y | ||
) | [inline, static] |
Definition at line 327 of file math_simd_details.h.
static float fcl::details::dot_prod4 | ( | const sse_meta_f4 & | x, |
const sse_meta_f4 & | y | ||
) | [inline, static] |
Definition at line 343 of file math_simd_details.h.
static __m128d fcl::details::dot_prod4 | ( | __m128d | x0, |
__m128d | x1, | ||
__m128d | y0, | ||
__m128d | y1 | ||
) | [inline, static] |
Definition at line 348 of file math_simd_details.h.
static double fcl::details::dot_prod4 | ( | const sse_meta_d4 & | x, |
const sse_meta_d4 & | y | ||
) | [inline, static] |
Definition at line 368 of file math_simd_details.h.
static bool fcl::details::equal | ( | const Vec3Data< T > & | x, |
const Vec3Data< T > & | y, | ||
T | epsilon | ||
) | [inline, static] |
Definition at line 160 of file math_details.h.
static bool fcl::details::equal | ( | const sse_meta_f4 & | x, |
const sse_meta_f4 & | y, | ||
float | epsilon | ||
) | [inline, static] |
Definition at line 407 of file math_simd_details.h.
static bool fcl::details::equal | ( | const sse_meta_d4 & | x, |
const sse_meta_d4 & | y, | ||
double | epsilon | ||
) | [inline, static] |
Definition at line 414 of file math_simd_details.h.
std::vector<Vec3f> fcl::details::getBoundVertices | ( | const Box & | box, |
const Transform3f & | tf | ||
) |
Definition at line 47 of file geometric_shapes_utility.cpp.
std::vector<Vec3f> fcl::details::getBoundVertices | ( | const Sphere & | sphere, |
const Transform3f & | tf | ||
) |
Definition at line 66 of file geometric_shapes_utility.cpp.
std::vector<Vec3f> fcl::details::getBoundVertices | ( | const Capsule & | capsule, |
const Transform3f & | tf | ||
) |
Definition at line 90 of file geometric_shapes_utility.cpp.
std::vector<Vec3f> fcl::details::getBoundVertices | ( | const Cone & | cone, |
const Transform3f & | tf | ||
) |
Definition at line 148 of file geometric_shapes_utility.cpp.
std::vector<Vec3f> fcl::details::getBoundVertices | ( | const Cylinder & | cylinder, |
const Transform3f & | tf | ||
) |
Definition at line 169 of file geometric_shapes_utility.cpp.
std::vector<Vec3f> fcl::details::getBoundVertices | ( | const Convex & | convex, |
const Transform3f & | tf | ||
) |
Definition at line 195 of file geometric_shapes_utility.cpp.
std::vector<Vec3f> fcl::details::getBoundVertices | ( | const Triangle2 & | triangle, |
const Transform3f & | tf | ||
) |
Definition at line 206 of file geometric_shapes_utility.cpp.
Vec3f fcl::details::getSupport | ( | const ShapeBase * | shape, |
const Vec3f & | dir | ||
) |
bool fcl::details::GJKCollide | ( | void * | obj1, |
ccd_support_fn | supp1, | ||
ccd_center_fn | cen1, | ||
void * | obj2, | ||
ccd_support_fn | supp2, | ||
ccd_center_fn | cen2, | ||
unsigned int | max_iterations, | ||
FCL_REAL | tolerance, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
GJK collision algorithm.
Definition at line 687 of file gjk_libccd.cpp.
bool fcl::details::GJKDistance | ( | void * | obj1, |
ccd_support_fn | supp1, | ||
void * | obj2, | ||
ccd_support_fn | supp2, | ||
unsigned int | max_iterations, | ||
FCL_REAL | tolerance, | ||
FCL_REAL * | dist | ||
) |
Definition at line 754 of file gjk_libccd.cpp.
bool 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 | ||
) |
@ 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 1656 of file narrowphase.cpp.
T fcl::details::halfspaceIntersectTolerance | ( | ) |
Definition at line 1245 of file narrowphase.cpp.
double fcl::details::halfspaceIntersectTolerance | ( | ) |
Definition at line 1251 of file narrowphase.cpp.
bool 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 | ||
) |
Definition at line 2265 of file narrowphase.cpp.
bool fcl::details::halfspaceTriangleIntersect | ( | const Halfspace & | s1, |
const Transform3f & | tf1, | ||
const Vec3f & | P1, | ||
const Vec3f & | P2, | ||
const Vec3f & | P3, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 1550 of file narrowphase.cpp.
static int fcl::details::intersectRectQuad2 | ( | FCL_REAL | h[2], |
FCL_REAL | p[8], | ||
FCL_REAL | ret[16] | ||
) | [static] |
Definition at line 510 of file narrowphase.cpp.
static void fcl::details::inverse | ( | __m128 | c0, |
__m128 | c1, | ||
__m128 | c2, | ||
__m128 * | i0, | ||
__m128 * | i1, | ||
__m128 * | i2 | ||
) | [inline, static] |
Definition at line 457 of file math_simd_details.h.
Matrix3Data<T> fcl::details::inverse | ( | const Matrix3Data< T > & | m | ) |
Definition at line 482 of file math_details.h.
static sse_meta_f12 fcl::details::inverse | ( | const sse_meta_f12 & | mat | ) | [inline, static] |
Definition at line 724 of file math_simd_details.h.
static void fcl::details::inverse | ( | __m128 | c0, |
__m128 | c1, | ||
__m128 | c2, | ||
__m128 | c3, | ||
__m128 * | res0, | ||
__m128 * | res1, | ||
__m128 * | res2, | ||
__m128 * | res3 | ||
) | [inline, static] |
Definition at line 746 of file math_simd_details.h.
static sse_meta_f16 fcl::details::inverse | ( | const sse_meta_f16 & | mat | ) | [inline, static] |
Definition at line 1135 of file math_simd_details.h.
static void fcl::details::lineClosestApproach | ( | const Vec3f & | pa, |
const Vec3f & | ua, | ||
const Vec3f & | pb, | ||
const Vec3f & | ub, | ||
FCL_REAL * | alpha, | ||
FCL_REAL * | beta | ||
) | [inline, static] |
Definition at line 481 of file narrowphase.cpp.
static Vec3Data<T> fcl::details::max | ( | const Vec3Data< T > & | x, |
const Vec3Data< T > & | y | ||
) | [inline, static] |
Definition at line 148 of file math_details.h.
static sse_meta_f4 fcl::details::max | ( | const sse_meta_f4 & | x, |
const sse_meta_f4 & | y | ||
) | [inline, static] |
Definition at line 385 of file math_simd_details.h.
static sse_meta_d4 fcl::details::max | ( | const sse_meta_d4 & | x, |
const sse_meta_d4 & | y | ||
) | [inline, static] |
Definition at line 390 of file math_simd_details.h.
static void fcl::details::meshCollisionOrientedNodeLeafTesting | ( | int | b1, |
int | b2, | ||
const BVHModel< BV > * | model1, | ||
const BVHModel< BV > * | model2, | ||
Vec3f * | vertices1, | ||
Vec3f * | vertices2, | ||
Triangle * | tri_indices1, | ||
Triangle * | tri_indices2, | ||
const Matrix3f & | R, | ||
const Vec3f & | T, | ||
const Transform3f & | tf1, | ||
const Transform3f & | tf2, | ||
bool | enable_statistics, | ||
FCL_REAL | cost_density, | ||
int & | num_leaf_tests, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) | [inline, static] |
Definition at line 46 of file traversal_node_bvhs.cpp.
static void fcl::details::meshDistanceOrientedNodeLeafTesting | ( | int | b1, |
int | b2, | ||
const BVHModel< BV > * | model1, | ||
const BVHModel< BV > * | model2, | ||
Vec3f * | vertices1, | ||
Vec3f * | vertices2, | ||
Triangle * | tri_indices1, | ||
Triangle * | tri_indices2, | ||
const Matrix3f & | R, | ||
const Vec3f & | T, | ||
bool | enable_statistics, | ||
int & | num_leaf_tests, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) | [inline, static] |
Definition at line 137 of file traversal_node_bvhs.cpp.
static Vec3Data<T> fcl::details::min | ( | const Vec3Data< T > & | x, |
const Vec3Data< T > & | y | ||
) | [inline, static] |
Definition at line 142 of file math_details.h.
static sse_meta_f4 fcl::details::min | ( | const sse_meta_f4 & | x, |
const sse_meta_f4 & | y | ||
) | [inline, static] |
Definition at line 375 of file math_simd_details.h.
static sse_meta_d4 fcl::details::min | ( | const sse_meta_d4 & | x, |
const sse_meta_d4 & | y | ||
) | [inline, static] |
Definition at line 380 of file math_simd_details.h.
static __m128 fcl::details::newtonraphson_rsqrt4 | ( | const __m128 | v | ) | [inline, static] |
Definition at line 83 of file math_simd_details.h.
static sse_meta_f4 fcl::details::normalize3 | ( | const sse_meta_f4 & | x | ) | [inline, static] |
Definition at line 428 of file math_simd_details.h.
static sse_meta_f4 fcl::details::normalize3_approx | ( | const sse_meta_f4 & | x | ) | [inline, static] |
Definition at line 435 of file math_simd_details.h.
std::size_t fcl::details::orientedBVHShapeCollide | ( | const CollisionGeometry * | o1, |
const Transform3f & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3f & | tf2, | ||
const NarrowPhaseSolver * | nsolver, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) |
Definition at line 270 of file collision_func_matrix.cpp.
FCL_REAL fcl::details::orientedBVHShapeDistance | ( | const CollisionGeometry * | o1, |
const Transform3f & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3f & | tf2, | ||
const NarrowPhaseSolver * | nsolver, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) |
Definition at line 169 of file distance_func_matrix.cpp.
std::size_t fcl::details::orientedMeshCollide | ( | const CollisionGeometry * | o1, |
const Transform3f & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3f & | tf2, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) |
Definition at line 388 of file collision_func_matrix.cpp.
FCL_REAL fcl::details::orientedMeshDistance | ( | const CollisionGeometry * | o1, |
const Transform3f & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3f & | tf2, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) |
Definition at line 239 of file distance_func_matrix.cpp.
bool 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 | ||
) |
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 1594 of file narrowphase.cpp.
bool fcl::details::planeIntersect | ( | const Plane & | s1, |
const Transform3f & | tf1, | ||
const Plane & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 2274 of file narrowphase.cpp.
T fcl::details::planeIntersectTolerance | ( | ) |
Definition at line 1714 of file narrowphase.cpp.
double fcl::details::planeIntersectTolerance< double > | ( | ) |
Definition at line 1720 of file narrowphase.cpp.
float fcl::details::planeIntersectTolerance< float > | ( | ) |
Definition at line 1726 of file narrowphase.cpp.
bool fcl::details::planeTriangleIntersect | ( | const Plane & | s1, |
const Transform3f & | tf1, | ||
const Vec3f & | P1, | ||
const Vec3f & | P2, | ||
const Vec3f & | P3, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 2187 of file narrowphase.cpp.
bool fcl::details::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.
Definition at line 119 of file narrowphase.cpp.
FCL_REAL fcl::details::projectOrigin | ( | const Vec3f & | a, |
const Vec3f & | b, | ||
FCL_REAL * | w, | ||
size_t & | m | ||
) |
project origin on to a line (a, b). w[0:1] return the (0, 1) parameterization of the projected point. m is a encode about the result case: 0x10--> project is larger than b; 0x01--> project is smaller than a; 0x11-> within the line; return value is distance between the origin and its projection.
FCL_REAL fcl::details::projectOrigin | ( | const Vec3f & | a, |
const Vec3f & | b, | ||
const Vec3f & | c, | ||
FCL_REAL * | w, | ||
size_t & | m | ||
) |
FCL_REAL fcl::details::projectOrigin | ( | const Vec3f & | a, |
const Vec3f & | b, | ||
const Vec3f & | c, | ||
const Vec3f & | d, | ||
FCL_REAL * | w, | ||
size_t & | m | ||
) |
FCL_REAL fcl::details::segmentSqrDistance | ( | const Vec3f & | from, |
const Vec3f & | to, | ||
const Vec3f & | p, | ||
Vec3f & | nearest | ||
) |
the minimum distance from a point to a line
Definition at line 91 of file narrowphase.cpp.
static bool fcl::details::setupMeshCollisionOrientedNode | ( | OrientedNode & | node, |
const BVHModel< BV > & | model1, | ||
const Transform3f & | tf1, | ||
const BVHModel< BV > & | model2, | ||
const Transform3f & | tf2, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) | [inline, static] |
Definition at line 47 of file traversal_node_setup.cpp.
static bool fcl::details::setupMeshDistanceOrientedNode | ( | OrientedNode & | node, |
const BVHModel< BV > & | model1, | ||
const Transform3f & | tf1, | ||
const BVHModel< BV > & | model2, | ||
const Transform3f & | tf2, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) | [inline, static] |
Definition at line 122 of file traversal_node_setup.cpp.
static bool fcl::details::setupShapeMeshDistanceOrientedNode | ( | OrientedNode< S, NarrowPhaseSolver > & | node, |
const S & | model1, | ||
const Transform3f & | tf1, | ||
const BVHModel< BV > & | model2, | ||
const Transform3f & | tf2, | ||
const NarrowPhaseSolver * | nsolver, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) | [inline, static] |
Definition at line 950 of file traversal_node_setup.h.
static void fcl::details::shapeToGJK | ( | const ShapeBase & | s, |
const Transform3f & | tf, | ||
ccd_obj_t * | o | ||
) | [static] |
Basic shape to ccd shape
Definition at line 441 of file gjk_libccd.cpp.
bool fcl::details::sphereHalfspaceIntersect | ( | const Sphere & | s1, |
const Transform3f & | tf1, | ||
const Halfspace & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 1262 of file narrowphase.cpp.
bool fcl::details::spherePlaneIntersect | ( | const Sphere & | s1, |
const Transform3f & | tf1, | ||
const Plane & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 1731 of file narrowphase.cpp.
bool fcl::details::sphereSphereDistance | ( | const Sphere & | s1, |
const Transform3f & | tf1, | ||
const Sphere & | s2, | ||
const Transform3f & | tf2, | ||
FCL_REAL * | dist | ||
) |
Definition at line 74 of file narrowphase.cpp.
bool fcl::details::sphereSphereIntersect | ( | const Sphere & | s1, |
const Transform3f & | tf1, | ||
const Sphere & | s2, | ||
const Transform3f & | tf2, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal | ||
) |
Definition at line 48 of file narrowphase.cpp.
static void fcl::details::sphereToGJK | ( | const Sphere & | s, |
const Transform3f & | tf, | ||
ccd_sphere_t * | sph | ||
) | [static] |
Definition at line 479 of file gjk_libccd.cpp.
bool fcl::details::sphereTriangleDistance | ( | const Sphere & | sp, |
const Transform3f & | tf, | ||
const Vec3f & | P1, | ||
const Vec3f & | P2, | ||
const Vec3f & | P3, | ||
FCL_REAL * | dist | ||
) |
Definition at line 229 of file narrowphase.cpp.
bool fcl::details::sphereTriangleIntersect | ( | const Sphere & | s, |
const Transform3f & | tf, | ||
const Vec3f & | P1, | ||
const Vec3f & | P2, | ||
const Vec3f & | P3, | ||
Vec3f * | contact_points, | ||
FCL_REAL * | penetration_depth, | ||
Vec3f * | normal_ | ||
) |
Definition at line 144 of file narrowphase.cpp.
static void fcl::details::supportBox | ( | const void * | obj, |
const ccd_vec3_t * | dir_, | ||
ccd_vec3_t * | v | ||
) | [static] |
Support functions
Definition at line 492 of file gjk_libccd.cpp.
static void fcl::details::supportCap | ( | const void * | obj, |
const ccd_vec3_t * | dir_, | ||
ccd_vec3_t * | v | ||
) | [static] |
Definition at line 505 of file gjk_libccd.cpp.
static void fcl::details::supportCone | ( | const void * | obj, |
const ccd_vec3_t * | dir_, | ||
ccd_vec3_t * | v | ||
) | [static] |
Definition at line 558 of file gjk_libccd.cpp.
static void fcl::details::supportConvex | ( | const void * | obj, |
const ccd_vec3_t * | dir_, | ||
ccd_vec3_t * | v | ||
) | [static] |
Definition at line 606 of file gjk_libccd.cpp.
static void fcl::details::supportCyl | ( | const void * | obj, |
const ccd_vec3_t * | dir_, | ||
ccd_vec3_t * | v | ||
) | [static] |
Definition at line 531 of file gjk_libccd.cpp.
static void fcl::details::supportSphere | ( | const void * | obj, |
const ccd_vec3_t * | dir_, | ||
ccd_vec3_t * | v | ||
) | [static] |
Definition at line 589 of file gjk_libccd.cpp.
static void fcl::details::supportTriangle | ( | const void * | obj, |
const ccd_vec3_t * | dir_, | ||
ccd_vec3_t * | v | ||
) | [static] |
Definition at line 637 of file gjk_libccd.cpp.
static void fcl::details::transpose | ( | __m128 | c0, |
__m128 | c1, | ||
__m128 | c2, | ||
__m128 * | r0, | ||
__m128 * | r1, | ||
__m128 * | r2 | ||
) | [inline, static] |
Definition at line 443 of file math_simd_details.h.
Matrix3Data<T> fcl::details::transpose | ( | const Matrix3Data< T > & | m | ) |
Definition at line 473 of file math_details.h.
static sse_meta_f12 fcl::details::transpose | ( | const sse_meta_f12 & | mat | ) | [inline, static] |
Definition at line 716 of file math_simd_details.h.
static void fcl::details::transpose | ( | __m128 | c0, |
__m128 | c1, | ||
__m128 | c2, | ||
__m128 | c3, | ||
__m128 * | r0, | ||
__m128 * | r1, | ||
__m128 * | r2, | ||
__m128 * | r3 | ||
) | [inline, static] |
Definition at line 732 of file math_simd_details.h.
static sse_meta_f16 fcl::details::transpose | ( | const sse_meta_f16 & | mat | ) | [inline, static] |
Definition at line 1127 of file math_simd_details.h.
void * fcl::details::triCreateGJKObject | ( | const Vec3f & | P1, |
const Vec3f & | P2, | ||
const Vec3f & | P3 | ||
) |
Definition at line 946 of file gjk_libccd.cpp.
void * fcl::details::triCreateGJKObject | ( | const Vec3f & | P1, |
const Vec3f & | P2, | ||
const Vec3f & | P3, | ||
const Transform3f & | tf | ||
) |
Definition at line 962 of file gjk_libccd.cpp.
void fcl::details::triDeleteGJKObject | ( | void * | o | ) |
Definition at line 980 of file gjk_libccd.cpp.
Definition at line 940 of file gjk_libccd.cpp.
Definition at line 934 of file gjk_libccd.cpp.
static void fcl::details::tripleCross | ( | const ccd_vec3_t * | a, |
const ccd_vec3_t * | b, | ||
const ccd_vec3_t * | c, | ||
ccd_vec3_t * | d | ||
) | [static] |
Definition at line 90 of file gjk_libccd.cpp.
static __m128 fcl::details::vec_sel | ( | __m128 | a, |
__m128 | b, | ||
__m128 | mask | ||
) | [inline, static] |
Definition at line 62 of file math_simd_details.h.
static __m128 fcl::details::vec_sel | ( | __m128 | a, |
__m128 | b, | ||
const unsigned int * | mask | ||
) | [inline, static] |
Definition at line 66 of file math_simd_details.h.
static __m128 fcl::details::vec_sel | ( | __m128 | a, |
__m128 | b, | ||
unsigned int | mask | ||
) | [inline, static] |
Definition at line 71 of file math_simd_details.h.
const FCL_REAL fcl::details::EPA_EPS = 0.000001 [static] |
const size_t fcl::details::EPA_MAX_FACES = 128 [static] |
const size_t fcl::details::EPA_MAX_ITERATIONS = 255 [static] |
const size_t fcl::details::EPA_MAX_VERTICES = 64 [static] |
const __m128d fcl::details::xmmd_0 = {0, 0} |
Definition at line 60 of file math_simd_details.h.
const __m128 fcl::details::xmms_0 = {0.f, 0.f, 0.f, 0.f} |
Definition at line 59 of file math_simd_details.h.