|
bool | are_coincident (const Vector3d &p, const Vector3d &q) |
|
::testing::AssertionResult | are_same (const Vector3d &expected, const ccd_vec3_t &tested, double tolerance) |
|
template int | boxBox2 (const Vector3< double > &side1, const Transform3< double > &tf1, const Vector3< double > &side2, const Transform3< double > &tf2, Vector3< double > &normal, double *depth, int *return_code, int maxc, std::vector< ContactPoint< double >> &contacts) |
|
template<typename S , typename DerivedA , typename DerivedB > |
FCL_EXPORT int | boxBox2 (const Vector3< S > &side1, const Eigen::MatrixBase< DerivedA > &R1, const Eigen::MatrixBase< DerivedB > &T1, const Vector3< S > &side2, const Eigen::MatrixBase< DerivedA > &R2, const Eigen::MatrixBase< DerivedB > &T2, Vector3< S > &normal, S *depth, int *return_code, int maxc, std::vector< ContactPoint< S >> &contacts) |
|
template<typename S , typename DerivedA , typename DerivedB > |
int | boxBox2 (const Vector3< S > &side1, const Eigen::MatrixBase< DerivedA > &R1, const Eigen::MatrixBase< DerivedB > &T1, const Vector3< S > &side2, const Eigen::MatrixBase< DerivedA > &R2, const Eigen::MatrixBase< DerivedB > &T2, Vector3< S > &normal, S *depth, int *return_code, int maxc, std::vector< ContactPoint< S >> &contacts) |
|
template<typename S > |
FCL_EXPORT int | boxBox2 (const Vector3< S > &side1, const Transform3< S > &tf1, const Vector3< S > &side2, const Transform3< S > &tf2, Vector3< S > &normal, S *depth, int *return_code, int maxc, std::vector< ContactPoint< S >> &contacts) |
|
template<typename S > |
int | boxBox2 (const Vector3< S > &side1, const Transform3< S > &tf1, const Vector3< S > &side2, const Transform3< S > &tf2, Vector3< S > &normal, S *depth, int *return_code, int maxc, std::vector< ContactPoint< S >> &contacts) |
|
template bool | boxBoxIntersect (const Box< double > &s1, const Transform3< double > &tf1, const Box< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts_) |
|
template<typename S > |
FCL_EXPORT bool | boxBoxIntersect (const Box< S > &s1, const Transform3< S > &tf1, const Box< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts_) |
|
template<typename S > |
bool | boxBoxIntersect (const Box< S > &s1, const Transform3< S > &tf1, const Box< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts_) |
|
template bool | boxHalfspaceIntersect (const Box< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2) |
|
template bool | boxHalfspaceIntersect (const Box< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | boxHalfspaceIntersect (const Box< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &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...
|
|
template<typename S > |
bool | boxHalfspaceIntersect (const Box< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &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...
|
|
template<typename S > |
FCL_EXPORT bool | boxHalfspaceIntersect (const Box< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | boxHalfspaceIntersect (const Box< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template bool | boxPlaneIntersect (const Box< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | boxPlaneIntersect (const Box< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
| 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...
|
|
template<typename S > |
bool | boxPlaneIntersect (const Box< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
| 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...
|
|
template<typename S > |
static void | boxToGJK (const Box< S > &s, const Transform3< S > &tf, ccd_box_t *box) |
|
template<typename BV > |
std::size_t | BVHCollide (const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV , typename NarrowPhaseSolver > |
std::size_t | BVHCollide (const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV , typename NarrowPhaseSolver > |
BV::S | BVHConservativeAdvancement (const CollisionGeometry< typename BV::S > *o1, const MotionBase< typename BV::S > *motion1, const CollisionGeometry< typename BV::S > *o2, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, const ContinuousCollisionRequest< typename BV::S > &request, ContinuousCollisionResult< typename BV::S > &result) |
|
template<typename BV > |
BV::S | BVHDistance (const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV , typename NarrowPhaseSolver > |
BV::S | BVHDistance (const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
BV::S | BVHShapeConservativeAdvancement (const CollisionGeometry< typename BV::S > *o1, const MotionBase< typename BV::S > *motion1, const CollisionGeometry< typename BV::S > *o2, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, const ContinuousCollisionRequest< typename BV::S > &request, ContinuousCollisionResult< typename BV::S > &result) |
|
template bool | capsuleCapsuleDistance (const Capsule< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, double *dist, Vector3d *p1_res, Vector3d *p2_res) |
|
template<typename S > |
FCL_EXPORT bool | capsuleCapsuleDistance (const Capsule< S > &s1, const Transform3< S > &X_FC1, const Capsule< S > &s2, const Transform3< S > &X_FC2, S *dist, Vector3< S > *p_FW1, Vector3< S > *p_FW2) |
|
template<typename S > |
bool | capsuleCapsuleDistance (const Capsule< S > &s1, const Transform3< S > &X_FC1, const Capsule< S > &s2, const Transform3< S > &X_FC2, S *dist, Vector3< S > *p_FW1, Vector3< S > *p_FW2) |
|
template bool | capsuleHalfspaceIntersect (const Capsule< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | capsuleHalfspaceIntersect (const Capsule< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | capsuleHalfspaceIntersect (const Capsule< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template bool | capsulePlaneIntersect (const Capsule< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2) |
|
template bool | capsulePlaneIntersect (const Capsule< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | capsulePlaneIntersect (const Capsule< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2) |
|
template<typename S > |
bool | capsulePlaneIntersect (const Capsule< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2) |
|
template<typename S > |
FCL_EXPORT bool | capsulePlaneIntersect (const Capsule< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | capsulePlaneIntersect (const Capsule< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
static void | capToGJK (const Capsule< S > &s, const Transform3< S > &tf, ccd_cap_t *cap) |
|
Vector3d | ccd_to_eigen (const ccd_vec3_t &vector) |
|
template<typename S > |
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) |
|
void | CheckComputeVisiblePatch (const Polytope &polytope, ccd_pt_face_t &face, const ccd_vec3_t &new_vertex, const std::unordered_set< int > &border_edge_indices_expected, const std::unordered_set< int > &visible_face_indices_expected, const std::unordered_set< int > &internal_edges_indices_expected) |
|
void | CheckComputeVisiblePatchColinearNewVertex (EquilateralTetrahedron &tet, double rho) |
|
void | CheckComputeVisiblePatchCommon (const Polytope &polytope, const std::unordered_set< ccd_pt_edge_t * > &border_edges, const std::unordered_set< ccd_pt_face_t * > &visible_faces, const std::unordered_set< ccd_pt_edge_t * > &internal_edges, const std::unordered_set< int > &border_edge_indices_expected, const std::unordered_set< int > &visible_face_indices_expected, const std::unordered_set< int > internal_edges_indices_expected) |
|
void | CheckComputeVisiblePatchRecursive (const Polytope &polytope, ccd_pt_face_t &face, const std::vector< int > &edge_indices, const ccd_vec3_t &new_vertex, const std::unordered_set< int > &border_edge_indices_expected, const std::unordered_set< int > &visible_face_indices_expected, const std::unordered_set< int > &internal_edges_indices_expected) |
|
void | CheckTetrahedronFaceNormal (const Tetrahedron &p) |
|
template double | clamp (double n, double min, double max) |
|
template<typename S > |
FCL_EXPORT S | clamp (S n, S min, S max) |
|
template<typename S > |
S | clamp (S n, S min, S max) |
|
template<typename S > |
FCL_EXPORT S | closestPtSegmentSegment (const Vector3< S > &p_FP1, const Vector3< S > &p_FQ1, const Vector3< S > &p_FP2, const Vector3< S > &p_FQ2, S *s, S *t, Vector3< S > *p_FC1, Vector3< S > *p_FC2) |
|
template<typename S > |
S | closestPtSegmentSegment (const Vector3< S > &p_FP1, const Vector3< S > &p_FQ1, const Vector3< S > &p_FP2, const Vector3< S > &p_FQ2, S *s, S *t, Vector3< S > *p_FC1, Vector3< S > *p_FC2) |
|
template double | closestPtSegmentSegment (const Vector3d &p_FP1, const Vector3d &p_FQ1, const Vector3d &p_FP2, const Vector3d &p_FQ2, double *s, double *t, Vector3d *p_FC1, Vector3d *p_FC2) |
|
template void | collide (CollisionTraversalNodeBase< double > *node, BVHFrontList *front_list) |
|
template<typename S > |
void | collide (CollisionTraversalNodeBase< S > *node, BVHFrontList *front_list) |
| collision on collision traversal node; can use front list to accelerate More...
|
|
template<typename S > |
FCL_EXPORT void | collide (CollisionTraversalNodeBase< S > *node, BVHFrontList *front_list=nullptr) |
| collision on collision traversal node; can use front list to accelerate More...
|
|
template void | collide2 (MeshCollisionTraversalNodeOBB< double > *node, BVHFrontList *front_list) |
|
template<typename S > |
void | collide2 (MeshCollisionTraversalNodeOBB< S > *node, BVHFrontList *front_list) |
| special collision on OBB traversal node More...
|
|
template<typename S > |
FCL_EXPORT void | collide2 (MeshCollisionTraversalNodeOBB< S > *node, BVHFrontList *front_list=nullptr) |
| special collision on OBB traversal node More...
|
|
template void | collide2 (MeshCollisionTraversalNodeRSS< double > *node, BVHFrontList *front_list) |
|
template<typename S > |
void | collide2 (MeshCollisionTraversalNodeRSS< S > *node, BVHFrontList *front_list) |
| special collision on RSS traversal node More...
|
|
template<typename S > |
FCL_EXPORT void | collide2 (MeshCollisionTraversalNodeRSS< S > *node, BVHFrontList *front_list=nullptr) |
| special collision on RSS traversal node More...
|
|
template void | collisionRecurse (CollisionTraversalNodeBase< double > *node, int b1, int b2, BVHFrontList *front_list) |
|
template<typename S > |
FCL_EXPORT void | collisionRecurse (CollisionTraversalNodeBase< S > *node, int b1, int b2, BVHFrontList *front_list) |
| Recurse function for collision. More...
|
|
template void | collisionRecurse (MeshCollisionTraversalNodeOBB< double > *node, int b1, int b2, const Matrix3< double > &R, const Vector3< double > &T, BVHFrontList *front_list) |
|
template<typename S > |
FCL_EXPORT void | collisionRecurse (MeshCollisionTraversalNodeOBB< S > *node, int b1, int b2, const Matrix3< S > &R, const Vector3< S > &T, BVHFrontList *front_list) |
| Recurse function for collision, specialized for OBB type. More...
|
|
template void | collisionRecurse (MeshCollisionTraversalNodeRSS< double > *node, int b1, int b2, const Matrix3< double > &R, const Vector3< double > &T, BVHFrontList *front_list) |
|
template<typename S > |
FCL_EXPORT void | collisionRecurse (MeshCollisionTraversalNodeRSS< S > *node, int b1, int b2, const Matrix3< S > &R, const Vector3< S > &T, BVHFrontList *front_list) |
| Recurse function for collision, specialized for RSS type. More...
|
|
void | CompareCcdVec3 (const ccd_vec3_t &v, const ccd_vec3_t &v_expected, ccd_real_t tol) |
|
void | ComparePolytope (const ccd_pt_t *polytope1, const ccd_pt_t *polytope2, ccd_real_t tol) |
|
template<typename S > |
S | ComputeSphereSphereDistance (S radius1, S radius2, const Vector3< S > &p_F1, const Vector3< S > &p_F2) |
|
template<typename S , typename BV > |
void | computeSplitValue_bvcenter (const BV &bv, S &split_value) |
|
template<typename S , typename BV > |
void | computeSplitValue_mean (const BV &bv, Vector3< S > *vertices, Triangle *triangles, unsigned int *primitive_indices, int num_primitives, BVHModelType type, const Vector3< S > &split_vector, S &split_value) |
|
template<typename S , typename BV > |
void | computeSplitValue_median (const BV &bv, Vector3< S > *vertices, Triangle *triangles, unsigned int *primitive_indices, int num_primitives, BVHModelType type, const Vector3< S > &split_vector, S &split_value) |
|
template<typename S , typename BV > |
void | computeSplitVector (const BV &bv, Vector3< S > &split_vector) |
|
template bool | coneHalfspaceIntersect (const Cone< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | coneHalfspaceIntersect (const Cone< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | coneHalfspaceIntersect (const Cone< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template bool | conePlaneIntersect (const Cone< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | conePlaneIntersect (const Cone< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | conePlaneIntersect (const Cone< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
static void | coneToGJK (const Cone< S > &s, const Transform3< S > &tf, ccd_cone_t *cone) |
|
template<typename BV > |
bool | conservativeAdvancement (const BVHModel< BV > &o1, const MotionBase< typename BV::S > *motion1, const BVHModel< BV > &o2, const MotionBase< typename BV::S > *motion2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, typename BV::S &toc) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
bool | conservativeAdvancement (const BVHModel< BV > &o1, const MotionBase< typename BV::S > *motion1, const Shape &o2, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, typename BV::S &toc) |
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | conservativeAdvancement (const BVHModel< OBBRSS< typename Shape::S >> &o1, const MotionBase< typename Shape::S > *motion1, const Shape &o2, const MotionBase< typename Shape::S > *motion2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result, typename Shape::S &toc) |
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | conservativeAdvancement (const BVHModel< RSS< typename Shape::S >> &o1, const MotionBase< typename Shape::S > *motion1, const Shape &o2, const MotionBase< typename Shape::S > *motion2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result, typename Shape::S &toc) |
|
template<typename Shape , typename BV , typename NarrowPhaseSolver > |
bool | conservativeAdvancement (const Shape &o1, const MotionBase< typename BV::S > *motion1, const BVHModel< BV > &o2, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, typename BV::S &toc) |
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | conservativeAdvancement (const Shape &o1, const MotionBase< typename Shape::S > *motion1, const BVHModel< OBBRSS< typename Shape::S >> &o2, const MotionBase< typename Shape::S > *motion2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result, typename Shape::S &toc) |
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | conservativeAdvancement (const Shape &o1, const MotionBase< typename Shape::S > *motion1, const BVHModel< RSS< typename Shape::S >> &o2, const MotionBase< typename Shape::S > *motion2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result, typename Shape::S &toc) |
|
template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver > |
bool | conservativeAdvancement (const Shape1 &o1, const MotionBase< typename Shape1::S > *motion1, const Shape2 &o2, const MotionBase< typename Shape1::S > *motion2, const NarrowPhaseSolver *solver, const CollisionRequest< typename Shape1::S > &request, CollisionResult< typename Shape1::S > &result, typename Shape1::S &toc) |
|
template<typename BV , typename ConservativeAdvancementOrientedNode > |
bool | conservativeAdvancementMeshOriented (const BVHModel< BV > &o1, const MotionBase< typename BV::S > *motion1, const BVHModel< BV > &o2, const MotionBase< typename BV::S > *motion2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, typename BV::S &toc) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver , typename ConservativeAdvancementOrientedNode > |
bool | conservativeAdvancementMeshShapeOriented (const BVHModel< BV > &o1, const MotionBase< typename BV::S > *motion1, const Shape &o2, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, typename BV::S &toc) |
|
template<typename Shape , typename BV , typename NarrowPhaseSolver , typename ConservativeAdvancementOrientedNode > |
bool | conservativeAdvancementShapeMeshOriented (const Shape &o1, const MotionBase< typename BV::S > *motion1, const BVHModel< BV > &o2, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, typename BV::S &toc) |
|
template<typename BV > |
FCL_EXPORT BV::S | continuousCollideBVHPolynomial (const CollisionGeometry< typename BV::S > *o1_, const TranslationMotion< typename BV::S > *motion1, const CollisionGeometry< typename BV::S > *o2_, const TranslationMotion< typename BV::S > *motion2, const ContinuousCollisionRequest< typename BV::S > &request, ContinuousCollisionResult< typename BV::S > &result) |
|
template<typename NarrowPhaseSolver > |
FCL_EXPORT NarrowPhaseSolver::S | continuousCollideConservativeAdvancement (const CollisionGeometry< typename NarrowPhaseSolver::S > *o1, const MotionBase< typename NarrowPhaseSolver::S > *motion1, const CollisionGeometry< typename NarrowPhaseSolver::S > *o2, const MotionBase< typename NarrowPhaseSolver::S > *motion2, const NarrowPhaseSolver *nsolver_, const ContinuousCollisionRequest< typename NarrowPhaseSolver::S > &request, ContinuousCollisionResult< typename NarrowPhaseSolver::S > &result) |
|
template bool | convexHalfspaceIntersect (const Convex< double > &convex_C, const Transform3< double > &X_FC, const Halfspace< double > &half_space_H, const Transform3< double > &X_FH, std::vector< ContactPoint< double >> *contacts) |
|
template bool | convexHalfspaceIntersect (const Convex< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal) |
|
template<typename S > |
FCL_EXPORT bool | convexHalfspaceIntersect (const Convex< S > &convex_C, const Transform3< S > &X_FC, const Halfspace< S > &half_space_H, const Transform3< S > &X_FH, std::vector< ContactPoint< S >> *contacts) |
| Reports whether a convex mesh and half space are intersecting. If contacts is not nullptr and the two geometries are intersecting, a new ContactPoint will be added to the data. More...
|
|
template<typename S > |
bool | convexHalfspaceIntersect (const Convex< S > &convex_C, const Transform3< S > &X_FC, const Halfspace< S > &half_space_H, const Transform3< S > &X_FH, std::vector< ContactPoint< S >> *contacts) |
| Reports whether a convex mesh and half space are intersecting. If contacts is not nullptr and the two geometries are intersecting, a new ContactPoint will be added to the data. More...
|
|
template<typename S > |
FCL_EXPORT bool | convexHalfspaceIntersect (const Convex< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
|
template<typename S > |
bool | convexHalfspaceIntersect (const Convex< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
|
template bool | convexPlaneIntersect (const Convex< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal) |
|
template<typename S > |
FCL_EXPORT bool | convexPlaneIntersect (const Convex< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
|
template<typename S > |
bool | convexPlaneIntersect (const Convex< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
|
template<typename S > |
static void | convexToGJK (const Convex< S > &s, const Transform3< S > &tf, ccd_convex_t< S > *conv) |
|
template void | cullPoints2 (int n, double p[], int m, int i0, int iret[]) |
|
template<typename S > |
FCL_EXPORT void | cullPoints2 (int n, S p[], int m, int i0, int iret[]) |
|
template<typename S > |
void | cullPoints2 (int n, S p[], int m, int i0, int iret[]) |
|
template bool | cylinderHalfspaceIntersect (const Cylinder< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | cylinderHalfspaceIntersect (const Cylinder< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | cylinderHalfspaceIntersect (const Cylinder< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template bool | cylinderPlaneIntersect (const Cylinder< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2) |
|
template bool | cylinderPlaneIntersect (const Cylinder< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | cylinderPlaneIntersect (const Cylinder< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &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 More...
|
|
template<typename S > |
bool | cylinderPlaneIntersect (const Cylinder< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &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 More...
|
|
template<typename S > |
FCL_EXPORT bool | cylinderPlaneIntersect (const Cylinder< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | cylinderPlaneIntersect (const Cylinder< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
static void | cylToGJK (const Cylinder< S > &s, const Transform3< S > &tf, ccd_cyl_t *cyl) |
|
template void | distance (DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize) |
|
template<typename S > |
void | distance (DistanceTraversalNodeBase< S > *node, BVHFrontList *front_list, int qsize) |
| distance computation on distance traversal node; can use front list to accelerate More...
|
|
template<typename S > |
FCL_EXPORT void | distance (DistanceTraversalNodeBase< S > *node, BVHFrontList *front_list=nullptr, int qsize=2) |
| distance computation on distance traversal node; can use front list to accelerate More...
|
|
template<typename BV > |
FCL_EXPORT void | distancePostprocessOrientedNode (const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Transform3< typename BV::S > &tf1, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV > |
void | distancePostprocessOrientedNode (const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Transform3< typename BV::S > &tf1, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV > |
FCL_EXPORT void | distancePreprocessOrientedNode (const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, int init_tri_id1, int init_tri_id2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV > |
void | distancePreprocessOrientedNode (const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, int init_tri_id1, int init_tri_id2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV > |
FCL_EXPORT void | distancePreprocessOrientedNode (const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, int init_tri_id1, int init_tri_id2, const Transform3< typename BV::S > &tf, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV > |
void | distancePreprocessOrientedNode (const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, int init_tri_id1, int init_tri_id2, const Transform3< typename BV::S > &tf, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
void | distancePreprocessOrientedNode (const BVHModel< BV > *model1, Vector3< typename BV::S > *vertices, Triangle *tri_indices, int init_tri_id, const Shape &model2, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &, DistanceResult< typename BV::S > &result) |
|
template void | distanceQueueRecurse (DistanceTraversalNodeBase< double > *node, int b1, int b2, BVHFrontList *front_list, int qsize) |
|
template<typename S > |
FCL_EXPORT void | distanceQueueRecurse (DistanceTraversalNodeBase< S > *node, int b1, int b2, BVHFrontList *front_list, int qsize) |
| Recurse function for distance, using queue acceleration. More...
|
|
template void | distanceRecurse (DistanceTraversalNodeBase< double > *node, int b1, int b2, BVHFrontList *front_list) |
|
template<typename S > |
FCL_EXPORT void | distanceRecurse (DistanceTraversalNodeBase< S > *node, int b1, int b2, BVHFrontList *front_list) |
| Recurse function for distance. More...
|
|
bool | EdgeMatch (const ccd_pt_edge_t *e1, const ccd_pt_edge_t *e2, const std::unordered_map< ccd_pt_vertex_t *, ccd_pt_vertex_t * > &map_v1_to_v2) |
|
ccd_vec3_t | eigen_to_ccd (const Vector3d &vector) |
|
template bool | ellipsoidHalfspaceIntersect (const Ellipsoid< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | ellipsoidHalfspaceIntersect (const Ellipsoid< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | ellipsoidHalfspaceIntersect (const Ellipsoid< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template bool | ellipsoidPlaneIntersect (const Ellipsoid< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | ellipsoidPlaneIntersect (const Ellipsoid< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | ellipsoidPlaneIntersect (const Ellipsoid< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
static void | ellipsoidToGJK (const Ellipsoid< S > &s, const Transform3< S > &tf, ccd_ellipsoid_t *ellipsoid) |
|
std::array< fcl::Vector3< ccd_real_t >, 4 > | EquilateralTetrahedronVertices (ccd_real_t bottom_center_x, ccd_real_t bottom_center_y, ccd_real_t bottom_center_z, ccd_real_t edge_length) |
|
template<typename S , typename BV > |
const FCL_EXPORT Vector3< S > | getBVAxis (const BV &bv, int i) |
|
template<typename BV > |
const Vector3< typename BV::S > | getBVAxis (const BV &bv, int i) |
|
template<typename S > |
FCL_EXPORT void | getExtentAndCenter_mesh (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3< S > &axis, Vector3< S > ¢er, Vector3< S > &extent) |
| Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known. More...
|
|
template void | getExtentAndCenter_mesh (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3d &axis, Vector3d ¢er, Vector3d &extent) |
|
template<typename S > |
FCL_EXPORT void | getExtentAndCenter_pointcloud (const Vector3< S > *const ps, const Vector3< S > *const ps2, unsigned int *indices, int n, const Matrix3< S > &axis, Vector3< S > ¢er, Vector3< S > &extent) |
| Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known. More...
|
|
template void | getExtentAndCenter_pointcloud (const Vector3d *const ps, const Vector3d *const ps2, unsigned int *indices, int n, const Matrix3d &axis, Vector3d ¢er, Vector3d &extent) |
|
template<typename S , typename Derived > |
Vector3< S > | getSupport (const ShapeBase< S > *shape, const Eigen::MatrixBase< Derived > &dir) |
| the support function for shape More...
|
|
template<typename S , typename Derived > |
FCL_EXPORT Vector3< S > | getSupport (const ShapeBase< S > *shape, const Eigen::MatrixBase< Derived > &dir) |
| the support function for shape More...
|
|
template 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, double tolerance, Vector3d *contact_points, double *penetration_depth, Vector3d *normal) |
|
template<typename S > |
FCL_EXPORT 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, S tolerance, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
| GJK collision algorithm. More...
|
|
template<typename S > |
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, S tolerance, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
| GJK collision algorithm. More...
|
|
template bool | GJKDistance (void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, double tolerance, double *dist, Vector3d *p1, Vector3d *p2) |
|
template<typename S > |
FCL_EXPORT bool | GJKDistance (void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, S tolerance, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template<typename S > |
bool | GJKDistance (void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, S tolerance, S *res, Vector3< S > *p1, Vector3< S > *p2) |
|
template<typename S > |
bool | GJKDistanceImpl (void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, S tolerance, detail::DistanceFn distance_func, S *res, Vector3< S > *p1, Vector3< S > *p2) |
|
template bool | GJKSignedDistance (void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, double tolerance, double *dist, Vector3d *p1, Vector3d *p2) |
|
template<typename S > |
FCL_EXPORT bool | GJKSignedDistance (void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, S tolerance, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template<typename S > |
bool | GJKSignedDistance (void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, S tolerance, S *res, Vector3< S > *p1, Vector3< S > *p2) |
|
| GTEST_TEST (DegenerateGeometry, CoincidentPoints) |
|
| GTEST_TEST (DegenerateGeometry, ZeroAreaTriangle) |
|
| GTEST_TEST (FCL_GJK_EPA, ComputeVisiblePatch_2FacesVisible) |
|
| GTEST_TEST (FCL_GJK_EPA, ComputeVisiblePatch_4FacesVisible) |
|
| GTEST_TEST (FCL_GJK_EPA, ComputeVisiblePatch_TopAndSideFacesVisible) |
|
| GTEST_TEST (FCL_GJK_EPA, ComputeVisiblePatch_TopFaceVisible) |
|
| GTEST_TEST (FCL_GJK_EPA, ComputeVisiblePatchColinearNewVertex) |
|
| GTEST_TEST (FCL_GJK_EPA, ComputeVisiblePatchSanityCheck) |
|
| GTEST_TEST (FCL_GJK_EPA, convert2SimplexToTetrahedron) |
|
| GTEST_TEST (FCL_GJK_EPA, expandPolytope_error) |
|
| GTEST_TEST (FCL_GJK_EPA, expandPolytope_hexagram_1visible_face) |
|
| GTEST_TEST (FCL_GJK_EPA, expandPolytope_hexagram_4_visible_faces) |
|
| GTEST_TEST (FCL_GJK_EPA, expandPolytope_tetrahedron1) |
|
| GTEST_TEST (FCL_GJK_EPA, expandPolytope_tetrahedron_2visible_faces) |
|
| GTEST_TEST (FCL_GJK_EPA, faceNormalPointingOutward) |
|
| GTEST_TEST (FCL_GJK_EPA, faceNormalPointingOutwardError) |
|
| GTEST_TEST (FCL_GJK_EPA, faceNormalPointingOutwardOriginNearFace1) |
|
| GTEST_TEST (FCL_GJK_EPA, faceNormalPointingOutwardOriginNearFace2) |
|
| GTEST_TEST (FCL_GJK_EPA, isOutsidePolytopeFace) |
|
| GTEST_TEST (FCL_GJK_EPA, isOutsidePolytopeFaceError) |
|
| GTEST_TEST (FCL_GJK_EPA, penEPAPosClosest_edge) |
|
| GTEST_TEST (FCL_GJK_EPA, penEPAPosClosest_face) |
|
| GTEST_TEST (FCL_GJK_EPA, penEPAPosClosest_vertex) |
|
| GTEST_TEST (FCL_GJK_EPA, supportEPADirection) |
|
| GTEST_TEST (FCL_GJK_EPA, supportEPADirectionError) |
|
| GTEST_TEST (FCL_GJKSignedDistance, box_box) |
|
| GTEST_TEST (FCL_GJKSignedDistance, sphere_sphere) |
|
template bool | halfspaceIntersect (const Halfspace< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Vector3< double > &p, Vector3< double > &d, Halfspace< double > &s, double &penetration_depth, int &ret) |
|
template<typename S > |
FCL_EXPORT bool | halfspaceIntersect (const Halfspace< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, Vector3< S > &p, Vector3< S > &d, Halfspace< S > &s, S &penetration_depth, int &ret) |
| 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 More...
|
|
template<typename S > |
bool | halfspaceIntersect (const Halfspace< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, Vector3< S > &p, Vector3< S > &d, Halfspace< S > &s, S &penetration_depth, int &ret) |
| 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 More...
|
|
template<> |
FCL_EXPORT float | halfspaceIntersectTolerance () |
|
template<typename S > |
FCL_EXPORT S | halfspaceIntersectTolerance () |
|
template<typename S > |
S | halfspaceIntersectTolerance () |
|
template bool | halfspacePlaneIntersect (const Halfspace< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, Plane< double > &pl, Vector3< double > &p, Vector3< double > &d, double &penetration_depth, int &ret) |
|
template<typename S > |
FCL_EXPORT bool | halfspacePlaneIntersect (const Halfspace< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, Plane< S > &pl, Vector3< S > &p, Vector3< S > &d, S &penetration_depth, int &ret) |
|
template<typename S > |
bool | halfspacePlaneIntersect (const Halfspace< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, Plane< S > &pl, Vector3< S > &p, Vector3< S > &d, S &penetration_depth, int &ret) |
|
template bool | halfspaceTriangleIntersect (const Halfspace< double > &s1, const Transform3< double > &tf1, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal) |
|
template<typename S > |
FCL_EXPORT bool | halfspaceTriangleIntersect (const Halfspace< S > &s1, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
|
template<typename S > |
bool | halfspaceTriangleIntersect (const Halfspace< S > &s1, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
|
template<typename BV > |
bool | initialize (MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit, bool refit_bottomup) |
| Initialize traversal node for collision between two meshes, given the current transforms. More...
|
|
template<typename BV > |
FCL_EXPORT bool | initialize (MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit=false, bool refit_bottomup=false) |
| Initialize traversal node for collision between two meshes, given the current transforms. More...
|
|
template bool | initialize (MeshCollisionTraversalNodekIOS< double > &node, const BVHModel< kIOS< double >> &model1, const Transform3< double > &tf1, const BVHModel< kIOS< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result) |
|
template<typename S > |
FCL_EXPORT bool | initialize (MeshCollisionTraversalNodekIOS< S > &node, const BVHModel< kIOS< S >> &model1, const Transform3< S > &tf1, const BVHModel< kIOS< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
| Initialize traversal node for collision between two meshes, specialized for kIOS type. More...
|
|
template<typename S > |
bool | initialize (MeshCollisionTraversalNodekIOS< S > &node, const BVHModel< kIOS< S >> &model1, const Transform3< S > &tf1, const BVHModel< kIOS< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
| Initialize traversal node for collision between two meshes, specialized for kIOS type. More...
|
|
template bool | initialize (MeshCollisionTraversalNodeOBB< double > &node, const BVHModel< OBB< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBB< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result) |
|
template<typename S > |
FCL_EXPORT bool | initialize (MeshCollisionTraversalNodeOBB< S > &node, const BVHModel< OBB< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBB< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
| Initialize traversal node for collision between two meshes, specialized for OBB type. More...
|
|
template<typename S > |
bool | initialize (MeshCollisionTraversalNodeOBB< S > &node, const BVHModel< OBB< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBB< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
| Initialize traversal node for collision between two meshes, specialized for OBB type. More...
|
|
template bool | initialize (MeshCollisionTraversalNodeOBBRSS< double > &node, const BVHModel< OBBRSS< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBBRSS< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result) |
|
template<typename S > |
FCL_EXPORT bool | initialize (MeshCollisionTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
| Initialize traversal node for collision between two meshes, specialized for OBBRSS type. More...
|
|
template<typename S > |
bool | initialize (MeshCollisionTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
| Initialize traversal node for collision between two meshes, specialized for OBBRSS type. More...
|
|
template bool | initialize (MeshCollisionTraversalNodeRSS< double > &node, const BVHModel< RSS< double >> &model1, const Transform3< double > &tf1, const BVHModel< RSS< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result) |
|
template<typename S > |
FCL_EXPORT bool | initialize (MeshCollisionTraversalNodeRSS< S > &node, const BVHModel< RSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< RSS< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
| Initialize traversal node for collision between two meshes, specialized for RSS type. More...
|
|
template<typename S > |
bool | initialize (MeshCollisionTraversalNodeRSS< S > &node, const BVHModel< RSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< RSS< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
| Initialize traversal node for collision between two meshes, specialized for RSS type. More...
|
|
template<typename BV > |
bool | initialize (MeshConservativeAdvancementTraversalNode< BV > &node, BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, typename BV::S w, bool use_refit, bool refit_bottomup) |
| Initialize traversal node for conservative advancement computation between two meshes, given the current transforms. More...
|
|
template<typename BV > |
FCL_EXPORT bool | initialize (MeshConservativeAdvancementTraversalNode< BV > &node, BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, typename BV::S w=1, bool use_refit=false, bool refit_bottomup=false) |
| Initialize traversal node for conservative advancement computation between two meshes, given the current transforms. More...
|
|
template bool | initialize (MeshConservativeAdvancementTraversalNodeOBBRSS< double > &node, const BVHModel< OBBRSS< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBBRSS< double >> &model2, const Transform3< double > &tf2, double w) |
|
template<typename S > |
bool | initialize (MeshConservativeAdvancementTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, S w) |
|
template<typename S > |
FCL_EXPORT bool | initialize (MeshConservativeAdvancementTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, S w=1) |
|
template bool | initialize (MeshConservativeAdvancementTraversalNodeRSS< double > &node, const BVHModel< RSS< double >> &model1, const Transform3< double > &tf1, const BVHModel< RSS< double >> &model2, const Transform3< double > &tf2, double w) |
|
template<typename S > |
bool | initialize (MeshConservativeAdvancementTraversalNodeRSS< S > &node, const BVHModel< RSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< RSS< S >> &model2, const Transform3< S > &tf2, S w) |
| Initialize traversal node for conservative advancement computation between two meshes, given the current transforms, specialized for RSS. More...
|
|
template<typename S > |
FCL_EXPORT bool | initialize (MeshConservativeAdvancementTraversalNodeRSS< S > &node, const BVHModel< RSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< RSS< S >> &model2, const Transform3< S > &tf2, S w=1) |
| Initialize traversal node for conservative advancement computation between two meshes, given the current transforms, specialized for RSS. More...
|
|
template<typename BV > |
FCL_EXPORT bool | initialize (MeshContinuousCollisionTraversalNode< BV > &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request) |
| Initialize traversal node for continuous collision detection between two meshes. More...
|
|
template<typename BV > |
bool | initialize (MeshContinuousCollisionTraversalNode< BV > &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request) |
| Initialize traversal node for continuous collision detection between two meshes. More...
|
|
template<typename BV > |
bool | initialize (MeshDistanceTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result, bool use_refit, bool refit_bottomup) |
| Initialize traversal node for distance computation between two meshes, given the current transforms. More...
|
|
template<typename BV > |
FCL_EXPORT bool | initialize (MeshDistanceTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result, bool use_refit=false, bool refit_bottomup=false) |
| Initialize traversal node for distance computation between two meshes, given the current transforms. More...
|
|
template bool | initialize (MeshDistanceTraversalNodekIOS< double > &node, const BVHModel< kIOS< double >> &model1, const Transform3< double > &tf1, const BVHModel< kIOS< double >> &model2, const Transform3< double > &tf2, const DistanceRequest< double > &request, DistanceResult< double > &result) |
|
template<typename S > |
FCL_EXPORT bool | initialize (MeshDistanceTraversalNodekIOS< S > &node, const BVHModel< kIOS< S >> &model1, const Transform3< S > &tf1, const BVHModel< kIOS< S >> &model2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
| Initialize traversal node for distance computation between two meshes, specialized for kIOS type. More...
|
|
template<typename S > |
bool | initialize (MeshDistanceTraversalNodekIOS< S > &node, const BVHModel< kIOS< S >> &model1, const Transform3< S > &tf1, const BVHModel< kIOS< S >> &model2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
| Initialize traversal node for distance computation between two meshes, specialized for kIOS type. More...
|
|
template bool | initialize (MeshDistanceTraversalNodeOBBRSS< double > &node, const BVHModel< OBBRSS< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBBRSS< double >> &model2, const Transform3< double > &tf2, const DistanceRequest< double > &request, DistanceResult< double > &result) |
|
template<typename S > |
FCL_EXPORT bool | initialize (MeshDistanceTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
| Initialize traversal node for distance computation between two meshes, specialized for OBBRSS type. More...
|
|
template<typename S > |
bool | initialize (MeshDistanceTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
| Initialize traversal node for distance computation between two meshes, specialized for OBBRSS type. More...
|
|
template bool | initialize (MeshDistanceTraversalNodeRSS< double > &node, const BVHModel< RSS< double >> &model1, const Transform3< double > &tf1, const BVHModel< RSS< double >> &model2, const Transform3< double > &tf2, const DistanceRequest< double > &request, DistanceResult< double > &result) |
|
template<typename S > |
FCL_EXPORT bool | initialize (MeshDistanceTraversalNodeRSS< S > &node, const BVHModel< RSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< RSS< S >> &model2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
| Initialize traversal node for distance computation between two meshes, specialized for RSS type. More...
|
|
template<typename S > |
bool | initialize (MeshDistanceTraversalNodeRSS< S > &node, const BVHModel< RSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< RSS< S >> &model2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
| Initialize traversal node for distance computation between two meshes, specialized for RSS type. More...
|
|
template<typename BV , typename NarrowPhaseSolver > |
bool | initialize (MeshOcTreeCollisionTraversalNode< BV, NarrowPhaseSolver > &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const OcTree< typename BV::S > &model2, const Transform3< typename BV::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
| Initialize traversal node for collision between one mesh and one octree, given current object transform. More...
|
|
template<typename BV , typename NarrowPhaseSolver > |
bool | initialize (MeshOcTreeDistanceTraversalNode< BV, NarrowPhaseSolver > &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const OcTree< typename BV::S > &model2, const Transform3< typename BV::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
| Initialize traversal node for distance between one mesh and one octree, given current object transform. More...
|
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeCollisionTraversalNode< BV, Shape, NarrowPhaseSolver > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit, bool refit_bottomup) |
| Initialize traversal node for collision between one mesh and one shape, given current object transform. More...
|
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (MeshShapeCollisionTraversalNode< BV, Shape, NarrowPhaseSolver > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit=false, bool refit_bottomup=false) |
| Initialize traversal node for collision between one mesh and one shape, given current object transform. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (MeshShapeCollisionTraversalNodekIOS< Shape, NarrowPhaseSolver > &node, const BVHModel< kIOS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for kIOS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeCollisionTraversalNodekIOS< Shape, NarrowPhaseSolver > &node, const BVHModel< kIOS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for kIOS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (MeshShapeCollisionTraversalNodeOBB< Shape, NarrowPhaseSolver > &node, const BVHModel< OBB< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for OBB type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeCollisionTraversalNodeOBB< Shape, NarrowPhaseSolver > &node, const BVHModel< OBB< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for OBB type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (MeshShapeCollisionTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< OBBRSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeCollisionTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< OBBRSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (MeshShapeCollisionTraversalNodeRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< RSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for RSS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeCollisionTraversalNodeRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< RSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for RSS type. More...
|
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeConservativeAdvancementTraversalNode< BV, Shape, NarrowPhaseSolver > &node, BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, typename BV::S w, bool use_refit, bool refit_bottomup) |
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeConservativeAdvancementTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< OBBRSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, typename Shape::S w) |
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeConservativeAdvancementTraversalNodeRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< RSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, typename Shape::S w) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeDistanceTraversalNode< BV, Shape, NarrowPhaseSolver > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result, bool use_refit=false, bool refit_bottomup=false) |
| Initialize traversal node for distance computation between one mesh and one shape, given the current transforms. More...
|
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeDistanceTraversalNode< BV, Shape, NarrowPhaseSolver > &node, BVHModel< BV > &model1, Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result, bool use_refit, bool refit_bottomup) |
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeDistanceTraversalNodekIOS< Shape, NarrowPhaseSolver > &node, const BVHModel< kIOS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance computation between one mesh and one shape, specialized for kIOS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeDistanceTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< OBBRSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance computation between one mesh and one shape, specialized for OBBRSS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (MeshShapeDistanceTraversalNodeRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< RSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
|
template<typename NarrowPhaseSolver > |
bool | initialize (OcTreeCollisionTraversalNode< NarrowPhaseSolver > &node, const OcTree< typename NarrowPhaseSolver::S > &model1, const Transform3< typename NarrowPhaseSolver::S > &tf1, const OcTree< typename NarrowPhaseSolver::S > &model2, const Transform3< typename NarrowPhaseSolver::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const CollisionRequest< typename NarrowPhaseSolver::S > &request, CollisionResult< typename NarrowPhaseSolver::S > &result) |
| Initialize traversal node for collision between two octrees, given current object transform. More...
|
|
template<typename NarrowPhaseSolver > |
bool | initialize (OcTreeDistanceTraversalNode< NarrowPhaseSolver > &node, const OcTree< typename NarrowPhaseSolver::S > &model1, const Transform3< typename NarrowPhaseSolver::S > &tf1, const OcTree< typename NarrowPhaseSolver::S > &model2, const Transform3< typename NarrowPhaseSolver::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const DistanceRequest< typename NarrowPhaseSolver::S > &request, DistanceResult< typename NarrowPhaseSolver::S > &result) |
| Initialize traversal node for distance between two octrees, given current object transform. More...
|
|
template<typename BV , typename NarrowPhaseSolver > |
bool | initialize (OcTreeMeshCollisionTraversalNode< BV, NarrowPhaseSolver > &node, const OcTree< typename BV::S > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
| Initialize traversal node for collision between one octree and one mesh, given current object transform. More...
|
|
template<typename BV , typename NarrowPhaseSolver > |
bool | initialize (OcTreeMeshDistanceTraversalNode< BV, NarrowPhaseSolver > &node, const OcTree< typename BV::S > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
| Initialize traversal node for collision between one octree and one mesh, given current object transform. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (OcTreeShapeCollisionTraversalNode< Shape, NarrowPhaseSolver > &node, const OcTree< typename Shape::S > &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize traversal node for collision between one octree and one shape, given current object transform. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (OcTreeShapeDistanceTraversalNode< Shape, NarrowPhaseSolver > &node, const OcTree< typename Shape::S > &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance between one octree and one shape, given current object transform. More...
|
|
template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver > |
bool | initialize (ShapeCollisionTraversalNode< Shape1, Shape2, NarrowPhaseSolver > &node, const Shape1 &shape1, const Transform3< typename Shape1::S > &tf1, const Shape2 &shape2, const Transform3< typename Shape1::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape1::S > &request, CollisionResult< typename Shape1::S > &result) |
| Initialize traversal node for collision between two geometric shapes, given current object transform. More...
|
|
template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver > |
bool | initialize (ShapeConservativeAdvancementTraversalNode< Shape1, Shape2, NarrowPhaseSolver > &node, const Shape1 &shape1, const Transform3< typename Shape1::S > &tf1, const Shape2 &shape2, const Transform3< typename Shape1::S > &tf2, const NarrowPhaseSolver *nsolver) |
|
template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver > |
bool | initialize (ShapeDistanceTraversalNode< Shape1, Shape2, NarrowPhaseSolver > &node, const Shape1 &shape1, const Transform3< typename Shape1::S > &tf1, const Shape2 &shape2, const Transform3< typename Shape1::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape1::S > &request, DistanceResult< typename Shape1::S > &result) |
| Initialize traversal node for distance between two geometric shapes. More...
|
|
template<typename Shape , typename BV , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (ShapeMeshCollisionTraversalNode< Shape, BV, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit=false, bool refit_bottomup=false) |
| Initialize traversal node for collision between one mesh and one shape, given current object transform. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (ShapeMeshCollisionTraversalNodekIOS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< kIOS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for kIOS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (ShapeMeshCollisionTraversalNodeOBB< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< OBB< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for OBB type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (ShapeMeshCollisionTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< OBBRSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (ShapeMeshCollisionTraversalNodeRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< RSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize the traversal node for collision between one mesh and one shape, specialized for RSS type. More...
|
|
template<typename Shape , typename BV , typename NarrowPhaseSolver > |
bool | initialize (ShapeMeshConservativeAdvancementTraversalNode< Shape, BV, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, typename BV::S w, bool use_refit, bool refit_bottomup) |
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (ShapeMeshConservativeAdvancementTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< OBBRSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, typename Shape::S w) |
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (ShapeMeshConservativeAdvancementTraversalNodeRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< RSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, typename Shape::S w) |
|
template<typename Shape , typename BV , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (ShapeMeshDistanceTraversalNode< Shape, BV, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result, bool use_refit, bool refit_bottomup) |
| Initialize traversal node for distance computation between one shape and one mesh, given the current transforms. More...
|
|
template<typename Shape , typename BV , typename NarrowPhaseSolver > |
bool | initialize (ShapeMeshDistanceTraversalNode< Shape, BV, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result, bool use_refit=false, bool refit_bottomup=false) |
| Initialize traversal node for distance computation between one shape and one mesh, given the current transforms. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (ShapeMeshDistanceTraversalNodekIOS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< kIOS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance computation between one shape and one mesh, specialized for kIOS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (ShapeMeshDistanceTraversalNodekIOS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< kIOS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance computation between one shape and one mesh, specialized for kIOS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (ShapeMeshDistanceTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< OBBRSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance computation between one shape and one mesh, specialized for OBBRSS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (ShapeMeshDistanceTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< OBBRSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance computation between one shape and one mesh, specialized for OBBRSS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (ShapeMeshDistanceTraversalNodeRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< RSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance computation between one shape and one mesh, specialized for RSS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT bool | initialize (ShapeMeshDistanceTraversalNodeRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< RSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance computation between one shape and one mesh, specialized for RSS type. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (ShapeOcTreeCollisionTraversalNode< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const OcTree< typename Shape::S > &model2, const Transform3< typename Shape::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result) |
| Initialize traversal node for collision between one shape and one octree, given current object transform. More...
|
|
template<typename Shape , typename NarrowPhaseSolver > |
bool | initialize (ShapeOcTreeDistanceTraversalNode< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const OcTree< typename Shape::S > &model2, const Transform3< typename Shape::S > &tf2, const OcTreeSolver< NarrowPhaseSolver > *otsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
| Initialize traversal node for distance between one shape and one octree, given current object transform. More...
|
|
template int | intersectRectQuad2 (double h[2], double p[8], double ret[16]) |
|
template<typename S > |
FCL_EXPORT int | intersectRectQuad2 (S h[2], S p[8], S ret[16]) |
|
template<typename S > |
int | intersectRectQuad2 (S h[2], S p[8], S ret[16]) |
|
template<typename T > |
bool | IsElementInSet (const std::unordered_set< T * > &S, const T *element) |
|
template void | lineClosestApproach (const Vector3< double > &pa, const Vector3< double > &ua, const Vector3< double > &pb, const Vector3< double > &ub, double *alpha, double *beta) |
|
template<typename S > |
FCL_EXPORT void | lineClosestApproach (const Vector3< S > &pa, const Vector3< S > &ua, const Vector3< S > &pb, const Vector3< S > &ub, S *alpha, S *beta) |
|
template<typename S > |
void | lineClosestApproach (const Vector3< S > &pa, const Vector3< S > &ua, const Vector3< S > &pb, const Vector3< S > &ub, S *alpha, S *beta) |
|
template void | lineSegmentPointClosestToPoint (const Vector3< double > &p, const Vector3< double > &s1, const Vector3< double > &s2, Vector3< double > &sp) |
|
template<typename S > |
FCL_EXPORT void | lineSegmentPointClosestToPoint (const Vector3< S > &p, const Vector3< S > &s1, const Vector3< S > &s2, Vector3< S > &sp) |
|
template<typename S > |
void | lineSegmentPointClosestToPoint (const Vector3< S > &p, const Vector3< S > &s1, const Vector3< S > &s2, Vector3< S > &sp) |
|
template<typename T > |
void | MapFeature1ToFeature2 (const ccd_list_t *feature1_list, const ccd_list_t *feature2_list, std::function< bool(const T *, const T *)> cmp_feature, std::unordered_set< T * > *feature1, std::unordered_set< T * > *feature2, std::unordered_map< T *, T * > *map_feature1_to_feature2) |
|
template<typename S > |
FCL_EXPORT S | maximumDistance_mesh (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3< S > &query) |
|
template double | maximumDistance_mesh (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3d &query) |
|
template<typename S > |
FCL_EXPORT S | maximumDistance_pointcloud (const Vector3< S > *const ps, const Vector3< S > *const ps2, unsigned int *indices, int n, const Vector3< S > &query) |
|
template double | maximumDistance_pointcloud (const Vector3d *const ps, const Vector3d *const ps2, unsigned int *indices, int n, const Vector3d &query) |
|
template<typename BV > |
FCL_EXPORT void | meshCollisionOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, bool enable_statistics, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV > |
void | meshCollisionOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, bool enable_statistics, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV > |
FCL_EXPORT void | meshCollisionOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Transform3< typename BV::S > &tf, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, bool enable_statistics, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV > |
void | meshCollisionOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Transform3< typename BV::S > &tf, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, bool enable_statistics, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV > |
FCL_EXPORT bool | meshConservativeAdvancementOrientedNodeCanStop (typename BV::S c, typename BV::S min_distance, typename BV::S abs_err, typename BV::S rel_err, typename BV::S w, const BVHModel< BV > *model1, const BVHModel< BV > *model2, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, std::vector< ConservativeAdvancementStackData< typename BV::S >> &stack, typename BV::S &delta_t) |
|
template<typename BV > |
bool | meshConservativeAdvancementOrientedNodeCanStop (typename BV::S c, typename BV::S min_distance, typename BV::S abs_err, typename BV::S rel_err, typename BV::S w, const BVHModel< BV > *model1, const BVHModel< BV > *model2, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, std::vector< ConservativeAdvancementStackData< typename BV::S >> &stack, typename BV::S &delta_t) |
|
template<typename BV > |
FCL_EXPORT void | meshConservativeAdvancementOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Triangle *tri_indices1, const Triangle *tri_indices2, const Vector3< typename BV::S > *vertices1, const Vector3< typename BV::S > *vertices2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, bool enable_statistics, typename BV::S &min_distance, Vector3< typename BV::S > &p1, Vector3< typename BV::S > &p2, int &last_tri_id1, int &last_tri_id2, typename BV::S &delta_t, int &num_leaf_tests) |
|
template<typename BV > |
void | meshConservativeAdvancementOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Triangle *tri_indices1, const Triangle *tri_indices2, const Vector3< typename BV::S > *vertices1, const Vector3< typename BV::S > *vertices2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, bool enable_statistics, typename BV::S &min_distance, Vector3< typename BV::S > &p1, Vector3< typename BV::S > &p2, int &last_tri_id1, int &last_tri_id2, typename BV::S &delta_t, int &num_leaf_tests) |
|
template<typename BV > |
FCL_EXPORT bool | meshConservativeAdvancementTraversalNodeCanStop (typename BV::S c, typename BV::S min_distance, typename BV::S abs_err, typename BV::S rel_err, typename BV::S w, const BVHModel< BV > *model1, const BVHModel< BV > *model2, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, std::vector< ConservativeAdvancementStackData< typename BV::S >> &stack, typename BV::S &delta_t) |
|
template<typename BV > |
bool | meshConservativeAdvancementTraversalNodeCanStop (typename BV::S c, typename BV::S min_distance, typename BV::S abs_err, typename BV::S rel_err, typename BV::S w, const BVHModel< BV > *model1, const BVHModel< BV > *model2, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, std::vector< ConservativeAdvancementStackData< typename BV::S >> &stack, typename BV::S &delta_t) |
|
template<typename BV > |
FCL_DEPRECATED_EXPORT void | meshDistanceOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, bool enable_statistics, int &num_leaf_tests, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV > |
void | meshDistanceOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, bool enable_statistics, int &num_leaf_tests, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV > |
FCL_EXPORT void | meshDistanceOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Transform3< typename BV::S > &tf, bool enable_statistics, int &num_leaf_tests, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV > |
void | meshDistanceOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Transform3< typename BV::S > &tf, bool enable_statistics, int &num_leaf_tests, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
FCL_EXPORT void | meshShapeCollisionOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const Shape &model2, Vector3< typename BV::S > *vertices, Triangle *tri_indices, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, bool enable_statistics, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
void | meshShapeCollisionOrientedNodeLeafTesting (int b1, int b2, const BVHModel< BV > *model1, const Shape &model2, Vector3< typename BV::S > *vertices, Triangle *tri_indices, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, bool enable_statistics, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV , typename Shape > |
bool | meshShapeConservativeAdvancementOrientedNodeCanStop (typename BV::S c, typename BV::S min_distance, typename BV::S abs_err, typename BV::S rel_err, typename BV::S w, const BVHModel< BV > *model1, const Shape &model2, const BV &model2_bv, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, std::vector< ConservativeAdvancementStackData< typename BV::S >> &stack, typename BV::S &delta_t) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
void | meshShapeConservativeAdvancementOrientedNodeLeafTesting (int b1, int, const BVHModel< BV > *model1, const Shape &model2, const BV &model2_bv, Vector3< typename BV::S > *vertices, Triangle *tri_indices, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, bool enable_statistics, typename BV::S &min_distance, Vector3< typename BV::S > &p1, Vector3< typename BV::S > &p2, int &last_tri_id, typename BV::S &delta_t, int &num_leaf_tests) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver > |
void | meshShapeDistanceOrientedNodeLeafTesting (int b1, int, const BVHModel< BV > *model1, const Shape &model2, Vector3< typename BV::S > *vertices, Triangle *tri_indices, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, bool enable_statistics, int &num_leaf_tests, const DistanceRequest< typename BV::S > &, DistanceResult< typename BV::S > &result) |
|
template<typename S > |
bool | nearestPointInBox (const Vector3< S > &size, const Vector3< S > &p_BQ, Vector3< S > *p_BN_ptr) |
|
template<typename S > |
bool | nearestPointInCylinder (const S &height, const S &radius, const Vector3< S > &p_CQ, Vector3< S > *p_CN_ptr) |
|
template<typename BV > |
bool | nodeBaseLess (NodeBase< BV > *a, NodeBase< BV > *b, int d) |
| Compare two nodes accoording to the d-th dimension of node center. More...
|
|
template<typename OrientMeshShapeCollisionTraveralNode , typename BV , typename Shape , typename NarrowPhaseSolver > |
std::size_t | orientedBVHShapeCollide (const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename OrientedMeshShapeDistanceTraversalNode , typename BV , typename Shape , typename NarrowPhaseSolver > |
Shape::S | orientedBVHShapeDistance (const CollisionGeometry< typename Shape::S > *o1, const Transform3< typename Shape::S > &tf1, const CollisionGeometry< typename Shape::S > *o2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result) |
|
template<typename OrientedMeshCollisionTraversalNode , typename BV > |
std::size_t | orientedMeshCollide (const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename OrientedMeshDistanceTraversalNode , typename BV > |
BV::S | orientedMeshDistance (const CollisionGeometry< typename BV::S > *o1, const Transform3< typename BV::S > &tf1, const CollisionGeometry< typename BV::S > *o2, const Transform3< typename BV::S > &tf2, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename S > |
bool | overlap (S a1, S a2, S b1, S b2) |
| returns 1 if the intervals overlap, and 0 otherwise More...
|
|
template bool | planeHalfspaceIntersect (const Plane< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Plane< double > &pl, Vector3< double > &p, Vector3< double > &d, double &penetration_depth, int &ret) |
|
template<typename S > |
FCL_EXPORT bool | planeHalfspaceIntersect (const Plane< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, Plane< S > &pl, Vector3< S > &p, Vector3< S > &d, S &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...
|
|
template<typename S > |
bool | planeHalfspaceIntersect (const Plane< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, Plane< S > &pl, Vector3< S > &p, Vector3< S > &d, S &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...
|
|
template bool | planeIntersect (const Plane< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
bool | planeIntersect (const Plane< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *) |
|
template<typename S > |
FCL_EXPORT bool | planeIntersect (const Plane< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<> |
FCL_EXPORT double | planeIntersectTolerance () |
|
template<typename S > |
FCL_EXPORT S | planeIntersectTolerance () |
|
template<typename S > |
S | planeIntersectTolerance () |
|
template bool | planeTriangleIntersect (const Plane< double > &s1, const Transform3< double > &tf1, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal) |
|
template<typename S > |
FCL_EXPORT bool | planeTriangleIntersect (const Plane< S > &s1, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
|
template<typename S > |
bool | planeTriangleIntersect (const Plane< S > &s1, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) |
|
template bool | projectInTriangle (const Vector3< double > &p1, const Vector3< double > &p2, const Vector3< double > &p3, const Vector3< double > &normal, const Vector3< double > &p) |
|
template<typename S > |
FCL_EXPORT bool | projectInTriangle (const Vector3< S > &p1, const Vector3< S > &p2, const Vector3< S > &p3, const Vector3< S > &normal, const Vector3< S > &p) |
| Whether a point's projection is in a triangle. More...
|
|
template<typename S > |
bool | projectInTriangle (const Vector3< S > &p1, const Vector3< S > &p2, const Vector3< S > &p3, const Vector3< S > &normal, const Vector3< S > &p) |
| Whether a point's projection is in a triangle. More...
|
|
template void | propagateBVHFrontListCollisionRecurse (CollisionTraversalNodeBase< double > *node, BVHFrontList *front_list) |
|
template<typename S > |
FCL_EXPORT void | propagateBVHFrontListCollisionRecurse (CollisionTraversalNodeBase< S > *node, BVHFrontList *front_list) |
| Recurse function for front list propagation. More...
|
|
template double | segmentSqrDistance (const Vector3< double > &from, const Vector3< double > &to, const Vector3< double > &p, Vector3< double > &nearest) |
|
template<typename S > |
FCL_EXPORT S | segmentSqrDistance (const Vector3< S > &from, const Vector3< S > &to, const Vector3< S > &p, Vector3< S > &nearest) |
| the minimum distance from a point to a line More...
|
|
template<typename S > |
S | segmentSqrDistance (const Vector3< S > &from, const Vector3< S > &to, const Vector3< S > &p, Vector3< S > &nearest) |
| the minimum distance from a point to a line More...
|
|
template<typename BV > |
size_t | select (const BV &query, const NodeBase< BV > &node1, const NodeBase< BV > &node2) |
| select from node1 and node2 which is close to a given query bounding volume. 0 for node1 and 1 for node2 More...
|
|
template<typename BV > |
size_t | select (const NodeBase< BV > &query, const NodeBase< BV > &node1, const NodeBase< BV > &node2) |
| select from node1 and node2 which is close to a given query. 0 for node1 and 1 for node2 More...
|
|
template void | selfCollide (CollisionTraversalNodeBase< double > *node, BVHFrontList *front_list) |
|
template<typename S > |
void | selfCollide (CollisionTraversalNodeBase< S > *node, BVHFrontList *front_list) |
| self collision on collision traversal node; can use front list to accelerate More...
|
|
template<typename S > |
FCL_EXPORT void | selfCollide (CollisionTraversalNodeBase< S > *node, BVHFrontList *front_list=nullptr) |
| self collision on collision traversal node; can use front list to accelerate More...
|
|
template void | selfCollisionRecurse (CollisionTraversalNodeBase< double > *node, int b, BVHFrontList *front_list) |
|
template<typename S > |
FCL_EXPORT void | selfCollisionRecurse (CollisionTraversalNodeBase< S > *node, int b, BVHFrontList *front_list) |
| Recurse function for self collision. Make sure node is set correctly so that the first and second tree are the same. More...
|
|
template<typename S > |
void | SetUpBoxToBox (const Transform3< S > &X_WF, void **o1, void **o2, ccd_t *ccd, fcl::Transform3< S > *X_FB1, fcl::Transform3< S > *X_FB2) |
|
template<typename BV , typename OrientedNode > |
bool | setupMeshCollisionOrientedNode (OrientedNode &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV , typename OrientedDistanceNode > |
bool | setupMeshConservativeAdvancementOrientedDistanceNode (OrientedDistanceNode &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, typename BV::S w) |
|
template<typename BV , typename OrientedNode > |
static bool | setupMeshDistanceOrientedNode (OrientedNode &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver , template< typename, typename > class OrientedNode> |
bool | setupMeshShapeCollisionOrientedNode (OrientedNode< Shape, NarrowPhaseSolver > &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename BV , typename Shape , typename NarrowPhaseSolver , template< typename, typename > class OrientedNode> |
static bool | setupMeshShapeDistanceOrientedNode (OrientedNode< Shape, NarrowPhaseSolver > &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename Shape , typename BV , typename NarrowPhaseSolver , template< typename, typename > class OrientedNode> |
static bool | setupShapeMeshCollisionOrientedNode (OrientedNode< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result) |
|
template<typename Shape , typename BV , typename NarrowPhaseSolver , template< typename, typename > class OrientedNode> |
static bool | setupShapeMeshDistanceOrientedNode (OrientedNode< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result) |
|
template<typename Shape , typename BV , typename NarrowPhaseSolver > |
BV::S | ShapeBVHConservativeAdvancement (const CollisionGeometry< typename BV::S > *o1, const MotionBase< typename BV::S > *motion1, const CollisionGeometry< typename BV::S > *o2, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, const ContinuousCollisionRequest< typename BV::S > &request, ContinuousCollisionResult< typename BV::S > &result) |
|
template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver > |
Shape1::S | ShapeConservativeAdvancement (const CollisionGeometry< typename Shape1::S > *o1, const MotionBase< typename Shape1::S > *motion1, const CollisionGeometry< typename Shape1::S > *o2, const MotionBase< typename Shape1::S > *motion2, const NarrowPhaseSolver *nsolver, const ContinuousCollisionRequest< typename Shape1::S > &request, ContinuousCollisionResult< typename Shape1::S > &result) |
|
template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver > |
std::size_t | ShapeShapeCollide (const CollisionGeometry< typename Shape1::S > *o1, const Transform3< typename Shape1::S > &tf1, const CollisionGeometry< typename Shape1::S > *o2, const Transform3< typename Shape1::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape1::S > &request, CollisionResult< typename Shape1::S > &result) |
|
template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver > |
Shape1::S | ShapeShapeDistance (const CollisionGeometry< typename Shape1::S > *o1, const Transform3< typename Shape1::S > &tf1, const CollisionGeometry< typename Shape1::S > *o2, const Transform3< typename Shape1::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename Shape1::S > &request, DistanceResult< typename Shape1::S > &result) |
|
template<typename S > |
static void | shapeToGJK (const ShapeBase< S > &s, const Transform3< S > &tf, ccd_obj_t *o) |
|
template FCL_EXPORT bool | sphereBoxDistance (const Sphere< double > &sphere, const Transform3< double > &X_FS, const Box< double > &box, const Transform3< double > &X_FB, double *distance, Vector3< double > *p_FSb, Vector3< double > *p_FBs) |
|
template FCL_EXPORT bool | sphereBoxIntersect (const Sphere< double > &sphere, const Transform3< double > &X_FS, const Box< double > &box, const Transform3< double > &X_FB, std::vector< ContactPoint< double >> *contacts) |
|
template bool | sphereCapsuleDistance (const Sphere< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, double *dist, Vector3< double > *p1, Vector3< double > *p2) |
|
template<typename S > |
FCL_EXPORT bool | sphereCapsuleDistance (const Sphere< S > &s1, const Transform3< S > &tf1, const Capsule< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template<typename S > |
bool | sphereCapsuleDistance (const Sphere< S > &s1, const Transform3< S > &tf1, const Capsule< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template bool | sphereCapsuleIntersect (const Sphere< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | sphereCapsuleIntersect (const Sphere< S > &s1, const Transform3< S > &tf1, const Capsule< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | sphereCapsuleIntersect (const Sphere< S > &s1, const Transform3< S > &tf1, const Capsule< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template FCL_EXPORT bool | sphereCylinderDistance (const Sphere< double > &sphere, const Transform3< double > &X_FS, const Cylinder< double > &cylinder, const Transform3< double > &X_FC, double *distance, Vector3< double > *p_FSc, Vector3< double > *p_FCs) |
|
template FCL_EXPORT bool | sphereCylinderIntersect (const Sphere< double > &sphere, const Transform3< double > &X_FS, const Cylinder< double > &cylinder, const Transform3< double > &X_FC, std::vector< ContactPoint< double >> *contacts) |
|
template bool | sphereHalfspaceIntersect (const Sphere< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | sphereHalfspaceIntersect (const Sphere< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | sphereHalfspaceIntersect (const Sphere< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template bool | spherePlaneIntersect (const Sphere< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | spherePlaneIntersect (const Sphere< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
bool | spherePlaneIntersect (const Sphere< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template FCL_EXPORT bool | sphereSphereDistance (const Sphere< double > &s1, const Transform3< double > &tf1, const Sphere< double > &s2, const Transform3< double > &tf2, double *dist, Vector3< double > *p1, Vector3< double > *p2) |
|
template<typename S > |
bool | sphereSphereDistance (const Sphere< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template<typename S > |
FCL_EXPORT bool | sphereSphereDistance (const Sphere< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template FCL_EXPORT bool | sphereSphereIntersect (const Sphere< double > &s1, const Transform3< double > &tf1, const Sphere< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts) |
|
template<typename S > |
bool | sphereSphereIntersect (const Sphere< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
FCL_EXPORT bool | sphereSphereIntersect (const Sphere< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts) |
|
template<typename S > |
static void | sphereToGJK (const Sphere< S > &s, const Transform3< S > &tf, ccd_sphere_t *sph) |
|
template bool | sphereTriangleDistance (const Sphere< double > &sp, const Transform3< double > &tf, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, double *dist) |
|
template bool | sphereTriangleDistance (const Sphere< double > &sp, const Transform3< double > &tf, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, double *dist, Vector3< double > *p1, Vector3< double > *p2) |
|
template bool | sphereTriangleDistance (const Sphere< double > &sp, const Transform3< double > &tf1, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, const Transform3< double > &tf2, double *dist, Vector3< double > *p1, Vector3< double > *p2) |
|
template<typename S > |
FCL_EXPORT bool | sphereTriangleDistance (const Sphere< S > &sp, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *dist) |
|
template<typename S > |
bool | sphereTriangleDistance (const Sphere< S > &sp, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *dist) |
|
template<typename S > |
FCL_EXPORT bool | sphereTriangleDistance (const Sphere< S > &sp, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template<typename S > |
bool | sphereTriangleDistance (const Sphere< S > &sp, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template<typename S > |
FCL_EXPORT bool | sphereTriangleDistance (const Sphere< S > &sp, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template<typename S > |
bool | sphereTriangleDistance (const Sphere< S > &sp, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2) |
|
template bool | sphereTriangleIntersect (const Sphere< double > &s, const Transform3< double > &tf, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal_) |
|
template<typename S > |
FCL_EXPORT bool | sphereTriangleIntersect (const Sphere< S > &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal_) |
|
template<typename S > |
bool | sphereTriangleIntersect (const Sphere< S > &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal_) |
|
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) |
|
template<typename S > |
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 | supportEllipsoid (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) |
|
| TEST_F (ExtractClosestPoint, ExtractFrom1Simplex) |
|
| TEST_F (ExtractClosestPoint, ExtractFrom1SimplexSupport) |
|
| TEST_F (ExtractClosestPoint, ExtractFrom2Simplex) |
|
| TEST_F (ExtractClosestPoint, ExtractFrom2SimplexDegenerate) |
|
| TEST_F (ExtractClosestPoint, ExtractFrom2SimplexSupport) |
|
| TEST_F (ExtractClosestPoint, ExtractFrom3SimplesDegenerateCoincident) |
|
| TEST_F (ExtractClosestPoint, ExtractFrom3SimplesDegenerateColinear) |
|
| TEST_F (ExtractClosestPoint, ExtractFrom3Simplex) |
|
template<typename S > |
void | TestBoxes () |
|
template<typename S > |
void | TestBoxesInFrameF (const Transform3< S > &X_WF) |
|
template<typename S > |
void | TestCollidingSphereGJKSignedDistance () |
|
template<typename S > |
void | TestNonCollidingSphereGJKSignedDistance () |
|
template<typename S > |
void | TestSimplexToPolytope3 () |
|
template<typename S > |
void | TestSimplexToPolytope3InGivenFrame (const Transform3< S > &X_WF) |
|
template<typename S > |
void | TestSphereToSphereGJKSignedDistance (S radius1, S radius2, const Vector3< S > &p_F1, const Vector3< S > &p_F2, S solver_tolerance, S test_tol, S min_distance_expected) |
|
std::array< Vector3< ccd_real_t >, 4 > | TetrahedronColinearVertices () |
|
std::array< Vector3< ccd_real_t >, 4 > | TetrahedronSmallFaceVertices () |
|
template<typename Shape1 , typename Shape2 , typename Solver , typename S > |
void | ThrowDetailedConfiguration (const Shape1 &s1, const Transform3< S > &X_FS1, const Shape2 &s2, const Transform3< S > &X_FS2, const Solver &solver, const std::exception &e) |
|
FCL_EXPORT void | ThrowFailedAtThisConfiguration (const std::string &message, const char *func, const char *file, int line) |
|
template<typename S > |
ccd_vec3_t | ToCcdVec3 (const Eigen::Ref< const Vector3< S >> &v) |
|
template<typename S > |
Vector3< S > | ToEigenVector (const ccd_vec3_t &v) |
|
bool | triangle_area_is_zero (const Vector3d &a, const Vector3d &b, const Vector3d &c) |
|
bool | TriangleMatch (const ccd_pt_face_t *f1, const ccd_pt_face_t *f2, const std::unordered_map< ccd_pt_edge_t *, ccd_pt_edge_t * > &map_e1_to_e2) |
|
template<typename S > |
FCL_EXPORT void * | triCreateGJKObject (const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3) |
|
template<typename S > |
void * | triCreateGJKObject (const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3) |
|
template<typename S > |
FCL_EXPORT void * | triCreateGJKObject (const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf) |
|
template<typename S > |
void * | triCreateGJKObject (const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf) |
|
template void * | triCreateGJKObject (const Vector3d &P1, const Vector3d &P2, const Vector3d &P3) |
|
template void * | triCreateGJKObject (const Vector3d &P1, const Vector3d &P2, const Vector3d &P3, const Transform3d &tf) |
|
void | triDeleteGJKObject (void *o_) |
|
GJKCenterFunction | triGetCenterFunction () |
|
GJKSupportFunction | triGetSupportFunction () |
| initialize GJK Triangle More...
|
|
FCL_EXPORT void | updateFrontList (BVHFrontList *front_list, int b1, int b2) |
| Add new front node into the front list. More...
|
|
template<typename Shape > |
::testing::AssertionResult | ValidateRepresentation (const Shape &shape, const std::string &code_string) |
|
bool | VertexPositionCoincide (const ccd_pt_vertex_t *v1, const ccd_pt_vertex_t *v2, ccd_real_t tol) |
|
template<typename S > |
void | WriteCommaSeparated (std::stringstream *sstream, const Transform3< S > &p) |
|
template<typename S > |
Vector3< S > | z_axis (const Transform3< S > &X_AB) |
|