Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
fcl::detail Namespace Reference

Namespaces

 dynamic_AABB_tree
 
 dynamic_AABB_tree_array
 
 implementation_array
 
 kIOS_fit_functions
 
 libccd_extension
 
 OBB_fit_functions
 
 OBBRSS_fit_functions
 
 RSS_fit_functions
 

Classes

struct  ApplyImpl
 
struct  ApplyImpl< S, kIOS< S > >
 
struct  ApplyImpl< S, OBB< S > >
 
struct  ApplyImpl< S, OBBRSS< S > >
 
struct  ApplyImpl< S, RSS< S > >
 
struct  BoxSpecification
 
class  BVFitter
 The class for the default algorithm fitting a bounding volume to a set of points. More...
 
class  BVFitterBase
 Interface for fitting a bv given the triangles or points inside it. More...
 
struct  BVHCollideImpl
 
struct  BVHCollideImpl< S, kIOS< S > >
 
struct  BVHCollideImpl< S, OBB< S > >
 
struct  BVHCollideImpl< S, OBBRSS< S > >
 
class  BVHCollisionTraversalNode
 Traversal node for collision between BVH models. More...
 
struct  BVHContinuousCollisionPair
 Traversal node for continuous collision between BVH models. More...
 
struct  BVHDistanceImpl
 
struct  BVHDistanceImpl< S, kIOS< S > >
 
struct  BVHDistanceImpl< S, OBBRSS< S > >
 
struct  BVHDistanceImpl< S, RSS< S > >
 
class  BVHDistanceTraversalNode
 Traversal node for distance computation between BVH models. More...
 
struct  BVHFrontNode
 Front list acceleration for collision Front list is a set of internal and leaf nodes in the BVTT hierarchy, where the traversal terminates while performing a query during a given time instance. The front list reflects the subset of a BVTT that is traversed for that particular proximity query. More...
 
struct  BVHShapeCollider
 
struct  BVHShapeCollider< kIOS< typename Shape::S >, Shape, NarrowPhaseSolver >
 
struct  BVHShapeCollider< OBB< typename Shape::S >, Shape, NarrowPhaseSolver >
 
struct  BVHShapeCollider< OBBRSS< typename Shape::S >, Shape, NarrowPhaseSolver >
 
struct  BVHShapeCollider< RSS< typename Shape::S >, Shape, NarrowPhaseSolver >
 
class  BVHShapeCollisionTraversalNode
 Traversal node for collision between BVH and shape. More...
 
struct  BVHShapeDistancer
 
struct  BVHShapeDistancer< kIOS< typename Shape::S >, Shape, NarrowPhaseSolver >
 
struct  BVHShapeDistancer< OBBRSS< typename Shape::S >, Shape, NarrowPhaseSolver >
 
struct  BVHShapeDistancer< RSS< typename Shape::S >, Shape, NarrowPhaseSolver >
 
class  BVHShapeDistanceTraversalNode
 Traversal node for distance computation between BVH and shape. More...
 
class  BVSplitter
 A class describing the split rule that splits each BV node. More...
 
class  BVSplitterBase
 Base interface for BV splitting algorithm. More...
 
struct  BVT
 Bounding volume test structure. More...
 
struct  BVT_Comparer
 Comparer between two BVT. More...
 
struct  BVTQ
 
struct  CanStopImpl
 
struct  CanStopImpl< S, OBB< S > >
 
struct  CanStopImpl< S, OBBRSS< S > >
 
struct  CanStopImpl< S, RSS< S > >
 
struct  ccd_box_t
 
struct  ccd_cap_t
 
struct  ccd_cone_t
 
struct  ccd_convex_t
 
struct  ccd_cyl_t
 
struct  ccd_ellipsoid_t
 
struct  ccd_obj_t
 
struct  ccd_sphere_t
 
struct  ccd_triangle_t
 
struct  CollisionFunctionMatrix
 collision matrix stores the functions for collision between different types of objects and provides a uniform call interface More...
 
class  CollisionTraversalNodeBase
 Node structure encoding the information required for collision traversal. More...
 
struct  ComputeBVImpl
 
struct  ComputeBVImpl< S, AABB< S >, Box< S > >
 
struct  ComputeBVImpl< S, AABB< S >, Capsule< S > >
 
struct  ComputeBVImpl< S, AABB< S >, Cone< S > >
 
struct  ComputeBVImpl< S, AABB< S >, Convex< S > >
 
struct  ComputeBVImpl< S, AABB< S >, Cylinder< S > >
 
struct  ComputeBVImpl< S, AABB< S >, Ellipsoid< S > >
 
struct  ComputeBVImpl< S, AABB< S >, Halfspace< S > >
 
struct  ComputeBVImpl< S, AABB< S >, Plane< S > >
 
struct  ComputeBVImpl< S, AABB< S >, Sphere< S > >
 
struct  ComputeBVImpl< S, AABB< S >, TriangleP< S > >
 
struct  ComputeBVImpl< S, KDOP< S, 16 >, Halfspace< S > >
 
struct  ComputeBVImpl< S, KDOP< S, 16 >, Plane< S > >
 
struct  ComputeBVImpl< S, KDOP< S, 18 >, Halfspace< S > >
 
struct  ComputeBVImpl< S, KDOP< S, 18 >, Plane< S > >
 
struct  ComputeBVImpl< S, KDOP< S, 24 >, Halfspace< S > >
 
struct  ComputeBVImpl< S, KDOP< S, 24 >, Plane< S > >
 
struct  ComputeBVImpl< S, kIOS< S >, Halfspace< S > >
 
struct  ComputeBVImpl< S, kIOS< S >, Plane< S > >
 
struct  ComputeBVImpl< S, OBB< S >, Box< S > >
 
struct  ComputeBVImpl< S, OBB< S >, Capsule< S > >
 
struct  ComputeBVImpl< S, OBB< S >, Cone< S > >
 
struct  ComputeBVImpl< S, OBB< S >, Convex< S > >
 
struct  ComputeBVImpl< S, OBB< S >, Cylinder< S > >
 
struct  ComputeBVImpl< S, OBB< S >, Ellipsoid< S > >
 
struct  ComputeBVImpl< S, OBB< S >, Halfspace< S > >
 
struct  ComputeBVImpl< S, OBB< S >, Plane< S > >
 
struct  ComputeBVImpl< S, OBB< S >, Sphere< S > >
 
struct  ComputeBVImpl< S, OBBRSS< S >, Halfspace< S > >
 
struct  ComputeBVImpl< S, OBBRSS< S >, Plane< S > >
 
struct  ComputeBVImpl< S, RSS< S >, Halfspace< S > >
 
struct  ComputeBVImpl< S, RSS< S >, Plane< S > >
 
struct  ComputeRuleCenterImpl
 
struct  ComputeRuleCenterImpl< S, kIOS< S > >
 
struct  ComputeRuleCenterImpl< S, OBB< S > >
 
struct  ComputeRuleCenterImpl< S, OBBRSS< S > >
 
struct  ComputeRuleCenterImpl< S, RSS< S > >
 
struct  ComputeRuleMeanImpl
 
struct  ComputeRuleMeanImpl< S, kIOS< S > >
 
struct  ComputeRuleMeanImpl< S, OBB< S > >
 
struct  ComputeRuleMeanImpl< S, OBBRSS< S > >
 
struct  ComputeRuleMeanImpl< S, RSS< S > >
 
struct  ComputeRuleMedianImpl
 
struct  ComputeRuleMedianImpl< S, kIOS< S > >
 
struct  ComputeRuleMedianImpl< S, OBB< S > >
 
struct  ComputeRuleMedianImpl< S, OBBRSS< S > >
 
struct  ComputeRuleMedianImpl< S, RSS< S > >
 
struct  ComputeSplitVectorImpl
 
struct  ComputeSplitVectorImpl< S, kIOS< S > >
 
struct  ComputeSplitVectorImpl< S, OBBRSS< S > >
 
struct  ConservativeAdvancementFunctionMatrix
 
struct  ConservativeAdvancementImpl
 
struct  ConservativeAdvancementImpl< S, BVHModel< OBBRSS< S > >, NarrowPhaseSolver >
 
struct  ConservativeAdvancementImpl< S, BVHModel< RSS< S > >, NarrowPhaseSolver >
 
struct  ConservativeAdvancementStackData
 
class  ConvertBVImpl
 Convert a bounding volume of type BV1 in configuration tf1 to a bounding volume of type BV2 in I configuration. More...
 
class  ConvertBVImpl< S, AABB< S >, AABB< S > >
 Convert from AABB to AABB, not very tight but is fast. More...
 
class  ConvertBVImpl< S, AABB< S >, OBB< S > >
 
class  ConvertBVImpl< S, AABB< S >, RSS< S > >
 
class  ConvertBVImpl< S, BV1, AABB< S > >
 
class  ConvertBVImpl< S, BV1, OBB< S > >
 
class  ConvertBVImpl< S, OBB< S >, OBB< S > >
 
class  ConvertBVImpl< S, OBB< S >, RSS< S > >
 
class  ConvertBVImpl< S, OBBRSS< S >, OBB< S > >
 
class  ConvertBVImpl< S, OBBRSS< S >, RSS< S > >
 
class  ConvertBVImpl< S, RSS< S >, OBB< S > >
 
class  ConvertBVImpl< S, RSS< S >, RSS< S > >
 
struct  dataDoubleVal
 
struct  dataIntVal
 
struct  DistanceFunctionMatrix
 distance matrix stores the functions for distance between different types of objects and provides a uniform call interface More...
 
class  DistanceTraversalNodeBase
 Node structure encoding the information required for distance traversal. More...
 
struct  EPA
 class for EPA algorithm More...
 
class  EquilateralTetrahedron
 
class  ExtractClosestPoint
 
class  FailedAtThisConfiguration
 
struct  FitImpl
 
struct  FitImpl< S, kIOS< S > >
 
struct  FitImpl< S, OBB< S > >
 
struct  FitImpl< S, OBBRSS< S > >
 
struct  FitImpl< S, RSS< S > >
 
struct  Fitter
 
struct  Fitter< S, kIOS< S > >
 
struct  Fitter< S, OBB< S > >
 
struct  Fitter< S, OBBRSS< S > >
 
struct  Fitter< S, RSS< S > >
 
struct  GetBVAxisImpl
 for OBB and RSS, there is local coordinate of BV, so normal need to be transformed More...
 
struct  GetBVAxisImpl< S, OBBRSS< S > >
 
struct  GJK
 class for GJK algorithm More...
 
class  GJKInitializer
 initialize GJK stuffs More...
 
class  GJKInitializer< S, Box< S > >
 initialize GJK Box More...
 
class  GJKInitializer< S, Capsule< S > >
 initialize GJK Capsule More...
 
class  GJKInitializer< S, Cone< S > >
 initialize GJK Cone More...
 
class  GJKInitializer< S, Convex< S > >
 initialize GJK Convex More...
 
class  GJKInitializer< S, Cylinder< S > >
 initialize GJK Cylinder More...
 
class  GJKInitializer< S, Ellipsoid< S > >
 initialize GJK Ellipsoid More...
 
class  GJKInitializer< S, Sphere< S > >
 initialize GJK Sphere More...
 
struct  GJKSolver_indep
 collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the GJK in bullet) More...
 
struct  GJKSolver_libccd
 collision and distance solver based on libccd library. More...
 
class  Hexagram
 
class  HierarchyTree
 Class for hierarchy tree structure. More...
 
class  Intersect
 CCD intersect kernel among primitives. More...
 
class  IntervalTree
 Interval tree. More...
 
class  IntervalTreeNode
 The node for interval tree. More...
 
struct  it_recursion_node
 Class describes the information needed when we take the right branch in searching for intervals but possibly come back and check the left branch as well. More...
 
class  MeshCollisionTraversalNode
 Traversal node for collision between two meshes. More...
 
class  MeshCollisionTraversalNodekIOS
 
class  MeshCollisionTraversalNodeOBB
 Traversal node for collision between two meshes if their underlying BVH node is oriented node (OBB, RSS, OBBRSS, kIOS) More...
 
class  MeshCollisionTraversalNodeOBBRSS
 
class  MeshCollisionTraversalNodeRSS
 
class  MeshConservativeAdvancementTraversalNode
 continuous collision node using conservative advancement. when using this default version, must refit the BVH in current configuration (R_t, T_t) into default configuration More...
 
class  MeshConservativeAdvancementTraversalNodeOBBRSS
 
class  MeshConservativeAdvancementTraversalNodeRSS
 
class  MeshContinuousCollisionTraversalNode
 Traversal node for continuous collision between meshes. More...
 
class  MeshDistanceTraversalNode
 Traversal node for distance computation between two meshes. More...
 
class  MeshDistanceTraversalNodekIOS
 
class  MeshDistanceTraversalNodeOBBRSS
 
class  MeshDistanceTraversalNodeRSS
 Traversal node for distance computation between two meshes if their underlying BVH node is oriented node (RSS, OBBRSS, kIOS) More...
 
class  MeshOcTreeCollisionTraversalNode
 Traversal node for mesh-octree collision. More...
 
class  MeshOcTreeDistanceTraversalNode
 Traversal node for mesh-octree distance. More...
 
class  MeshShapeCollisionTraversalNode
 Traversal node for collision between mesh and shape. More...
 
class  MeshShapeCollisionTraversalNodekIOS
 
class  MeshShapeCollisionTraversalNodeOBB
 Traversal node for mesh and shape, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS) More...
 
class  MeshShapeCollisionTraversalNodeOBBRSS
 
class  MeshShapeCollisionTraversalNodeRSS
 
class  MeshShapeConservativeAdvancementTraversalNode
 Traversal node for conservative advancement computation between BVH and shape. More...
 
class  MeshShapeConservativeAdvancementTraversalNodeOBBRSS
 
class  MeshShapeConservativeAdvancementTraversalNodeRSS
 
class  MeshShapeDistanceTraversalNode
 Traversal node for distance between mesh and shape. More...
 
class  MeshShapeDistanceTraversalNodekIOS
 
class  MeshShapeDistanceTraversalNodeOBBRSS
 
class  MeshShapeDistanceTraversalNodeRSS
 Traversal node for distance between mesh and shape, when mesh BVH is one of the oriented node (RSS, OBBRSS, kIOS) More...
 
struct  MinkowskiDiff
 Minkowski difference class of two shapes. More...
 
struct  NodeBase
 dynamic AABB tree node More...
 
class  OcTreeCollisionTraversalNode
 Traversal node for octree collision. More...
 
class  OcTreeDistanceTraversalNode
 Traversal node for octree distance. More...
 
class  OcTreeMeshCollisionTraversalNode
 Traversal node for octree-mesh collision. More...
 
class  OcTreeMeshDistanceTraversalNode
 Traversal node for octree-mesh distance. More...
 
class  OcTreeShapeCollisionTraversalNode
 Traversal node for octree-shape collision. More...
 
class  OcTreeShapeDistanceTraversalNode
 Traversal node for octree-shape distance. More...
 
class  OcTreeSolver
 Algorithms for collision related with octree. More...
 
class  PolySolver
 A class solves polynomial degree (1,2,3) equations. More...
 
class  Polytope
 
class  Profiler
 This is a simple thread-safe tool for counting time spent in various chunks of code. This is different from external profiling tools in that it allows the user to count time spent in various bits of code (sub-function granularity) or count how many times certain pieces of code are executed. More...
 
class  Project
 Project functions. More...
 
struct  ScalarRepr
 
struct  ScalarRepr< double >
 
struct  ScalarRepr< float >
 
struct  ScalarTrait
 
struct  ScalarTrait< double >
 
struct  ScalarTrait< float >
 
struct  ScalarTrait< long double >
 
class  Seed
 
struct  SelectImpl
 
struct  SelectImpl< S, AABB< S > >
 
struct  SetImpl
 
struct  SetImpl< S, kIOS< S > >
 
struct  SetImpl< S, OBB< S > >
 
struct  SetImpl< S, OBBRSS< S > >
 
struct  SetImpl< S, RSS< S > >
 
class  ShapeBVHCollisionTraversalNode
 Traversal node for collision between shape and BVH. More...
 
class  ShapeBVHDistanceTraversalNode
 Traversal node for distance computation between shape and BVH. More...
 
class  ShapeCollisionTraversalNode
 Traversal node for collision between two shapes. More...
 
class  ShapeConservativeAdvancementTraversalNode
 
struct  ShapeDistanceIndepImpl
 
struct  ShapeDistanceIndepImpl< S, Box< S >, Sphere< S > >
 
struct  ShapeDistanceIndepImpl< S, Capsule< S >, Capsule< S > >
 
struct  ShapeDistanceIndepImpl< S, Capsule< S >, Sphere< S > >
 
struct  ShapeDistanceIndepImpl< S, Cylinder< S >, Sphere< S > >
 
struct  ShapeDistanceIndepImpl< S, Sphere< S >, Box< S > >
 
struct  ShapeDistanceIndepImpl< S, Sphere< S >, Capsule< S > >
 
struct  ShapeDistanceIndepImpl< S, Sphere< S >, Cylinder< S > >
 
struct  ShapeDistanceIndepImpl< S, Sphere< S >, Sphere< S > >
 
struct  ShapeDistanceLibccdImpl
 
struct  ShapeDistanceLibccdImpl< S, Box< S >, Sphere< S > >
 
struct  ShapeDistanceLibccdImpl< S, Capsule< S >, Capsule< S > >
 
struct  ShapeDistanceLibccdImpl< S, Capsule< S >, Sphere< S > >
 
struct  ShapeDistanceLibccdImpl< S, Cylinder< S >, Sphere< S > >
 
struct  ShapeDistanceLibccdImpl< S, Sphere< S >, Box< S > >
 
struct  ShapeDistanceLibccdImpl< S, Sphere< S >, Capsule< S > >
 
struct  ShapeDistanceLibccdImpl< S, Sphere< S >, Cylinder< S > >
 
struct  ShapeDistanceLibccdImpl< S, Sphere< S >, Sphere< S > >
 
class  ShapeDistanceTraversalNode
 Traversal node for distance between two shapes. More...
 
struct  ShapeIntersectIndepImpl
 
struct  ShapeIntersectIndepImpl< S, Halfspace< S >, Halfspace< S > >
 
struct  ShapeIntersectIndepImpl< S, Halfspace< S >, Plane< S > >
 
struct  ShapeIntersectIndepImpl< S, Plane< S >, Halfspace< S > >
 
struct  ShapeIntersectIndepImpl< S, Plane< S >, Plane< S > >
 
struct  ShapeIntersectLibccdImpl
 
struct  ShapeIntersectLibccdImpl< S, Halfspace< S >, Halfspace< S > >
 
struct  ShapeIntersectLibccdImpl< S, Halfspace< S >, Plane< S > >
 
struct  ShapeIntersectLibccdImpl< S, Plane< S >, Halfspace< S > >
 
struct  ShapeIntersectLibccdImpl< S, Plane< S >, Plane< S > >
 
class  ShapeMeshCollisionTraversalNode
 Traversal node for collision between shape and mesh. More...
 
class  ShapeMeshCollisionTraversalNodekIOS
 
class  ShapeMeshCollisionTraversalNodeOBB
 Traversal node for shape and mesh, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS) More...
 
class  ShapeMeshCollisionTraversalNodeOBBRSS
 
class  ShapeMeshCollisionTraversalNodeRSS
 
class  ShapeMeshConservativeAdvancementTraversalNode
 
class  ShapeMeshConservativeAdvancementTraversalNodeOBBRSS
 
class  ShapeMeshConservativeAdvancementTraversalNodeRSS
 
class  ShapeMeshDistanceTraversalNode
 Traversal node for distance between shape and mesh. More...
 
class  ShapeMeshDistanceTraversalNodekIOS
 
class  ShapeMeshDistanceTraversalNodeOBBRSS
 
class  ShapeMeshDistanceTraversalNodeRSS
 
class  ShapeOcTreeCollisionTraversalNode
 Traversal node for shape-octree collision. More...
 
class  ShapeOcTreeDistanceTraversalNode
 Traversal node for shape-octree distance. More...
 
struct  ShapeSignedDistanceLibccdImpl
 
struct  ShapeTransformedTriangleDistanceIndepImpl
 
struct  ShapeTransformedTriangleDistanceIndepImpl< S, Sphere< S > >
 
struct  ShapeTransformedTriangleDistanceLibccdImpl
 
struct  ShapeTransformedTriangleDistanceLibccdImpl< S, Sphere< S > >
 
struct  ShapeTransformedTriangleIntersectIndepImpl
 
struct  ShapeTransformedTriangleIntersectIndepImpl< S, Halfspace< S > >
 
struct  ShapeTransformedTriangleIntersectIndepImpl< S, Plane< S > >
 
struct  ShapeTransformedTriangleIntersectIndepImpl< S, Sphere< S > >
 
struct  ShapeTransformedTriangleIntersectLibccdImpl
 
struct  ShapeTransformedTriangleIntersectLibccdImpl< S, Halfspace< S > >
 
struct  ShapeTransformedTriangleIntersectLibccdImpl< S, Plane< S > >
 
struct  ShapeTransformedTriangleIntersectLibccdImpl< S, Sphere< S > >
 
struct  ShapeTriangleDistanceIndepImpl
 
struct  ShapeTriangleDistanceIndepImpl< S, Sphere< S > >
 
struct  ShapeTriangleDistanceLibccdImpl
 
struct  ShapeTriangleDistanceLibccdImpl< S, Sphere< S > >
 
struct  ShapeTriangleIntersectIndepImpl
 
struct  ShapeTriangleIntersectIndepImpl< S, Sphere< S > >
 
struct  ShapeTriangleIntersectLibccdImpl
 
struct  ShapeTriangleIntersectLibccdImpl< S, Sphere< S > >
 
class  SimpleHashTable
 A simple hash table implemented as multiple buckets. HashFnc is any extended hash function: HashFnc(key) = {index1, index2, ..., }. More...
 
struct  SimpleInterval
 Interval trees implemented using red-black-trees as described in the book Introduction_To_Algorithms_ by Cormen, Leisserson, and Rivest. More...
 
struct  SortDoubleByValue
 
struct  SortIntByValue
 
class  SparseHashTable
 A hash table implemented using unordered_map. More...
 
struct  SpatialHash
 Spatial hash function: hash an AABB to a set of integer values. More...
 
struct  SphereSpecification
 
class  Tetrahedron
 
class  TraversalNodeBase
 Node structure encoding the information required for traversal. More...
 
class  TriangleDistance
 Triangle distance functions. More...
 
class  unordered_map_hash_table
 
struct  UpdateImpl
 

Typedefs

using BVHFrontList = std::list< BVHFrontNode >
 BVH front list is a list of front nodes. More...
 
using CollisionTraversalNodeBased = CollisionTraversalNodeBase< double >
 
using CollisionTraversalNodeBasef = CollisionTraversalNodeBase< float >
 
using DistanceFn = std::function< ccd_real_t(const void *, const void *, const ccd_t *, ccd_vec3_t *, ccd_vec3_t *)>
 
using EPAd = EPA< double >
 
using EPAf = EPA< float >
 
using GJKCenterFunction = void(*)(const void *obj, ccd_vec3_t *c)
 
using GJKd = GJK< double >
 
using GJKf = GJK< float >
 
using GJKSolver_indepd = GJKSolver_indep< double >
 
using GJKSolver_indepf = GJKSolver_indep< float >
 
using GJKSolver_libccdd = GJKSolver_libccd< double >
 
using GJKSolver_libccdf = GJKSolver_libccd< float >
 
using GJKSupportFunction = void(*)(const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v)
 callback function used by GJK algorithm More...
 
using Intersectd = Intersect< double >
 
using Intersectf = Intersect< float >
 
using IntervalTreed = IntervalTree< double >
 
using IntervalTreef = IntervalTree< float >
 
using IntervalTreeNoded = IntervalTreeNode< double >
 
using IntervalTreeNodef = IntervalTreeNode< float >
 
using it_recursion_noded = it_recursion_node< double >
 
using it_recursion_nodef = it_recursion_node< float >
 
using MeshCollisionTraversalNodekIOSd = MeshCollisionTraversalNodekIOS< double >
 
using MeshCollisionTraversalNodekIOSf = MeshCollisionTraversalNodekIOS< float >
 
using MeshCollisionTraversalNodeOBBd = MeshCollisionTraversalNodeOBB< double >
 
using MeshCollisionTraversalNodeOBBf = MeshCollisionTraversalNodeOBB< float >
 
using MeshCollisionTraversalNodeOBBRSSd = MeshCollisionTraversalNodeOBBRSS< double >
 
using MeshCollisionTraversalNodeOBBRSSf = MeshCollisionTraversalNodeOBBRSS< float >
 
using MeshCollisionTraversalNodeRSSd = MeshCollisionTraversalNodeRSS< double >
 
using MeshCollisionTraversalNodeRSSf = MeshCollisionTraversalNodeRSS< float >
 
using MeshConservativeAdvancementTraversalNodeOBBRSSd = MeshConservativeAdvancementTraversalNodeOBBRSS< double >
 
using MeshConservativeAdvancementTraversalNodeOBBRSSf = MeshConservativeAdvancementTraversalNodeOBBRSS< float >
 
using MeshConservativeAdvancementTraversalNodeRSSd = MeshConservativeAdvancementTraversalNodeRSS< double >
 
using MeshConservativeAdvancementTraversalNodeRSSf = MeshConservativeAdvancementTraversalNodeRSS< float >
 
using MeshDistanceTraversalNodekIOSd = MeshDistanceTraversalNodekIOS< double >
 
using MeshDistanceTraversalNodekIOSf = MeshDistanceTraversalNodekIOS< float >
 
using MeshDistanceTraversalNodeOBBRSSd = MeshDistanceTraversalNodeOBBRSS< double >
 
using MeshDistanceTraversalNodeOBBRSSf = MeshDistanceTraversalNodeOBBRSS< float >
 
using MeshDistanceTraversalNodeRSSd = MeshDistanceTraversalNodeRSS< double >
 
using MeshDistanceTraversalNodeRSSf = MeshDistanceTraversalNodeRSS< float >
 
using MinkowskiDiffd = MinkowskiDiff< double >
 
using MinkowskiDifff = MinkowskiDiff< float >
 
using PolySolverd = PolySolver< double >
 
using PolySolverf = PolySolver< float >
 
using Projectd = Project< double >
 
using Projectf = Project< float >
 
using SimpleIntervald = SimpleInterval< double >
 
using SimpleIntervalf = SimpleInterval< float >
 
using SpatialHashd = SpatialHash< double >
 
using SpatialHashf = SpatialHash< float >
 
using TriangleDistanced = TriangleDistance< double >
 
using TriangleDistancef = TriangleDistance< float >
 
using Vector3d = Vector3< double >
 

Enumerations

enum  SplitMethodType { SPLIT_METHOD_MEAN, SPLIT_METHOD_MEDIAN, SPLIT_METHOD_BV_CENTER }
 Three types of split algorithms are provided in FCL as default. More...
 

Functions

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 >
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 >
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 >
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 > &center, 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 &center, 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 > &center, 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 &center, 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 >
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 >
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 >
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)
 

Variables

template class FCL_EXPORT CollisionTraversalNodeBase< double >
 
template class FCL_EXPORT ConvertBVImpl< double, AABB< double >, AABB< double > >
 
template class FCL_EXPORT ConvertBVImpl< double, AABB< double >, OBB< double > >
 
template class FCL_EXPORT ConvertBVImpl< double, AABB< double >, RSS< double > >
 
template class FCL_EXPORT ConvertBVImpl< double, OBB< double >, OBB< double > >
 
template class FCL_EXPORT ConvertBVImpl< double, OBB< double >, RSS< double > >
 
template class FCL_EXPORT ConvertBVImpl< double, OBBRSS< double >, OBB< double > >
 
template class FCL_EXPORT ConvertBVImpl< double, OBBRSS< double >, RSS< double > >
 
template class FCL_EXPORT ConvertBVImpl< double, RSS< double >, OBB< double > >
 
template class FCL_EXPORT ConvertBVImpl< double, RSS< double >, RSS< double > >
 
template class FCL_EXPORT DistanceTraversalNodeBase< double >
 
template class FCL_EXPORT GJKInitializer< double, Box< double > >
 
template class FCL_EXPORT GJKInitializer< double, Capsule< double > >
 
template class FCL_EXPORT GJKInitializer< double, Cone< double > >
 
template class FCL_EXPORT GJKInitializer< double, Convex< double > >
 
template class FCL_EXPORT GJKInitializer< double, Cylinder< double > >
 
template class FCL_EXPORT GJKInitializer< double, Ellipsoid< double > >
 
template class FCL_EXPORT GJKInitializer< double, Sphere< double > >
 
template class FCL_EXPORT Intersect< double >
 
template<typename S >
class FCL_EXPORT IntervalTree
 
template class FCL_EXPORT IntervalTreeNode< double >
 
template class FCL_EXPORT MeshCollisionTraversalNodekIOS< double >
 
template class FCL_EXPORT MeshCollisionTraversalNodeOBB< double >
 
template class FCL_EXPORT MeshCollisionTraversalNodeOBBRSS< double >
 
template class FCL_EXPORT MeshCollisionTraversalNodeRSS< double >
 
template class FCL_EXPORT MeshConservativeAdvancementTraversalNodeOBBRSS< double >
 
template class FCL_EXPORT MeshConservativeAdvancementTraversalNodeRSS< double >
 
template class FCL_EXPORT MeshDistanceTraversalNodekIOS< double >
 
template class FCL_EXPORT MeshDistanceTraversalNodeOBBRSS< double >
 
template class FCL_EXPORT MeshDistanceTraversalNodeRSS< double >
 
template class FCL_EXPORT PolySolver< double >
 
template class FCL_EXPORT Project< double >
 
template class FCL_EXPORT TraversalNodeBase< double >
 
template class FCL_EXPORT TriangleDistance< double >
 

Typedef Documentation

◆ BVHFrontList

using fcl::detail::BVHFrontList = typedef std::list<BVHFrontNode>

BVH front list is a list of front nodes.

Definition at line 69 of file BVH_front.h.

◆ CollisionTraversalNodeBased

Definition at line 82 of file collision_traversal_node_base.h.

◆ CollisionTraversalNodeBasef

Definition at line 81 of file collision_traversal_node_base.h.

◆ DistanceFn

using fcl::detail::DistanceFn = typedef std::function<ccd_real_t ( const void*, const void*, const ccd_t*, ccd_vec3_t*, ccd_vec3_t*)>

Definition at line 2622 of file gjk_libccd-inl.h.

◆ EPAd

using fcl::detail::EPAd = typedef EPA<double>

Definition at line 138 of file epa.h.

◆ EPAf

using fcl::detail::EPAf = typedef EPA<float>

Definition at line 137 of file epa.h.

◆ GJKCenterFunction

using fcl::detail::GJKCenterFunction = typedef void (*)(const void* obj, ccd_vec3_t* c)

Definition at line 72 of file gjk_libccd.h.

◆ GJKd

using fcl::detail::GJKd = typedef GJK<double>

Definition at line 123 of file gjk.h.

◆ GJKf

using fcl::detail::GJKf = typedef GJK<float>

Definition at line 122 of file gjk.h.

◆ GJKSolver_indepd

Definition at line 201 of file gjk_solver_indep.h.

◆ GJKSolver_indepf

Definition at line 200 of file gjk_solver_indep.h.

◆ GJKSolver_libccdd

Definition at line 187 of file gjk_solver_libccd.h.

◆ GJKSolver_libccdf

Definition at line 186 of file gjk_solver_libccd.h.

◆ GJKSupportFunction

using fcl::detail::GJKSupportFunction = typedef void (*)(const void* obj, const ccd_vec3_t* dir_, ccd_vec3_t* v)

callback function used by GJK algorithm

Definition at line 71 of file gjk_libccd.h.

◆ Intersectd

using fcl::detail::Intersectd = typedef Intersect<double>

Definition at line 258 of file intersect.h.

◆ Intersectf

using fcl::detail::Intersectf = typedef Intersect<float>

Definition at line 257 of file intersect.h.

◆ IntervalTreed

using fcl::detail::IntervalTreed = typedef IntervalTree<double>

Definition at line 135 of file interval_tree.h.

◆ IntervalTreef

using fcl::detail::IntervalTreef = typedef IntervalTree<float>

Definition at line 134 of file interval_tree.h.

◆ IntervalTreeNoded

Definition at line 96 of file interval_tree_node.h.

◆ IntervalTreeNodef

Definition at line 95 of file interval_tree_node.h.

◆ it_recursion_noded

Definition at line 65 of file interval_tree.h.

◆ it_recursion_nodef

Definition at line 64 of file interval_tree.h.

◆ MeshCollisionTraversalNodekIOSd

Definition at line 197 of file mesh_collision_traversal_node.h.

◆ MeshCollisionTraversalNodekIOSf

Definition at line 196 of file mesh_collision_traversal_node.h.

◆ MeshCollisionTraversalNodeOBBd

Definition at line 123 of file mesh_collision_traversal_node.h.

◆ MeshCollisionTraversalNodeOBBf

Definition at line 122 of file mesh_collision_traversal_node.h.

◆ MeshCollisionTraversalNodeOBBRSSd

Definition at line 230 of file mesh_collision_traversal_node.h.

◆ MeshCollisionTraversalNodeOBBRSSf

Definition at line 229 of file mesh_collision_traversal_node.h.

◆ MeshCollisionTraversalNodeRSSd

Definition at line 165 of file mesh_collision_traversal_node.h.

◆ MeshCollisionTraversalNodeRSSf

Definition at line 164 of file mesh_collision_traversal_node.h.

◆ MeshConservativeAdvancementTraversalNodeOBBRSSd

◆ MeshConservativeAdvancementTraversalNodeOBBRSSf

◆ MeshConservativeAdvancementTraversalNodeRSSd

◆ MeshConservativeAdvancementTraversalNodeRSSf

◆ MeshDistanceTraversalNodekIOSd

Definition at line 162 of file mesh_distance_traversal_node.h.

◆ MeshDistanceTraversalNodekIOSf

Definition at line 161 of file mesh_distance_traversal_node.h.

◆ MeshDistanceTraversalNodeOBBRSSd

Definition at line 203 of file mesh_distance_traversal_node.h.

◆ MeshDistanceTraversalNodeOBBRSSf

Definition at line 202 of file mesh_distance_traversal_node.h.

◆ MeshDistanceTraversalNodeRSSd

Definition at line 121 of file mesh_distance_traversal_node.h.

◆ MeshDistanceTraversalNodeRSSf

Definition at line 120 of file mesh_distance_traversal_node.h.

◆ MinkowskiDiffd

using fcl::detail::MinkowskiDiffd = typedef MinkowskiDiff<double>

Definition at line 96 of file minkowski_diff.h.

◆ MinkowskiDifff

Definition at line 95 of file minkowski_diff.h.

◆ PolySolverd

using fcl::detail::PolySolverd = typedef PolySolver<double>

Definition at line 73 of file polysolver.h.

◆ PolySolverf

using fcl::detail::PolySolverf = typedef PolySolver<float>

Definition at line 72 of file polysolver.h.

◆ Projectd

using fcl::detail::Projectd = typedef Project<double>

Definition at line 89 of file project.h.

◆ Projectf

using fcl::detail::Projectf = typedef Project<float>

Definition at line 88 of file project.h.

◆ SimpleIntervald

Definition at line 64 of file simple_interval.h.

◆ SimpleIntervalf

Definition at line 63 of file simple_interval.h.

◆ SpatialHashd

using fcl::detail::SpatialHashd = typedef SpatialHash<double>

Definition at line 67 of file spatial_hash.h.

◆ SpatialHashf

using fcl::detail::SpatialHashf = typedef SpatialHash<float>

Definition at line 66 of file spatial_hash.h.

◆ TriangleDistanced

Definition at line 107 of file triangle_distance.h.

◆ TriangleDistancef

Definition at line 106 of file triangle_distance.h.

◆ Vector3d

using fcl::detail::Vector3d = typedef Vector3<double>

Definition at line 47 of file test_gjk_libccd-inl_extractClosestPoints.cpp.

Enumeration Type Documentation

◆ SplitMethodType

Three types of split algorithms are provided in FCL as default.

Enumerator
SPLIT_METHOD_MEAN 
SPLIT_METHOD_MEDIAN 
SPLIT_METHOD_BV_CENTER 

Definition at line 56 of file BV_splitter.h.

Function Documentation

◆ are_coincident()

bool fcl::detail::are_coincident ( const Vector3d p,
const Vector3d q 
)

◆ are_same()

::testing::AssertionResult fcl::detail::are_same ( const Vector3d expected,
const ccd_vec3_t &  tested,
double  tolerance 
)

Definition at line 68 of file test_gjk_libccd-inl_extractClosestPoints.cpp.

◆ boxBox2() [1/5]

template int fcl::detail::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 
)

◆ boxBox2() [2/5]

template<typename S , typename DerivedA , typename DerivedB >
FCL_EXPORT int fcl::detail::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 
)

Definition at line 248 of file box_box-inl.h.

◆ boxBox2() [3/5]

template<typename S , typename DerivedA , typename DerivedB >
int fcl::detail::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 
)

Definition at line 248 of file box_box-inl.h.

◆ boxBox2() [4/5]

template<typename S >
FCL_EXPORT int fcl::detail::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 
)

Definition at line 840 of file box_box-inl.h.

◆ boxBox2() [5/5]

template<typename S >
int fcl::detail::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 
)

Definition at line 840 of file box_box-inl.h.

◆ boxBoxIntersect() [1/3]

template bool fcl::detail::boxBoxIntersect ( const Box< double > &  s1,
const Transform3< double > &  tf1,
const Box< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts_ 
)

◆ boxBoxIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::boxBoxIntersect ( const Box< S > &  s1,
const Transform3< S > &  tf1,
const Box< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts_ 
)

Definition at line 857 of file box_box-inl.h.

◆ boxBoxIntersect() [3/3]

template<typename S >
bool fcl::detail::boxBoxIntersect ( const Box< S > &  s1,
const Transform3< S > &  tf1,
const Box< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts_ 
)

Definition at line 857 of file box_box-inl.h.

◆ boxHalfspaceIntersect() [1/6]

template bool fcl::detail::boxHalfspaceIntersect ( const Box< double > &  s1,
const Transform3< double > &  tf1,
const Halfspace< double > &  s2,
const Transform3< double > &  tf2 
)

◆ boxHalfspaceIntersect() [2/6]

template bool fcl::detail::boxHalfspaceIntersect ( const Box< double > &  s1,
const Transform3< double > &  tf1,
const Halfspace< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ boxHalfspaceIntersect() [3/6]

template<typename S >
FCL_EXPORT bool fcl::detail::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

Definition at line 226 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ boxHalfspaceIntersect() [4/6]

template<typename S >
bool fcl::detail::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

Definition at line 226 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ boxHalfspaceIntersect() [5/6]

template<typename S >
FCL_EXPORT bool fcl::detail::boxHalfspaceIntersect ( const Box< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

find deepest point

compute the contact point from the deepest point

Definition at line 244 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ boxHalfspaceIntersect() [6/6]

template<typename S >
bool fcl::detail::boxHalfspaceIntersect ( const Box< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

find deepest point

compute the contact point from the deepest point

Definition at line 244 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ boxPlaneIntersect() [1/3]

template bool fcl::detail::boxPlaneIntersect ( const Box< double > &  s1,
const Transform3< double > &  tf1,
const Plane< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ boxPlaneIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

Definition at line 197 of file narrowphase/detail/primitive_shape_algorithm/plane-inl.h.

◆ boxPlaneIntersect() [3/3]

template<typename S >
bool fcl::detail::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.

Definition at line 197 of file narrowphase/detail/primitive_shape_algorithm/plane-inl.h.

◆ boxToGJK()

template<typename S >
static void fcl::detail::boxToGJK ( const Box< S > &  s,
const Transform3< S > &  tf,
ccd_box_t box 
)
static

Definition at line 2278 of file gjk_libccd-inl.h.

◆ BVHCollide() [1/2]

template<typename BV >
std::size_t fcl::detail::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 
)

Definition at line 558 of file collision_func_matrix-inl.h.

◆ BVHCollide() [2/2]

template<typename BV , typename NarrowPhaseSolver >
std::size_t fcl::detail::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 
)

Definition at line 648 of file collision_func_matrix-inl.h.

◆ BVHConservativeAdvancement()

template<typename BV , typename NarrowPhaseSolver >
BV::S fcl::detail::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 
)

Definition at line 693 of file conservative_advancement_func_matrix-inl.h.

◆ BVHDistance() [1/2]

template<typename BV >
BV::S fcl::detail::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 
)

Definition at line 374 of file distance_func_matrix-inl.h.

◆ BVHDistance() [2/2]

template<typename BV , typename NarrowPhaseSolver >
BV::S fcl::detail::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 
)

Definition at line 462 of file distance_func_matrix-inl.h.

◆ BVHShapeConservativeAdvancement()

template<typename BV , typename Shape , typename NarrowPhaseSolver >
BV::S fcl::detail::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 
)

Definition at line 758 of file conservative_advancement_func_matrix-inl.h.

◆ capsuleCapsuleDistance() [1/3]

template bool fcl::detail::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 
)

◆ capsuleCapsuleDistance() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

Computes the signed distance between two capsules s1 and s2 (with given poses X_FC1 and X_FC2 of the two capsules in a common frame F). Further reports the witness points to that distance (p_FW1 and p_FW2).

It is guaranteed that |p_FW1 - p_FW2| = |dist|.

There are degenerate cases where there is no unique pair of witness points. If the center lines of the two capsules intersect (either once or multiple times when the are co-linear) then distance will still be reported (a negative value with the maximum magnitude possible between the two capsules) and an arbitrary pair of witness points from the set of valid pairs.

Parameters
s1The first capsule.
X_FC1The pose of the first capsule in a common frame F.
s2The second capsule.
X_FC2The pose of the second capsule in a common frame F.
distThe signed distance between the two capsules (negative indicates intersection).
p_FW1The first witness point: a point on the surface of the first capsule measured and expressed in the common frame F.
p_FW2The second witness point: a point on the surface of the second capsule measured and expressed in the common frame F.
Returns
true.
Template Parameters
SThe scalar type for computation.

Definition at line 160 of file capsule_capsule-inl.h.

◆ capsuleCapsuleDistance() [3/3]

template<typename S >
bool fcl::detail::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 
)

Computes the signed distance between two capsules s1 and s2 (with given poses X_FC1 and X_FC2 of the two capsules in a common frame F). Further reports the witness points to that distance (p_FW1 and p_FW2).

It is guaranteed that |p_FW1 - p_FW2| = |dist|.

There are degenerate cases where there is no unique pair of witness points. If the center lines of the two capsules intersect (either once or multiple times when the are co-linear) then distance will still be reported (a negative value with the maximum magnitude possible between the two capsules) and an arbitrary pair of witness points from the set of valid pairs.

Parameters
s1The first capsule.
X_FC1The pose of the first capsule in a common frame F.
s2The second capsule.
X_FC2The pose of the second capsule in a common frame F.
distThe signed distance between the two capsules (negative indicates intersection).
p_FW1The first witness point: a point on the surface of the first capsule measured and expressed in the common frame F.
p_FW2The second witness point: a point on the surface of the second capsule measured and expressed in the common frame F.
Returns
true.
Template Parameters
SThe scalar type for computation.

Definition at line 160 of file capsule_capsule-inl.h.

◆ capsuleHalfspaceIntersect() [1/3]

template bool fcl::detail::capsuleHalfspaceIntersect ( const Capsule< double > &  s1,
const Transform3< double > &  tf1,
const Halfspace< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ capsuleHalfspaceIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::capsuleHalfspaceIntersect ( const Capsule< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ capsuleHalfspaceIntersect() [3/3]

template<typename S >
bool fcl::detail::capsuleHalfspaceIntersect ( const Capsule< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ capsulePlaneIntersect() [1/6]

template bool fcl::detail::capsulePlaneIntersect ( const Capsule< double > &  s1,
const Transform3< double > &  tf1,
const Plane< double > &  s2,
const Transform3< double > &  tf2 
)

◆ capsulePlaneIntersect() [2/6]

template bool fcl::detail::capsulePlaneIntersect ( const Capsule< double > &  s1,
const Transform3< double > &  tf1,
const Plane< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ capsulePlaneIntersect() [3/6]

template<typename S >
FCL_EXPORT bool fcl::detail::capsulePlaneIntersect ( const Capsule< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2 
)

◆ capsulePlaneIntersect() [4/6]

template<typename S >
bool fcl::detail::capsulePlaneIntersect ( const Capsule< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2 
)

◆ capsulePlaneIntersect() [5/6]

template<typename S >
FCL_EXPORT bool fcl::detail::capsulePlaneIntersect ( const Capsule< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ capsulePlaneIntersect() [6/6]

template<typename S >
bool fcl::detail::capsulePlaneIntersect ( const Capsule< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ capToGJK()

template<typename S >
static void fcl::detail::capToGJK ( const Capsule< S > &  s,
const Transform3< S > &  tf,
ccd_cap_t cap 
)
static

Definition at line 2287 of file gjk_libccd-inl.h.

◆ ccd_to_eigen()

Vector3d fcl::detail::ccd_to_eigen ( const ccd_vec3_t &  vector)

Definition at line 60 of file test_gjk_libccd-inl_extractClosestPoints.cpp.

◆ centerConvex()

template<typename S >
static void fcl::detail::centerConvex ( const void *  obj,
ccd_vec3_t *  c 
)
static

Definition at line 2557 of file gjk_libccd-inl.h.

◆ centerShape()

static void fcl::detail::centerShape ( const void *  obj,
ccd_vec3_t *  c 
)
inlinestatic

Definition at line 2550 of file gjk_libccd-inl.h.

◆ centerTriangle()

static void fcl::detail::centerTriangle ( const void *  obj,
ccd_vec3_t *  c 
)
static

Definition at line 2566 of file gjk_libccd-inl.h.

◆ CheckComputeVisiblePatch()

void fcl::detail::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 
)

Definition at line 613 of file test_gjk_libccd-inl_epa.cpp.

◆ CheckComputeVisiblePatchColinearNewVertex()

void fcl::detail::CheckComputeVisiblePatchColinearNewVertex ( EquilateralTetrahedron tet,
double  rho 
)

Definition at line 712 of file test_gjk_libccd-inl_epa.cpp.

◆ CheckComputeVisiblePatchCommon()

void fcl::detail::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 
)

Definition at line 558 of file test_gjk_libccd-inl_epa.cpp.

◆ CheckComputeVisiblePatchRecursive()

void fcl::detail::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 
)

Definition at line 586 of file test_gjk_libccd-inl_epa.cpp.

◆ CheckTetrahedronFaceNormal()

void fcl::detail::CheckTetrahedronFaceNormal ( const Tetrahedron p)

Definition at line 193 of file test_gjk_libccd-inl_epa.cpp.

◆ clamp() [1/3]

template double fcl::detail::clamp ( double  n,
double  min,
double  max 
)

◆ clamp() [2/3]

template<typename S >
FCL_EXPORT S fcl::detail::clamp ( n,
min,
max 
)

Definition at line 70 of file capsule_capsule-inl.h.

◆ clamp() [3/3]

template<typename S >
S fcl::detail::clamp ( n,
min,
max 
)

Definition at line 70 of file capsule_capsule-inl.h.

◆ closestPtSegmentSegment() [1/3]

template<typename S >
FCL_EXPORT S fcl::detail::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 
)

Computes the pair of closest points (p_FC1, p_FC2) between two line segments given by point pairs (p_FP1, p_FQ1) and (p_FP2, p_FQ2)`. If the lines are parallel, there may be no unique such point pair, in that case it computes one from the set of nearest pairs. As a by-product, it reports the squared distance between those points and the parameters (s and t) such that p_FC1 = p_FP1 + s * (p_FQ1 - p_FP1) for segment one, and similarly for p_FC2 and t, with 0 ≤ s,t ≤ 1. All points are measured and expressed in a common frame F.

Parameters
p_FP1Segment 1's first point, P1.
p_FQ1Segment 1's second point, Q1.
p_FP2Segment 2's first point, P2.
p_FQ2Segment 2's second point, Q2.
sThe parameter relating C1 with P1 and Q1.
tThe parameter relating C2 with P2 and Q2.
p_FC1The point C1 on segment 1, nearest segment 2.
p_FC2The point C2 on segment 2, nearest segment 1.
Returns
The squared distance between points C1 and C2.
Template Parameters
SThe scalar type for computation.

Definition at line 79 of file capsule_capsule-inl.h.

◆ closestPtSegmentSegment() [2/3]

template<typename S >
S fcl::detail::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 
)

Computes the pair of closest points (p_FC1, p_FC2) between two line segments given by point pairs (p_FP1, p_FQ1) and (p_FP2, p_FQ2)`. If the lines are parallel, there may be no unique such point pair, in that case it computes one from the set of nearest pairs. As a by-product, it reports the squared distance between those points and the parameters (s and t) such that p_FC1 = p_FP1 + s * (p_FQ1 - p_FP1) for segment one, and similarly for p_FC2 and t, with 0 ≤ s,t ≤ 1. All points are measured and expressed in a common frame F.

Parameters
p_FP1Segment 1's first point, P1.
p_FQ1Segment 1's second point, Q1.
p_FP2Segment 2's first point, P2.
p_FQ2Segment 2's second point, Q2.
sThe parameter relating C1 with P1 and Q1.
tThe parameter relating C2 with P2 and Q2.
p_FC1The point C1 on segment 1, nearest segment 2.
p_FC2The point C2 on segment 2, nearest segment 1.
Returns
The squared distance between points C1 and C2.
Template Parameters
SThe scalar type for computation.

Definition at line 79 of file capsule_capsule-inl.h.

◆ closestPtSegmentSegment() [3/3]

template double fcl::detail::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 
)

◆ collide() [1/3]

template void fcl::detail::collide ( CollisionTraversalNodeBase< double > *  node,
BVHFrontList front_list 
)

◆ collide() [2/3]

template<typename S >
void fcl::detail::collide ( CollisionTraversalNodeBase< S > *  node,
BVHFrontList front_list 
)

collision on collision traversal node; can use front list to accelerate

Definition at line 72 of file collision_node-inl.h.

◆ collide() [3/3]

template<typename S >
FCL_EXPORT void fcl::detail::collide ( CollisionTraversalNodeBase< S > *  node,
BVHFrontList front_list = nullptr 
)

collision on collision traversal node; can use front list to accelerate

Definition at line 72 of file collision_node-inl.h.

◆ collide2() [1/6]

template void fcl::detail::collide2 ( MeshCollisionTraversalNodeOBB< double > *  node,
BVHFrontList front_list 
)

◆ collide2() [2/6]

template<typename S >
void fcl::detail::collide2 ( MeshCollisionTraversalNodeOBB< S > *  node,
BVHFrontList front_list 
)

special collision on OBB traversal node

Definition at line 86 of file collision_node-inl.h.

◆ collide2() [3/6]

template<typename S >
FCL_EXPORT void fcl::detail::collide2 ( MeshCollisionTraversalNodeOBB< S > *  node,
BVHFrontList front_list = nullptr 
)

special collision on OBB traversal node

Definition at line 86 of file collision_node-inl.h.

◆ collide2() [4/6]

template void fcl::detail::collide2 ( MeshCollisionTraversalNodeRSS< double > *  node,
BVHFrontList front_list 
)

◆ collide2() [5/6]

template<typename S >
void fcl::detail::collide2 ( MeshCollisionTraversalNodeRSS< S > *  node,
BVHFrontList front_list 
)

special collision on RSS traversal node

Definition at line 108 of file collision_node-inl.h.

◆ collide2() [6/6]

template<typename S >
FCL_EXPORT void fcl::detail::collide2 ( MeshCollisionTraversalNodeRSS< S > *  node,
BVHFrontList front_list = nullptr 
)

special collision on RSS traversal node

Definition at line 108 of file collision_node-inl.h.

◆ collisionRecurse() [1/6]

template void fcl::detail::collisionRecurse ( CollisionTraversalNodeBase< double > *  node,
int  b1,
int  b2,
BVHFrontList front_list 
)

◆ collisionRecurse() [2/6]

template<typename S >
FCL_EXPORT void fcl::detail::collisionRecurse ( CollisionTraversalNodeBase< S > *  node,
int  b1,
int  b2,
BVHFrontList front_list 
)

Recurse function for collision.

Definition at line 84 of file traversal_recurse-inl.h.

◆ collisionRecurse() [3/6]

template void fcl::detail::collisionRecurse ( MeshCollisionTraversalNodeOBB< double > *  node,
int  b1,
int  b2,
const Matrix3< double > &  R,
const Vector3< double > &  T,
BVHFrontList front_list 
)

◆ collisionRecurse() [4/6]

template<typename S >
FCL_EXPORT void fcl::detail::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.

Definition at line 134 of file traversal_recurse-inl.h.

◆ collisionRecurse() [5/6]

template void fcl::detail::collisionRecurse ( MeshCollisionTraversalNodeRSS< double > *  node,
int  b1,
int  b2,
const Matrix3< double > &  R,
const Vector3< double > &  T,
BVHFrontList front_list 
)

◆ collisionRecurse() [6/6]

template<typename S >
FCL_EXPORT void fcl::detail::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.

Definition at line 220 of file traversal_recurse-inl.h.

◆ CompareCcdVec3()

void fcl::detail::CompareCcdVec3 ( const ccd_vec3_t &  v,
const ccd_vec3_t &  v_expected,
ccd_real_t  tol 
)

Definition at line 1208 of file test_gjk_libccd-inl_epa.cpp.

◆ ComparePolytope()

void fcl::detail::ComparePolytope ( const ccd_pt_t polytope1,
const ccd_pt_t polytope2,
ccd_real_t  tol 
)

Definition at line 921 of file test_gjk_libccd-inl_epa.cpp.

◆ ComputeSphereSphereDistance()

template<typename S >
S fcl::detail::ComputeSphereSphereDistance ( radius1,
radius2,
const Vector3< S > &  p_F1,
const Vector3< S > &  p_F2 
)

Definition at line 57 of file test_gjk_libccd-inl_signed_distance.cpp.

◆ computeSplitValue_bvcenter()

template<typename S , typename BV >
void fcl::detail::computeSplitValue_bvcenter ( const BV &  bv,
S &  split_value 
)

Definition at line 550 of file BV_splitter-inl.h.

◆ computeSplitValue_mean()

template<typename S , typename BV >
void fcl::detail::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 
)

Definition at line 558 of file BV_splitter-inl.h.

◆ computeSplitValue_median()

template<typename S , typename BV >
void fcl::detail::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 
)

Definition at line 603 of file BV_splitter-inl.h.

◆ computeSplitVector()

template<typename S , typename BV >
void fcl::detail::computeSplitVector ( const BV &  bv,
Vector3< S > &  split_vector 
)

Definition at line 523 of file BV_splitter-inl.h.

◆ coneHalfspaceIntersect() [1/3]

template bool fcl::detail::coneHalfspaceIntersect ( const Cone< double > &  s1,
const Transform3< double > &  tf1,
const Halfspace< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ coneHalfspaceIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::coneHalfspaceIntersect ( const Cone< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ coneHalfspaceIntersect() [3/3]

template<typename S >
bool fcl::detail::coneHalfspaceIntersect ( const Cone< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ conePlaneIntersect() [1/3]

template bool fcl::detail::conePlaneIntersect ( const Cone< double > &  s1,
const Transform3< double > &  tf1,
const Plane< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ conePlaneIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::conePlaneIntersect ( const Cone< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ conePlaneIntersect() [3/3]

template<typename S >
bool fcl::detail::conePlaneIntersect ( const Cone< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ coneToGJK()

template<typename S >
static void fcl::detail::coneToGJK ( const Cone< S > &  s,
const Transform3< S > &  tf,
ccd_cone_t cone 
)
static

Definition at line 2305 of file gjk_libccd-inl.h.

◆ conservativeAdvancement() [1/8]

template<typename BV >
bool fcl::detail::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 
)

Definition at line 75 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancement() [2/8]

template<typename BV , typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

Definition at line 291 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancement() [3/8]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

Definition at line 444 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancement() [4/8]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

Definition at line 429 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancement() [5/8]

template<typename Shape , typename BV , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

Definition at line 459 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancement() [6/8]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

Definition at line 642 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancement() [7/8]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

Definition at line 627 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancement() [8/8]

template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

Definition at line 222 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancementMeshOriented()

template<typename BV , typename ConservativeAdvancementOrientedNode >
bool fcl::detail::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 
)

Definition at line 150 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancementMeshShapeOriented()

template<typename BV , typename Shape , typename NarrowPhaseSolver , typename ConservativeAdvancementOrientedNode >
bool fcl::detail::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 
)

Definition at line 361 of file conservative_advancement_func_matrix-inl.h.

◆ conservativeAdvancementShapeMeshOriented()

template<typename Shape , typename BV , typename NarrowPhaseSolver , typename ConservativeAdvancementOrientedNode >
bool fcl::detail::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 
)

Definition at line 529 of file conservative_advancement_func_matrix-inl.h.

◆ continuousCollideBVHPolynomial()

template<typename BV >
FCL_EXPORT BV::S fcl::detail::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 
)

Definition at line 179 of file continuous_collision-inl.h.

◆ continuousCollideConservativeAdvancement()

template<typename NarrowPhaseSolver >
FCL_EXPORT NarrowPhaseSolver::S fcl::detail::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 
)

Definition at line 305 of file continuous_collision-inl.h.

◆ convexHalfspaceIntersect() [1/6]

template bool fcl::detail::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 
)

◆ convexHalfspaceIntersect() [2/6]

template bool fcl::detail::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 
)

◆ convexHalfspaceIntersect() [3/6]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

The two geometries are considered to be free of intersection if and only if all points in the Convex mesh lie strictly outside the half space. Lying on the boundary of the half space is considered intersecting.

The two geometries are each defined in their own frames, but we have transforms to a common frame F.

If the two geometries are intersecting and contacts is not nullptr, the new ContactPoint.normal will point in the opposite direction as the half space normal (expressed in Frame F) – it points into the half space. We define the point P to be a point of convex_C that most deeply penetrates into the half space. It is not guaranteed to be unique. If it is not unique, it will be arbitrarily selected from the set of all such points. The ContactPoint.penetration_depth value is the depth of P. ContactPoint.pos is defined as the point halfway between P and the nearest point on the boundary of the half space, measured and expressed in F.

ContactPoint is documented to report contact position in the world frame W. This function will only truly satisfy that requirement if F = W. It is the responsibility of the caller to understand the semantics of F and confirm that it satisfies that requirement.

This makes use of the Drake monogram notation to describe quantities (particularly the poses of shapes).

Parameters
convex_CThe convex mesh. Its vertex positions are measured and expressed in Frame C.
X_FCThe transform relating Frame C with the common frame F.
half_space_HThe half space. The position and orientation of its boundary plane are measured and expressed in Frame H.
X_FHThe transform relating Frame H with the common frame F.
[out]contactsThe optional accumulator for data characterizing the intersection.
Returns
true if the two geometries are intersecting.
Template Parameters
SThe computational scalar.

Definition at line 546 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ convexHalfspaceIntersect() [4/6]

template<typename S >
bool fcl::detail::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.

The two geometries are considered to be free of intersection if and only if all points in the Convex mesh lie strictly outside the half space. Lying on the boundary of the half space is considered intersecting.

The two geometries are each defined in their own frames, but we have transforms to a common frame F.

If the two geometries are intersecting and contacts is not nullptr, the new ContactPoint.normal will point in the opposite direction as the half space normal (expressed in Frame F) – it points into the half space. We define the point P to be a point of convex_C that most deeply penetrates into the half space. It is not guaranteed to be unique. If it is not unique, it will be arbitrarily selected from the set of all such points. The ContactPoint.penetration_depth value is the depth of P. ContactPoint.pos is defined as the point halfway between P and the nearest point on the boundary of the half space, measured and expressed in F.

ContactPoint is documented to report contact position in the world frame W. This function will only truly satisfy that requirement if F = W. It is the responsibility of the caller to understand the semantics of F and confirm that it satisfies that requirement.

This makes use of the Drake monogram notation to describe quantities (particularly the poses of shapes).

Parameters
convex_CThe convex mesh. Its vertex positions are measured and expressed in Frame C.
X_FCThe transform relating Frame C with the common frame F.
half_space_HThe half space. The position and orientation of its boundary plane are measured and expressed in Frame H.
X_FHThe transform relating Frame H with the common frame F.
[out]contactsThe optional accumulator for data characterizing the intersection.
Returns
true if the two geometries are intersecting.
Template Parameters
SThe computational scalar.

Definition at line 546 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ convexHalfspaceIntersect() [5/6]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

◆ convexHalfspaceIntersect() [6/6]

template<typename S >
bool fcl::detail::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 
)

◆ convexPlaneIntersect() [1/3]

template bool fcl::detail::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 
)

◆ convexPlaneIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

◆ convexPlaneIntersect() [3/3]

template<typename S >
bool fcl::detail::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 
)

◆ convexToGJK()

template<typename S >
static void fcl::detail::convexToGJK ( const Convex< S > &  s,
const Transform3< S > &  tf,
ccd_convex_t< S > *  conv 
)
static

Definition at line 2332 of file gjk_libccd-inl.h.

◆ cullPoints2() [1/3]

template void fcl::detail::cullPoints2 ( int  n,
double  p[],
int  m,
int  i0,
int  iret[] 
)

◆ cullPoints2() [2/3]

template<typename S >
FCL_EXPORT void fcl::detail::cullPoints2 ( int  n,
p[],
int  m,
int  i0,
int  iret[] 
)

Definition at line 173 of file box_box-inl.h.

◆ cullPoints2() [3/3]

template<typename S >
void fcl::detail::cullPoints2 ( int  n,
p[],
int  m,
int  i0,
int  iret[] 
)

Definition at line 173 of file box_box-inl.h.

◆ cylinderHalfspaceIntersect() [1/3]

template bool fcl::detail::cylinderHalfspaceIntersect ( const Cylinder< double > &  s1,
const Transform3< double > &  tf1,
const Halfspace< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ cylinderHalfspaceIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::cylinderHalfspaceIntersect ( const Cylinder< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ cylinderHalfspaceIntersect() [3/3]

template<typename S >
bool fcl::detail::cylinderHalfspaceIntersect ( const Cylinder< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ cylinderPlaneIntersect() [1/6]

template bool fcl::detail::cylinderPlaneIntersect ( const Cylinder< double > &  s1,
const Transform3< double > &  tf1,
const Plane< double > &  s2,
const Transform3< double > &  tf2 
)

◆ cylinderPlaneIntersect() [2/6]

template bool fcl::detail::cylinderPlaneIntersect ( const Cylinder< double > &  s1,
const Transform3< double > &  tf1,
const Plane< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ cylinderPlaneIntersect() [3/6]

template<typename S >
FCL_EXPORT bool fcl::detail::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

Definition at line 392 of file narrowphase/detail/primitive_shape_algorithm/plane-inl.h.

◆ cylinderPlaneIntersect() [4/6]

template<typename S >
bool fcl::detail::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

Definition at line 392 of file narrowphase/detail/primitive_shape_algorithm/plane-inl.h.

◆ cylinderPlaneIntersect() [5/6]

template<typename S >
FCL_EXPORT bool fcl::detail::cylinderPlaneIntersect ( const Cylinder< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ cylinderPlaneIntersect() [6/6]

template<typename S >
bool fcl::detail::cylinderPlaneIntersect ( const Cylinder< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ cylToGJK()

template<typename S >
static void fcl::detail::cylToGJK ( const Cylinder< S > &  s,
const Transform3< S > &  tf,
ccd_cyl_t cyl 
)
static

Definition at line 2296 of file gjk_libccd-inl.h.

◆ distance() [1/3]

template void fcl::detail::distance ( DistanceTraversalNodeBase< double > *  node,
BVHFrontList front_list,
int  qsize 
)

◆ distance() [2/3]

template<typename S >
void fcl::detail::distance ( DistanceTraversalNodeBase< S > *  node,
BVHFrontList front_list,
int  qsize 
)

distance computation on distance traversal node; can use front list to accelerate

Definition at line 137 of file collision_node-inl.h.

◆ distance() [3/3]

template<typename S >
FCL_EXPORT void fcl::detail::distance ( DistanceTraversalNodeBase< S > *  node,
BVHFrontList front_list = nullptr,
int  qsize = 2 
)

distance computation on distance traversal node; can use front list to accelerate

Definition at line 137 of file collision_node-inl.h.

◆ distancePostprocessOrientedNode() [1/2]

template<typename BV >
FCL_EXPORT void fcl::detail::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 
)

the points obtained by triDistance are not in world space: both are in object1's local coordinate system, so we need to convert them into the world space.

Definition at line 590 of file mesh_distance_traversal_node-inl.h.

◆ distancePostprocessOrientedNode() [2/2]

template<typename BV >
void fcl::detail::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 
)

the points obtained by triDistance are not in world space: both are in object1's local coordinate system, so we need to convert them into the world space.

Definition at line 590 of file mesh_distance_traversal_node-inl.h.

◆ distancePreprocessOrientedNode() [1/5]

template<typename BV >
FCL_EXPORT void fcl::detail::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 
)

Definition at line 503 of file mesh_distance_traversal_node-inl.h.

◆ distancePreprocessOrientedNode() [2/5]

template<typename BV >
void fcl::detail::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 
)

Definition at line 503 of file mesh_distance_traversal_node-inl.h.

◆ distancePreprocessOrientedNode() [3/5]

template<typename BV >
FCL_EXPORT void fcl::detail::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 
)

Definition at line 546 of file mesh_distance_traversal_node-inl.h.

◆ distancePreprocessOrientedNode() [4/5]

template<typename BV >
void fcl::detail::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 
)

Definition at line 546 of file mesh_distance_traversal_node-inl.h.

◆ distancePreprocessOrientedNode() [5/5]

template<typename BV , typename Shape , typename NarrowPhaseSolver >
void fcl::detail::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 
)

Definition at line 204 of file mesh_shape_distance_traversal_node-inl.h.

◆ distanceQueueRecurse() [1/2]

template void fcl::detail::distanceQueueRecurse ( DistanceTraversalNodeBase< double > *  node,
int  b1,
int  b2,
BVHFrontList front_list,
int  qsize 
)

◆ distanceQueueRecurse() [2/2]

template<typename S >
FCL_EXPORT void fcl::detail::distanceQueueRecurse ( DistanceTraversalNodeBase< S > *  node,
int  b1,
int  b2,
BVHFrontList front_list,
int  qsize 
)

Recurse function for distance, using queue acceleration.

Definition at line 386 of file traversal_recurse-inl.h.

◆ distanceRecurse() [1/2]

template void fcl::detail::distanceRecurse ( DistanceTraversalNodeBase< double > *  node,
int  b1,
int  b2,
BVHFrontList front_list 
)

◆ distanceRecurse() [2/2]

template<typename S >
FCL_EXPORT void fcl::detail::distanceRecurse ( DistanceTraversalNodeBase< S > *  node,
int  b1,
int  b2,
BVHFrontList front_list 
)

Recurse function for distance.

Definition at line 259 of file traversal_recurse-inl.h.

◆ EdgeMatch()

bool fcl::detail::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 
)

Definition at line 826 of file test_gjk_libccd-inl_epa.cpp.

◆ eigen_to_ccd()

ccd_vec3_t fcl::detail::eigen_to_ccd ( const Vector3d vector)

Definition at line 52 of file test_gjk_libccd-inl_extractClosestPoints.cpp.

◆ ellipsoidHalfspaceIntersect() [1/3]

template bool fcl::detail::ellipsoidHalfspaceIntersect ( const Ellipsoid< double > &  s1,
const Transform3< double > &  tf1,
const Halfspace< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ ellipsoidHalfspaceIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::ellipsoidHalfspaceIntersect ( const Ellipsoid< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ ellipsoidHalfspaceIntersect() [3/3]

template<typename S >
bool fcl::detail::ellipsoidHalfspaceIntersect ( const Ellipsoid< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ ellipsoidPlaneIntersect() [1/3]

template bool fcl::detail::ellipsoidPlaneIntersect ( const Ellipsoid< double > &  s1,
const Transform3< double > &  tf1,
const Plane< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ ellipsoidPlaneIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::ellipsoidPlaneIntersect ( const Ellipsoid< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ ellipsoidPlaneIntersect() [3/3]

template<typename S >
bool fcl::detail::ellipsoidPlaneIntersect ( const Ellipsoid< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ ellipsoidToGJK()

template<typename S >
static void fcl::detail::ellipsoidToGJK ( const Ellipsoid< S > &  s,
const Transform3< S > &  tf,
ccd_ellipsoid_t ellipsoid 
)
static

Definition at line 2322 of file gjk_libccd-inl.h.

◆ EquilateralTetrahedronVertices()

std::array<fcl::Vector3<ccd_real_t>, 4> fcl::detail::EquilateralTetrahedronVertices ( ccd_real_t  bottom_center_x,
ccd_real_t  bottom_center_y,
ccd_real_t  bottom_center_z,
ccd_real_t  edge_length 
)

Definition at line 127 of file test_gjk_libccd-inl_epa.cpp.

◆ getBVAxis() [1/2]

template<typename S , typename BV >
const FCL_EXPORT Vector3<S> fcl::detail::getBVAxis ( const BV &  bv,
int  i 
)

◆ getBVAxis() [2/2]

template<typename BV >
const Vector3<typename BV::S> fcl::detail::getBVAxis ( const BV &  bv,
int  i 
)

◆ getExtentAndCenter_mesh() [1/2]

template<typename S >
FCL_EXPORT void fcl::detail::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 > &  center,
Vector3< S > &  extent 
)

Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known.

Definition at line 294 of file geometry-inl.h.

◆ getExtentAndCenter_mesh() [2/2]

template void fcl::detail::getExtentAndCenter_mesh ( const Vector3d *const  ps,
const Vector3d *const  ps2,
Triangle ts,
unsigned int *  indices,
int  n,
const Matrix3d axis,
Vector3d center,
Vector3d extent 
)

◆ getExtentAndCenter_pointcloud() [1/2]

template<typename S >
FCL_EXPORT void fcl::detail::getExtentAndCenter_pointcloud ( const Vector3< S > *const  ps,
const Vector3< S > *const  ps2,
unsigned int *  indices,
int  n,
const Matrix3< S > &  axis,
Vector3< S > &  center,
Vector3< S > &  extent 
)

Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known.

Definition at line 229 of file geometry-inl.h.

◆ getExtentAndCenter_pointcloud() [2/2]

template void fcl::detail::getExtentAndCenter_pointcloud ( const Vector3d *const  ps,
const Vector3d *const  ps2,
unsigned int *  indices,
int  n,
const Matrix3d axis,
Vector3d center,
Vector3d extent 
)

◆ getSupport() [1/2]

template<typename S , typename Derived >
Vector3<S> fcl::detail::getSupport ( const ShapeBase< S > *  shape,
const Eigen::MatrixBase< Derived > &  dir 
)

the support function for shape

Definition at line 67 of file minkowski_diff-inl.h.

◆ getSupport() [2/2]

template<typename S , typename Derived >
FCL_EXPORT Vector3<S> fcl::detail::getSupport ( const ShapeBase< S > *  shape,
const Eigen::MatrixBase< Derived > &  dir 
)

the support function for shape

Definition at line 67 of file minkowski_diff-inl.h.

◆ GJKCollide() [1/3]

template bool fcl::detail::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 
)

◆ GJKCollide() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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,
tolerance,
Vector3< S > *  contact_points,
S *  penetration_depth,
Vector3< S > *  normal 
)

GJK collision algorithm.

libccd returns dir and pos in world space and dir is pointing from object 1 to object 2

Definition at line 2575 of file gjk_libccd-inl.h.

◆ GJKCollide() [3/3]

template<typename S >
bool fcl::detail::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,
tolerance,
Vector3< S > *  contact_points,
S *  penetration_depth,
Vector3< S > *  normal 
)

GJK collision algorithm.

libccd returns dir and pos in world space and dir is pointing from object 1 to object 2

Definition at line 2575 of file gjk_libccd-inl.h.

◆ GJKDistance() [1/3]

template bool fcl::detail::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 
)

◆ GJKDistance() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::GJKDistance ( void *  obj1,
ccd_support_fn  supp1,
void *  obj2,
ccd_support_fn  supp2,
unsigned int  max_iterations,
tolerance,
S *  dist,
Vector3< S > *  p1,
Vector3< S > *  p2 
)

Compute the distance between two objects using GJK algorithm.

Parameters
[in]obj1A convex geometric object.
[in]supp1A function to compute the support of obj1 along some direction.
[in]obj2A convex geometric object.
[in]supp2A function to compute the support of obj2 along some direction.
max_iterationsThe maximal iterations before the GJK algorithm terminates.
[in]toleranceThe tolerance used in GJK. When the change of distance is smaller than this tolerance, the algorithm terminates.
[out]distThe distance between the objects. When the two objects are not colliding, this is the actual distance, a positive number. When the two objects are colliding, it is -1.
[out]p1The closest point on object 1 in the world frame.
[out]p2The closest point on object 2 in the world frame.
Return values
is_separatedTrue if the objects are separated, false otherwise.

Definition at line 2680 of file gjk_libccd-inl.h.

◆ GJKDistance() [3/3]

template<typename S >
bool fcl::detail::GJKDistance ( void *  obj1,
ccd_support_fn  supp1,
void *  obj2,
ccd_support_fn  supp2,
unsigned int  max_iterations,
tolerance,
S *  dist,
Vector3< S > *  p1,
Vector3< S > *  p2 
)

Compute the distance between two objects using GJK algorithm.

Parameters
[in]obj1A convex geometric object.
[in]supp1A function to compute the support of obj1 along some direction.
[in]obj2A convex geometric object.
[in]supp2A function to compute the support of obj2 along some direction.
max_iterationsThe maximal iterations before the GJK algorithm terminates.
[in]toleranceThe tolerance used in GJK. When the change of distance is smaller than this tolerance, the algorithm terminates.
[out]distThe distance between the objects. When the two objects are not colliding, this is the actual distance, a positive number. When the two objects are colliding, it is -1.
[out]p1The closest point on object 1 in the world frame.
[out]p2The closest point on object 2 in the world frame.
Return values
is_separatedTrue if the objects are separated, false otherwise.

Definition at line 2680 of file gjk_libccd-inl.h.

◆ GJKDistanceImpl()

template<typename S >
bool fcl::detail::GJKDistanceImpl ( void *  obj1,
ccd_support_fn  supp1,
void *  obj2,
ccd_support_fn  supp2,
unsigned int  max_iterations,
tolerance,
detail::DistanceFn  distance_func,
S *  res,
Vector3< S > *  p1,
Vector3< S > *  p2 
)

Compute the distance between two objects using GJK algorithm.

Parameters
[in]obj1A convex geometric object.
[in]supp1A function to compute the support of obj1 along some direction.
[in]obj2A convex geometric object.
[in]supp2A function to compute the support of obj2 along some direction.
max_iterationsThe maximal iterations before the GJK algorithm terminates.
[in]toleranceThe tolerance used in GJK. When the change of distance is smaller than this tolerance, the algorithm terminates.
[in]distance_funcThe actual function that computes the distance. Different functions should be passed in, depending on whether the user wants to compute a signed distance (with penetration depth) or not.
[out]resThe distance between the objects. When the two objects are not colliding, this is the actual distance, a positive number. When the two objects are colliding, it is a negative value. The actual meaning of the negative distance is defined by distance_func.
[out]p1The closest point on object 1 in the world frame.
[out]p2The closest point on object 2 in the world frame.
Return values
is_separatedTrue if the objects are separated, false otherwise.

Definition at line 2647 of file gjk_libccd-inl.h.

◆ GJKSignedDistance() [1/3]

template bool fcl::detail::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 
)

◆ GJKSignedDistance() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::GJKSignedDistance ( void *  obj1,
ccd_support_fn  supp1,
void *  obj2,
ccd_support_fn  supp2,
unsigned int  max_iterations,
tolerance,
S *  res,
Vector3< S > *  p1,
Vector3< S > *  p2 
)

Compute the signed distance between two objects using GJK and EPA algorithm.

Parameters
[in]obj1A convex geometric object.
[in]supp1A function to compute the support of obj1 along some direction.
[in]obj2A convex geometric object.
[in]supp2A function to compute the support of obj2 along some direction.
[in]max_iterationsThe maximal iterations before the GJK algorithm terminates.
[in]toleranceThe tolerance used in GJK. When the change of distance is smaller than this tolerance, the algorithm terminates.
[out]distThe distance between the objects. When the two objects are not colliding, this is the actual distance, a positive number. When the two objects are colliding, it is the negation of the penetration depth, a negative value.
[out]p1The closest point on object 1 in the world frame.
[out]p2The closest point on object 2 in the world frame.
Return values
is_separatedTrue if the objects are separated, false otherwise.

Compute the signed distance between two mesh objects. When the objects are separating, the signed distance is > 0. When the objects are touching or penetrating, the signed distance is <= 0.

Parameters
tolerance.When the objects are separating, the GJK algorithm terminates when the change of distance between iterations is smaller than this tolerance. Note that this does NOT necessarily mean that the computed distance is within tolerance to the actual distance. On the other hand, when the objects are penetrating, the EPA algorithm terminates when the difference between the upper bound and the lower bound of the penetration depth is smaller than tolerance. Hence the computed penetration depth is within tolerance to the true depth.

Definition at line 2703 of file gjk_libccd-inl.h.

◆ GJKSignedDistance() [3/3]

template<typename S >
bool fcl::detail::GJKSignedDistance ( void *  obj1,
ccd_support_fn  supp1,
void *  obj2,
ccd_support_fn  supp2,
unsigned int  max_iterations,
tolerance,
S *  res,
Vector3< S > *  p1,
Vector3< S > *  p2 
)

Compute the signed distance between two mesh objects. When the objects are separating, the signed distance is > 0. When the objects are touching or penetrating, the signed distance is <= 0.

Parameters
tolerance.When the objects are separating, the GJK algorithm terminates when the change of distance between iterations is smaller than this tolerance. Note that this does NOT necessarily mean that the computed distance is within tolerance to the actual distance. On the other hand, when the objects are penetrating, the EPA algorithm terminates when the difference between the upper bound and the lower bound of the penetration depth is smaller than tolerance. Hence the computed penetration depth is within tolerance to the true depth.

Definition at line 2703 of file gjk_libccd-inl.h.

◆ GTEST_TEST() [1/27]

fcl::detail::GTEST_TEST ( DegenerateGeometry  ,
CoincidentPoints   
)

◆ GTEST_TEST() [2/27]

fcl::detail::GTEST_TEST ( DegenerateGeometry  ,
ZeroAreaTriangle   
)

◆ GTEST_TEST() [3/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
ComputeVisiblePatch_2FacesVisible   
)

Definition at line 680 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [4/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
ComputeVisiblePatch_4FacesVisible   
)

Definition at line 648 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [5/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
ComputeVisiblePatch_TopAndSideFacesVisible   
)

Definition at line 666 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [6/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
ComputeVisiblePatch_TopFaceVisible   
)

Definition at line 631 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [7/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
ComputeVisiblePatchColinearNewVertex   
)

Definition at line 741 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [8/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
ComputeVisiblePatchSanityCheck   
)

Definition at line 754 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [9/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
convert2SimplexToTetrahedron   
)

Definition at line 1584 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [10/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
expandPolytope_error   
)

Definition at line 1184 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [11/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
expandPolytope_hexagram_1visible_face   
)

Definition at line 1090 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [12/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
expandPolytope_hexagram_4_visible_faces   
)

Definition at line 1134 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [13/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
expandPolytope_tetrahedron1   
)

Definition at line 994 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [14/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
expandPolytope_tetrahedron_2visible_faces   
)

Definition at line 1037 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [15/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
faceNormalPointingOutward   
)

Definition at line 205 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [16/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
faceNormalPointingOutwardError   
)

Definition at line 301 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [17/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
faceNormalPointingOutwardOriginNearFace1   
)

Definition at line 246 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [18/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
faceNormalPointingOutwardOriginNearFace2   
)

Definition at line 281 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [19/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
isOutsidePolytopeFace   
)

Definition at line 397 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [20/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
isOutsidePolytopeFaceError   
)

Definition at line 435 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [21/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
penEPAPosClosest_edge   
)

Definition at line 1235 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [22/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
penEPAPosClosest_face   
)

Definition at line 1269 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [23/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
penEPAPosClosest_vertex   
)

Definition at line 1215 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [24/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
supportEPADirection   
)

Definition at line 327 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [25/27]

fcl::detail::GTEST_TEST ( FCL_GJK_EPA  ,
supportEPADirectionError   
)

Definition at line 385 of file test_gjk_libccd-inl_epa.cpp.

◆ GTEST_TEST() [26/27]

fcl::detail::GTEST_TEST ( FCL_GJKSignedDistance  ,
box_box   
)

Definition at line 445 of file test_gjk_libccd-inl_signed_distance.cpp.

◆ GTEST_TEST() [27/27]

fcl::detail::GTEST_TEST ( FCL_GJKSignedDistance  ,
sphere_sphere   
)

Definition at line 225 of file test_gjk_libccd-inl_signed_distance.cpp.

◆ halfspaceIntersect() [1/3]

template bool fcl::detail::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 
)

◆ halfspaceIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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

Definition at line 691 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ halfspaceIntersect() [3/3]

template<typename S >
bool fcl::detail::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

Definition at line 691 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ halfspaceIntersectTolerance() [1/3]

template<>
double fcl::detail::halfspaceIntersectTolerance ( )

◆ halfspaceIntersectTolerance() [2/3]

template<typename S >
FCL_EXPORT S fcl::detail::halfspaceIntersectTolerance ( )

◆ halfspaceIntersectTolerance() [3/3]

template<typename S >
S fcl::detail::halfspaceIntersectTolerance ( )

◆ halfspacePlaneIntersect() [1/3]

template bool fcl::detail::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 
)

◆ halfspacePlaneIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

◆ halfspacePlaneIntersect() [3/3]

template<typename S >
bool fcl::detail::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 
)

◆ halfspaceTriangleIntersect() [1/3]

template bool fcl::detail::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 
)

◆ halfspaceTriangleIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

◆ halfspaceTriangleIntersect() [3/3]

template<typename S >
bool fcl::detail::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 
)

◆ initialize() [1/82]

template<typename BV >
bool fcl::detail::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.

Definition at line 211 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [2/82]

template<typename BV >
FCL_EXPORT bool fcl::detail::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.

Definition at line 211 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [3/82]

template bool fcl::detail::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 
)

◆ initialize() [4/82]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

Definition at line 779 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [5/82]

template<typename S >
bool fcl::detail::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.

Definition at line 779 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [6/82]

template bool fcl::detail::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 
)

◆ initialize() [7/82]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

Definition at line 749 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [8/82]

template<typename S >
bool fcl::detail::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.

Definition at line 749 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [9/82]

template bool fcl::detail::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 
)

◆ initialize() [10/82]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

Definition at line 794 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [11/82]

template<typename S >
bool fcl::detail::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.

Definition at line 794 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [12/82]

template bool fcl::detail::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 
)

◆ initialize() [13/82]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

Definition at line 764 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [14/82]

template<typename S >
bool fcl::detail::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.

Definition at line 764 of file mesh_collision_traversal_node-inl.h.

◆ initialize() [15/82]

template<typename BV >
bool fcl::detail::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.

Definition at line 311 of file mesh_conservative_advancement_traversal_node-inl.h.

◆ initialize() [16/82]

template<typename BV >
FCL_EXPORT bool fcl::detail::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.

Definition at line 311 of file mesh_conservative_advancement_traversal_node-inl.h.

◆ initialize() [17/82]

template bool fcl::detail::initialize ( MeshConservativeAdvancementTraversalNodeOBBRSS< double > &  node,
const BVHModel< OBBRSS< double >> &  model1,
const Transform3< double > &  tf1,
const BVHModel< OBBRSS< double >> &  model2,
const Transform3< double > &  tf2,
double  w 
)

◆ initialize() [18/82]

template<typename S >
bool fcl::detail::initialize ( MeshConservativeAdvancementTraversalNodeOBBRSS< S > &  node,
const BVHModel< OBBRSS< S >> &  model1,
const Transform3< S > &  tf1,
const BVHModel< OBBRSS< S >> &  model2,
const Transform3< S > &  tf2,
w 
)

◆ initialize() [19/82]

template<typename S >
FCL_EXPORT bool fcl::detail::initialize ( MeshConservativeAdvancementTraversalNodeOBBRSS< S > &  node,
const BVHModel< OBBRSS< S >> &  model1,
const Transform3< S > &  tf1,
const BVHModel< OBBRSS< S >> &  model2,
const Transform3< S > &  tf2,
w = 1 
)

◆ initialize() [20/82]

template bool fcl::detail::initialize ( MeshConservativeAdvancementTraversalNodeRSS< double > &  node,
const BVHModel< RSS< double >> &  model1,
const Transform3< double > &  tf1,
const BVHModel< RSS< double >> &  model2,
const Transform3< double > &  tf2,
double  w 
)

◆ initialize() [21/82]

template<typename S >
bool fcl::detail::initialize ( MeshConservativeAdvancementTraversalNodeRSS< S > &  node,
const BVHModel< RSS< S >> &  model1,
const Transform3< S > &  tf1,
const BVHModel< RSS< S >> &  model2,
const Transform3< S > &  tf2,
w 
)

Initialize traversal node for conservative advancement computation between two meshes, given the current transforms, specialized for RSS.

Definition at line 777 of file mesh_conservative_advancement_traversal_node-inl.h.

◆ initialize() [22/82]

template<typename S >
FCL_EXPORT bool fcl::detail::initialize ( MeshConservativeAdvancementTraversalNodeRSS< S > &  node,
const BVHModel< RSS< S >> &  model1,
const Transform3< S > &  tf1,
const BVHModel< RSS< S >> &  model2,
const Transform3< S > &  tf2,
w = 1 
)

Initialize traversal node for conservative advancement computation between two meshes, given the current transforms, specialized for RSS.

Definition at line 777 of file mesh_conservative_advancement_traversal_node-inl.h.

◆ initialize() [23/82]

template<typename BV >
FCL_EXPORT bool fcl::detail::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.

Definition at line 183 of file mesh_continuous_collision_traversal_node-inl.h.

◆ initialize() [24/82]

template<typename BV >
bool fcl::detail::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.

Definition at line 183 of file mesh_continuous_collision_traversal_node-inl.h.

◆ initialize() [25/82]

template<typename BV >
bool fcl::detail::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.

Definition at line 157 of file mesh_distance_traversal_node-inl.h.

◆ initialize() [26/82]

template<typename BV >
FCL_EXPORT bool fcl::detail::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.

Definition at line 157 of file mesh_distance_traversal_node-inl.h.

◆ initialize() [27/82]

template bool fcl::detail::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 
)

◆ initialize() [28/82]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

Definition at line 652 of file mesh_distance_traversal_node-inl.h.

◆ initialize() [29/82]

template<typename S >
bool fcl::detail::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.

Definition at line 652 of file mesh_distance_traversal_node-inl.h.

◆ initialize() [30/82]

template bool fcl::detail::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 
)

◆ initialize() [31/82]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

Definition at line 667 of file mesh_distance_traversal_node-inl.h.

◆ initialize() [32/82]

template<typename S >
bool fcl::detail::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.

Definition at line 667 of file mesh_distance_traversal_node-inl.h.

◆ initialize() [33/82]

template bool fcl::detail::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 
)

◆ initialize() [34/82]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

Definition at line 637 of file mesh_distance_traversal_node-inl.h.

◆ initialize() [35/82]

template<typename S >
bool fcl::detail::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.

Definition at line 637 of file mesh_distance_traversal_node-inl.h.

◆ initialize() [36/82]

template<typename BV , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 79 of file mesh_octree_collision_traversal_node-inl.h.

◆ initialize() [37/82]

template<typename BV , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 79 of file mesh_octree_distance_traversal_node-inl.h.

◆ initialize() [38/82]

template<typename BV , typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 137 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [39/82]

template<typename BV , typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 137 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [40/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 442 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [41/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 442 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [42/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 410 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [43/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 410 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [44/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 458 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [45/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 458 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [46/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 426 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [47/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 426 of file mesh_shape_collision_traversal_node-inl.h.

◆ initialize() [48/82]

template<typename BV , typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

◆ initialize() [49/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

◆ initialize() [50/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

◆ initialize() [51/82]

template<typename BV , typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

◆ initialize() [52/82]

template<typename BV , typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

Definition at line 111 of file mesh_shape_distance_traversal_node-inl.h.

◆ initialize() [53/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 428 of file mesh_shape_distance_traversal_node-inl.h.

◆ initialize() [54/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 441 of file mesh_shape_distance_traversal_node-inl.h.

◆ initialize() [55/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

Definition at line 415 of file mesh_shape_distance_traversal_node-inl.h.

◆ initialize() [56/82]

template<typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 78 of file octree_collision_traversal_node-inl.h.

◆ initialize() [57/82]

template<typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 80 of file octree_distance_traversal_node-inl.h.

◆ initialize() [58/82]

template<typename BV , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 79 of file octree_mesh_collision_traversal_node-inl.h.

◆ initialize() [59/82]

template<typename BV , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 79 of file octree_mesh_distance_traversal_node-inl.h.

◆ initialize() [60/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 79 of file octree_shape_collision_traversal_node-inl.h.

◆ initialize() [61/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 80 of file octree_shape_distance_traversal_node-inl.h.

◆ initialize() [62/82]

template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 140 of file shape_collision_traversal_node-inl.h.

◆ initialize() [63/82]

template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

◆ initialize() [64/82]

template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 106 of file shape_distance_traversal_node-inl.h.

◆ initialize() [65/82]

template<typename Shape , typename BV , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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,
bool  refit_bottomup 
)

Initialize traversal node for collision between one mesh and one shape, given current object transform.

Definition at line 143 of file shape_mesh_collision_traversal_node-inl.h.

◆ initialize() [66/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 379 of file shape_mesh_collision_traversal_node-inl.h.

◆ initialize() [67/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 345 of file shape_mesh_collision_traversal_node-inl.h.

◆ initialize() [68/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 396 of file shape_mesh_collision_traversal_node-inl.h.

◆ initialize() [69/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 362 of file shape_mesh_collision_traversal_node-inl.h.

◆ initialize() [70/82]

template<typename Shape , typename BV , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

◆ initialize() [71/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

◆ initialize() [72/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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 
)

◆ initialize() [73/82]

template<typename Shape , typename BV , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 112 of file shape_mesh_distance_traversal_node-inl.h.

◆ initialize() [74/82]

template<typename Shape , typename BV , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 112 of file shape_mesh_distance_traversal_node-inl.h.

◆ initialize() [75/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 366 of file shape_mesh_distance_traversal_node-inl.h.

◆ initialize() [76/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 366 of file shape_mesh_distance_traversal_node-inl.h.

◆ initialize() [77/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 379 of file shape_mesh_distance_traversal_node-inl.h.

◆ initialize() [78/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 379 of file shape_mesh_distance_traversal_node-inl.h.

◆ initialize() [79/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 353 of file shape_mesh_distance_traversal_node-inl.h.

◆ initialize() [80/82]

template<typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT bool fcl::detail::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.

Definition at line 353 of file shape_mesh_distance_traversal_node-inl.h.

◆ initialize() [81/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 79 of file shape_octree_collision_traversal_node-inl.h.

◆ initialize() [82/82]

template<typename Shape , typename NarrowPhaseSolver >
bool fcl::detail::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.

Definition at line 80 of file shape_octree_distance_traversal_node-inl.h.

◆ intersectRectQuad2() [1/3]

template int fcl::detail::intersectRectQuad2 ( double  h[2],
double  p[8],
double  ret[16] 
)

◆ intersectRectQuad2() [2/3]

template<typename S >
FCL_EXPORT int fcl::detail::intersectRectQuad2 ( h[2],
p[8],
ret[16] 
)

Definition at line 110 of file box_box-inl.h.

◆ intersectRectQuad2() [3/3]

template<typename S >
int fcl::detail::intersectRectQuad2 ( h[2],
p[8],
ret[16] 
)

Definition at line 110 of file box_box-inl.h.

◆ IsElementInSet()

template<typename T >
bool fcl::detail::IsElementInSet ( const std::unordered_set< T * > &  S,
const T *  element 
)

Definition at line 551 of file test_gjk_libccd-inl_epa.cpp.

◆ lineClosestApproach() [1/3]

template void fcl::detail::lineClosestApproach ( const Vector3< double > &  pa,
const Vector3< double > &  ua,
const Vector3< double > &  pb,
const Vector3< double > &  ub,
double *  alpha,
double *  beta 
)

◆ lineClosestApproach() [2/3]

template<typename S >
FCL_EXPORT void fcl::detail::lineClosestApproach ( const Vector3< S > &  pa,
const Vector3< S > &  ua,
const Vector3< S > &  pb,
const Vector3< S > &  ub,
S *  alpha,
S *  beta 
)

Definition at line 86 of file box_box-inl.h.

◆ lineClosestApproach() [3/3]

template<typename S >
void fcl::detail::lineClosestApproach ( const Vector3< S > &  pa,
const Vector3< S > &  ua,
const Vector3< S > &  pb,
const Vector3< S > &  ub,
S *  alpha,
S *  beta 
)

Definition at line 86 of file box_box-inl.h.

◆ lineSegmentPointClosestToPoint() [1/3]

template void fcl::detail::lineSegmentPointClosestToPoint ( const Vector3< double > &  p,
const Vector3< double > &  s1,
const Vector3< double > &  s2,
Vector3< double > &  sp 
)

◆ lineSegmentPointClosestToPoint() [2/3]

template<typename S >
FCL_EXPORT void fcl::detail::lineSegmentPointClosestToPoint ( const Vector3< S > &  p,
const Vector3< S > &  s1,
const Vector3< S > &  s2,
Vector3< S > &  sp 
)

Definition at line 71 of file sphere_capsule-inl.h.

◆ lineSegmentPointClosestToPoint() [3/3]

template<typename S >
void fcl::detail::lineSegmentPointClosestToPoint ( const Vector3< S > &  p,
const Vector3< S > &  s1,
const Vector3< S > &  s2,
Vector3< S > &  sp 
)

Definition at line 71 of file sphere_capsule-inl.h.

◆ MapFeature1ToFeature2()

template<typename T >
void fcl::detail::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 
)

Definition at line 880 of file test_gjk_libccd-inl_epa.cpp.

◆ maximumDistance_mesh() [1/2]

template<typename S >
FCL_EXPORT S fcl::detail::maximumDistance_mesh ( const Vector3< S > *const  ps,
const Vector3< S > *const  ps2,
Triangle ts,
unsigned int *  indices,
int  n,
const Vector3< S > &  query 
)

Definition at line 149 of file geometry-inl.h.

◆ maximumDistance_mesh() [2/2]

template double fcl::detail::maximumDistance_mesh ( const Vector3d *const  ps,
const Vector3d *const  ps2,
Triangle ts,
unsigned int *  indices,
int  n,
const Vector3d query 
)

◆ maximumDistance_pointcloud() [1/2]

template<typename S >
FCL_EXPORT S fcl::detail::maximumDistance_pointcloud ( const Vector3< S > *const  ps,
const Vector3< S > *const  ps2,
unsigned int *  indices,
int  n,
const Vector3< S > &  query 
)

Definition at line 194 of file geometry-inl.h.

◆ maximumDistance_pointcloud() [2/2]

template double fcl::detail::maximumDistance_pointcloud ( const Vector3d *const  ps,
const Vector3d *const  ps2,
unsigned int *  indices,
int  n,
const Vector3d query 
)

◆ meshCollisionOrientedNodeLeafTesting() [1/4]

template<typename BV >
FCL_EXPORT void fcl::detail::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 
)

Definition at line 527 of file mesh_collision_traversal_node-inl.h.

◆ meshCollisionOrientedNodeLeafTesting() [2/4]

template<typename BV >
void fcl::detail::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 
)

Definition at line 527 of file mesh_collision_traversal_node-inl.h.

◆ meshCollisionOrientedNodeLeafTesting() [3/4]

template<typename BV >
FCL_EXPORT void fcl::detail::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 
)

Definition at line 624 of file mesh_collision_traversal_node-inl.h.

◆ meshCollisionOrientedNodeLeafTesting() [4/4]

template<typename BV >
void fcl::detail::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 
)

Definition at line 624 of file mesh_collision_traversal_node-inl.h.

◆ meshConservativeAdvancementOrientedNodeCanStop() [1/2]

template<typename BV >
FCL_EXPORT bool fcl::detail::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 
)

◆ meshConservativeAdvancementOrientedNodeCanStop() [2/2]

template<typename BV >
bool fcl::detail::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 
)

◆ meshConservativeAdvancementOrientedNodeLeafTesting() [1/2]

template<typename BV >
FCL_EXPORT void fcl::detail::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 
)

n is the local frame of object 1, pointing from object 1 to object2

turn n into the global frame, pointing from object 1 to object 2

Definition at line 664 of file mesh_conservative_advancement_traversal_node-inl.h.

◆ meshConservativeAdvancementOrientedNodeLeafTesting() [2/2]

template<typename BV >
void fcl::detail::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 
)

n is the local frame of object 1, pointing from object 1 to object2

turn n into the global frame, pointing from object 1 to object 2

Definition at line 664 of file mesh_conservative_advancement_traversal_node-inl.h.

◆ meshConservativeAdvancementTraversalNodeCanStop() [1/2]

template<typename BV >
FCL_EXPORT bool fcl::detail::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 
)

◆ meshConservativeAdvancementTraversalNodeCanStop() [2/2]

template<typename BV >
bool fcl::detail::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 
)

◆ meshDistanceOrientedNodeLeafTesting() [1/4]

template<typename BV >
FCL_DEPRECATED_EXPORT void fcl::detail::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 
)

Definition at line 402 of file mesh_distance_traversal_node-inl.h.

◆ meshDistanceOrientedNodeLeafTesting() [2/4]

template<typename BV >
void fcl::detail::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 
)

Definition at line 402 of file mesh_distance_traversal_node-inl.h.

◆ meshDistanceOrientedNodeLeafTesting() [3/4]

template<typename BV >
FCL_EXPORT void fcl::detail::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 
)

Definition at line 453 of file mesh_distance_traversal_node-inl.h.

◆ meshDistanceOrientedNodeLeafTesting() [4/4]

template<typename BV >
void fcl::detail::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 
)

Definition at line 453 of file mesh_distance_traversal_node-inl.h.

◆ meshShapeCollisionOrientedNodeLeafTesting() [1/2]

template<typename BV , typename Shape , typename NarrowPhaseSolver >
FCL_EXPORT void fcl::detail::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 
)

Definition at line 192 of file mesh_shape_collision_traversal_node-inl.h.

◆ meshShapeCollisionOrientedNodeLeafTesting() [2/2]

template<typename BV , typename Shape , typename NarrowPhaseSolver >
void fcl::detail::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 
)

Definition at line 192 of file mesh_shape_collision_traversal_node-inl.h.

◆ meshShapeConservativeAdvancementOrientedNodeCanStop()

template<typename BV , typename Shape >
bool fcl::detail::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 
)

◆ meshShapeConservativeAdvancementOrientedNodeLeafTesting()

template<typename BV , typename Shape , typename NarrowPhaseSolver >
void fcl::detail::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 
)

◆ meshShapeDistanceOrientedNodeLeafTesting()

template<typename BV , typename Shape , typename NarrowPhaseSolver >
void fcl::detail::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 
)

Definition at line 164 of file mesh_shape_distance_traversal_node-inl.h.

◆ nearestPointInBox()

template<typename S >
bool fcl::detail::nearestPointInBox ( const Vector3< S > &  size,
const Vector3< S > &  p_BQ,
Vector3< S > *  p_BN_ptr 
)

Definition at line 73 of file sphere_box-inl.h.

◆ nearestPointInCylinder()

template<typename S >
bool fcl::detail::nearestPointInCylinder ( const S &  height,
const S &  radius,
const Vector3< S > &  p_CQ,
Vector3< S > *  p_CN_ptr 
)

Definition at line 79 of file sphere_cylinder-inl.h.

◆ nodeBaseLess()

template<typename BV >
bool fcl::detail::nodeBaseLess ( NodeBase< BV > *  a,
NodeBase< BV > *  b,
int  d 
)

Compare two nodes accoording to the d-th dimension of node center.

Definition at line 1050 of file hierarchy_tree-inl.h.

◆ orientedBVHShapeCollide()

template<typename OrientMeshShapeCollisionTraveralNode , typename BV , typename Shape , typename NarrowPhaseSolver >
std::size_t fcl::detail::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 
)

Definition at line 378 of file collision_func_matrix-inl.h.

◆ orientedBVHShapeDistance()

template<typename OrientedMeshShapeDistanceTraversalNode , typename BV , typename Shape , typename NarrowPhaseSolver >
Shape::S fcl::detail::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 
)

Definition at line 259 of file distance_func_matrix-inl.h.

◆ orientedMeshCollide()

template<typename OrientedMeshCollisionTraversalNode , typename BV >
std::size_t fcl::detail::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 
)

Definition at line 572 of file collision_func_matrix-inl.h.

◆ orientedMeshDistance()

template<typename OrientedMeshDistanceTraversalNode , typename BV >
BV::S fcl::detail::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 
)

Definition at line 387 of file distance_func_matrix-inl.h.

◆ overlap()

template<typename S >
bool fcl::detail::overlap ( a1,
a2,
b1,
b2 
)

returns 1 if the intervals overlap, and 0 otherwise

Definition at line 498 of file interval_tree-inl.h.

◆ planeHalfspaceIntersect() [1/3]

template bool fcl::detail::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 
)

◆ planeHalfspaceIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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

Definition at line 624 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ planeHalfspaceIntersect() [3/3]

template<typename S >
bool fcl::detail::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

Definition at line 624 of file narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h.

◆ planeIntersect() [1/3]

template bool fcl::detail::planeIntersect ( const Plane< double > &  s1,
const Transform3< double > &  tf1,
const Plane< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ planeIntersect() [2/3]

template<typename S >
bool fcl::detail::planeIntersect ( const Plane< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *   
)

◆ planeIntersect() [3/3]

template<typename S >
FCL_EXPORT bool fcl::detail::planeIntersect ( const Plane< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ planeIntersectTolerance() [1/3]

template<>
float fcl::detail::planeIntersectTolerance ( )

◆ planeIntersectTolerance() [2/3]

template<typename S >
FCL_EXPORT S fcl::detail::planeIntersectTolerance ( )

◆ planeIntersectTolerance() [3/3]

template<typename S >
S fcl::detail::planeIntersectTolerance ( )

◆ planeTriangleIntersect() [1/3]

template bool fcl::detail::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 
)

◆ planeTriangleIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

◆ planeTriangleIntersect() [3/3]

template<typename S >
bool fcl::detail::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 
)

◆ projectInTriangle() [1/3]

template bool fcl::detail::projectInTriangle ( const Vector3< double > &  p1,
const Vector3< double > &  p2,
const Vector3< double > &  p3,
const Vector3< double > &  normal,
const Vector3< double > &  p 
)

◆ projectInTriangle() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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.

Definition at line 113 of file sphere_triangle-inl.h.

◆ projectInTriangle() [3/3]

template<typename S >
bool fcl::detail::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.

Definition at line 113 of file sphere_triangle-inl.h.

◆ propagateBVHFrontListCollisionRecurse() [1/2]

template void fcl::detail::propagateBVHFrontListCollisionRecurse ( CollisionTraversalNodeBase< double > *  node,
BVHFrontList front_list 
)

◆ propagateBVHFrontListCollisionRecurse() [2/2]

template<typename S >
FCL_EXPORT void fcl::detail::propagateBVHFrontListCollisionRecurse ( CollisionTraversalNodeBase< S > *  node,
BVHFrontList front_list 
)

Recurse function for front list propagation.

Definition at line 465 of file traversal_recurse-inl.h.

◆ segmentSqrDistance() [1/3]

template double fcl::detail::segmentSqrDistance ( const Vector3< double > &  from,
const Vector3< double > &  to,
const Vector3< double > &  p,
Vector3< double > &  nearest 
)

◆ segmentSqrDistance() [2/3]

template<typename S >
FCL_EXPORT S fcl::detail::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

Definition at line 84 of file sphere_triangle-inl.h.

◆ segmentSqrDistance() [3/3]

template<typename S >
S fcl::detail::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

Definition at line 84 of file sphere_triangle-inl.h.

◆ select() [1/2]

template<typename BV >
size_t fcl::detail::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

Definition at line 1089 of file hierarchy_tree-inl.h.

◆ select() [2/2]

template<typename BV >
size_t fcl::detail::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

Definition at line 1079 of file hierarchy_tree-inl.h.

◆ selfCollide() [1/3]

template void fcl::detail::selfCollide ( CollisionTraversalNodeBase< double > *  node,
BVHFrontList front_list 
)

◆ selfCollide() [2/3]

template<typename S >
void fcl::detail::selfCollide ( CollisionTraversalNodeBase< S > *  node,
BVHFrontList front_list 
)

self collision on collision traversal node; can use front list to accelerate

Definition at line 122 of file collision_node-inl.h.

◆ selfCollide() [3/3]

template<typename S >
FCL_EXPORT void fcl::detail::selfCollide ( CollisionTraversalNodeBase< S > *  node,
BVHFrontList front_list = nullptr 
)

self collision on collision traversal node; can use front list to accelerate

Definition at line 122 of file collision_node-inl.h.

◆ selfCollisionRecurse() [1/2]

template void fcl::detail::selfCollisionRecurse ( CollisionTraversalNodeBase< double > *  node,
int  b,
BVHFrontList front_list 
)

◆ selfCollisionRecurse() [2/2]

template<typename S >
FCL_EXPORT void fcl::detail::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.

Recurse function for self collision Make sure node is set correctly so that the first and second tree are the same

Definition at line 238 of file traversal_recurse-inl.h.

◆ SetUpBoxToBox()

template<typename S >
void fcl::detail::SetUpBoxToBox ( const Transform3< S > &  X_WF,
void **  o1,
void **  o2,
ccd_t *  ccd,
fcl::Transform3< S > *  X_FB1,
fcl::Transform3< S > *  X_FB2 
)

Definition at line 1336 of file test_gjk_libccd-inl_epa.cpp.

◆ setupMeshCollisionOrientedNode()

template<typename BV , typename OrientedNode >
bool fcl::detail::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 
)

Definition at line 716 of file mesh_collision_traversal_node-inl.h.

◆ setupMeshConservativeAdvancementOrientedDistanceNode()

template<typename BV , typename OrientedDistanceNode >
bool fcl::detail::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 
)

◆ setupMeshDistanceOrientedNode()

template<typename BV , typename OrientedNode >
static bool fcl::detail::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 
)
static

Definition at line 606 of file mesh_distance_traversal_node-inl.h.

◆ setupMeshShapeCollisionOrientedNode()

template<typename BV , typename Shape , typename NarrowPhaseSolver , template< typename, typename > class OrientedNode>
bool fcl::detail::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 
)

Definition at line 377 of file mesh_shape_collision_traversal_node-inl.h.

◆ setupMeshShapeDistanceOrientedNode()

template<typename BV , typename Shape , typename NarrowPhaseSolver , template< typename, typename > class OrientedNode>
static bool fcl::detail::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 
)
static

Definition at line 386 of file mesh_shape_distance_traversal_node-inl.h.

◆ setupShapeMeshCollisionOrientedNode()

template<typename Shape , typename BV , typename NarrowPhaseSolver , template< typename, typename > class OrientedNode>
static bool fcl::detail::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 
)
static

Definition at line 313 of file shape_mesh_collision_traversal_node-inl.h.

◆ setupShapeMeshDistanceOrientedNode()

template<typename Shape , typename BV , typename NarrowPhaseSolver , template< typename, typename > class OrientedNode>
static bool fcl::detail::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 
)
static

Definition at line 321 of file shape_mesh_distance_traversal_node-inl.h.

◆ ShapeBVHConservativeAdvancement()

template<typename Shape , typename BV , typename NarrowPhaseSolver >
BV::S fcl::detail::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 
)

Definition at line 736 of file conservative_advancement_func_matrix-inl.h.

◆ ShapeConservativeAdvancement()

template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver >
Shape1::S fcl::detail::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 
)

Definition at line 715 of file conservative_advancement_func_matrix-inl.h.

◆ ShapeShapeCollide()

template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver >
std::size_t fcl::detail::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 
)

Definition at line 279 of file collision_func_matrix-inl.h.

◆ ShapeShapeDistance()

template<typename Shape1 , typename Shape2 , typename NarrowPhaseSolver >
Shape1::S fcl::detail::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 
)

Definition at line 208 of file distance_func_matrix-inl.h.

◆ shapeToGJK()

template<typename S >
static void fcl::detail::shapeToGJK ( const ShapeBase< S > &  s,
const Transform3< S > &  tf,
ccd_obj_t o 
)
static

Basic shape to ccd shape

Definition at line 2265 of file gjk_libccd-inl.h.

◆ sphereBoxDistance() [1/2]

template bool fcl::detail::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 
)

◆ sphereBoxDistance() [2/2]

template<typename S >
FCL_EXPORT bool fcl::detail::sphereBoxDistance ( const Sphere< S > &  sphere,
const Transform3< S > &  X_FS,
const Box< S > &  box,
const Transform3< S > &  X_FB,
S *  distance,
Vector3< S > *  p_FSb,
Vector3< S > *  p_FBs 
)

Evaluate the minimum separating distance between a sphere and box. If separated, the nearest points on each shape will be returned in frame F.

Parameters
sphereThe sphere geometry.
X_FSThe pose of the sphere S in the common frame F.
boxThe box geometry.
X_FBThe pose of the box B in the common frame F.
distance[out](optional) The separating distance between the box and sphere. Set to -1 if the shapes are penetrating.
p_FSb[out](optional) The closest point on the sphere to the box measured and expressed in frame F.
p_FBs[out](optional) The closest point on the box to the sphere measured and expressed in frame F.
Returns
True if the objects are separated.
Template Parameters
SThe scalar parameter (must be a valid Eigen scalar).

Definition at line 183 of file sphere_box-inl.h.

◆ sphereBoxIntersect() [1/2]

template bool fcl::detail::sphereBoxIntersect ( const Sphere< double > &  sphere,
const Transform3< double > &  X_FS,
const Box< double > &  box,
const Transform3< double > &  X_FB,
std::vector< ContactPoint< double >> *  contacts 
)

◆ sphereBoxIntersect() [2/2]

template<typename S >
FCL_EXPORT bool fcl::detail::sphereBoxIntersect ( const Sphere< S > &  sphere,
const Transform3< S > &  X_FS,
const Box< S > &  box,
const Transform3< S > &  X_FB,
std::vector< ContactPoint< S >> *  contacts 
)

Detect collision between the sphere and box. If colliding, return characterization of collision in the provided vector.

The reported depth is guaranteed to be continuous with respect to the relative pose of the two objects. The normal and contact position are guaranteed to be continuous while the sphere center lies outside the box. However, if the sphere center lies inside the box, there are regions of discontinuity in both normal and contact position. This is due to the fact that there is not necessarily a unique characterization of penetration depth (i.e., the sphere center may be equidistant to multiple faces). In this case, the faces are arbitrarily prioritized and the face with the highest priority is used to compute normal and position. The priority order is +x, -x, +y, -y, +z, and -z. For example:

  • If the center is near the edge between the -y and +z faces, the normal will be defined w.r.t. to the -y face.
  • If the center is near the corner of the +x, +y, & +z faces, the +x face will be used.
Parameters
sphereThe sphere geometry.
X_FSThe pose of the sphere S in the common frame F.
boxThe box geometry.
X_FBThe pose of the box B in the common frame F.
contacts[out](optional) If the shapes collide, the contact point data will be appended to the end of this vector.
Returns
True if the objects are colliding (including touching).
Template Parameters
SThe scalar parameter (must be a valid Eigen scalar).

Definition at line 98 of file sphere_box-inl.h.

◆ sphereCapsuleDistance() [1/3]

template bool fcl::detail::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 
)

◆ sphereCapsuleDistance() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

Definition at line 125 of file sphere_capsule-inl.h.

◆ sphereCapsuleDistance() [3/3]

template<typename S >
bool fcl::detail::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 
)

Definition at line 125 of file sphere_capsule-inl.h.

◆ sphereCapsuleIntersect() [1/3]

template bool fcl::detail::sphereCapsuleIntersect ( const Sphere< double > &  s1,
const Transform3< double > &  tf1,
const Capsule< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ sphereCapsuleIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::sphereCapsuleIntersect ( const Sphere< S > &  s1,
const Transform3< S > &  tf1,
const Capsule< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

Definition at line 91 of file sphere_capsule-inl.h.

◆ sphereCapsuleIntersect() [3/3]

template<typename S >
bool fcl::detail::sphereCapsuleIntersect ( const Sphere< S > &  s1,
const Transform3< S > &  tf1,
const Capsule< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

Definition at line 91 of file sphere_capsule-inl.h.

◆ sphereCylinderDistance() [1/2]

template bool fcl::detail::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 
)

◆ sphereCylinderDistance() [2/2]

template<typename S >
FCL_EXPORT bool fcl::detail::sphereCylinderDistance ( const Sphere< S > &  sphere,
const Transform3< S > &  X_FS,
const Cylinder< S > &  cylinder,
const Transform3< S > &  X_FC,
S *  distance,
Vector3< S > *  p_FSc,
Vector3< S > *  p_FCs 
)

Evaluate the minimum separating distance between a sphere and cylinder. If separated, the nearest points on each shape will be returned in frame F.

Parameters
sphereThe sphere geometry.
X_FSThe pose of the sphere S in the common frame F.
cylinderThe cylinder geometry.
X_FCThe pose of the cylinder C in the common frame F.
distance[out](optional) The separating distance between the cylinder and sphere. Set to -1 if the shapes are penetrating.
p_FSc[out](optional) The closest point on the sphere to the cylinder measured and expressed in frame F.
p_FCs[out](optional) The closest point on the cylinder to the sphere measured and expressed in frame F.
Returns
True if the objects are separated.
Template Parameters
SThe scalar parameter (must be a valid Eigen scalar).

Definition at line 226 of file sphere_cylinder-inl.h.

◆ sphereCylinderIntersect() [1/2]

template bool fcl::detail::sphereCylinderIntersect ( const Sphere< double > &  sphere,
const Transform3< double > &  X_FS,
const Cylinder< double > &  cylinder,
const Transform3< double > &  X_FC,
std::vector< ContactPoint< double >> *  contacts 
)

◆ sphereCylinderIntersect() [2/2]

template<typename S >
FCL_EXPORT bool fcl::detail::sphereCylinderIntersect ( const Sphere< S > &  sphere,
const Transform3< S > &  X_FS,
const Cylinder< S > &  cylinder,
const Transform3< S > &  X_FC,
std::vector< ContactPoint< S >> *  contacts 
)

Detect collision between the sphere and cylinder. If colliding, return characterization of collision in the provided vector.

The reported depth is guaranteed to be continuous with respect to the relative pose. In contrast, the normal and contact position are only guaranteed to be similarly continuous while the sphere center lies outside the cylinder. However, if the sphere center lies inside the cylinder, there are regions of discontinuity in both normal and contact position. This is due to the fact that there is not necessarily a unique characterization of penetration depth (e.g., the sphere center may be equidistant to both a cap face as well as the barrel). This ambiguity is resolved through an arbitrary prioritization scheme. If the sphere center is equidistant to both an end face and the barrel, the end face is used for normal and contact position computation. If the sphere center is closer to the barrel, but there is no unique solution (i.e., the sphere center lies on the center axis), the sphere is arbitrarily considered to be penetrating from the direction of the cylinder's +x direction (yielding a contact normal in the cylinder's -x direction.)

Parameters
sphereThe sphere geometry.
X_FSThe pose of the sphere S in the common frame F.
cylinderThe cylinder geometry.
X_FCThe pose of the cylinder C in the common frame F.
contacts[out](optional) If the shapes collide, the contact point data will be appended to the end of this vector.
Returns
True if the objects are colliding (including touching).
Template Parameters
SThe scalar parameter (must be a valid Eigen scalar).

Definition at line 114 of file sphere_cylinder-inl.h.

◆ sphereHalfspaceIntersect() [1/3]

template bool fcl::detail::sphereHalfspaceIntersect ( const Sphere< double > &  s1,
const Transform3< double > &  tf1,
const Halfspace< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ sphereHalfspaceIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::sphereHalfspaceIntersect ( const Sphere< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ sphereHalfspaceIntersect() [3/3]

template<typename S >
bool fcl::detail::sphereHalfspaceIntersect ( const Sphere< S > &  s1,
const Transform3< S > &  tf1,
const Halfspace< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ spherePlaneIntersect() [1/3]

template bool fcl::detail::spherePlaneIntersect ( const Sphere< double > &  s1,
const Transform3< double > &  tf1,
const Plane< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ spherePlaneIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::spherePlaneIntersect ( const Sphere< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ spherePlaneIntersect() [3/3]

template<typename S >
bool fcl::detail::spherePlaneIntersect ( const Sphere< S > &  s1,
const Transform3< S > &  tf1,
const Plane< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

◆ sphereSphereDistance() [1/3]

template bool fcl::detail::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 
)

◆ sphereSphereDistance() [2/3]

template<typename S >
bool fcl::detail::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 
)

Definition at line 91 of file sphere_sphere-inl.h.

◆ sphereSphereDistance() [3/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

Definition at line 91 of file sphere_sphere-inl.h.

◆ sphereSphereIntersect() [1/3]

template bool fcl::detail::sphereSphereIntersect ( const Sphere< double > &  s1,
const Transform3< double > &  tf1,
const Sphere< double > &  s2,
const Transform3< double > &  tf2,
std::vector< ContactPoint< double >> *  contacts 
)

◆ sphereSphereIntersect() [2/3]

template<typename S >
bool fcl::detail::sphereSphereIntersect ( const Sphere< S > &  s1,
const Transform3< S > &  tf1,
const Sphere< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

Definition at line 66 of file sphere_sphere-inl.h.

◆ sphereSphereIntersect() [3/3]

template<typename S >
FCL_EXPORT bool fcl::detail::sphereSphereIntersect ( const Sphere< S > &  s1,
const Transform3< S > &  tf1,
const Sphere< S > &  s2,
const Transform3< S > &  tf2,
std::vector< ContactPoint< S >> *  contacts 
)

Definition at line 66 of file sphere_sphere-inl.h.

◆ sphereToGJK()

template<typename S >
static void fcl::detail::sphereToGJK ( const Sphere< S > &  s,
const Transform3< S > &  tf,
ccd_sphere_t sph 
)
static

Definition at line 2314 of file gjk_libccd-inl.h.

◆ sphereTriangleDistance() [1/9]

template bool fcl::detail::sphereTriangleDistance ( const Sphere< double > &  sp,
const Transform3< double > &  tf,
const Vector3< double > &  P1,
const Vector3< double > &  P2,
const Vector3< double > &  P3,
double *  dist 
)

◆ sphereTriangleDistance() [2/9]

template bool fcl::detail::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 
)

◆ sphereTriangleDistance() [3/9]

template bool fcl::detail::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 
)

◆ sphereTriangleDistance() [4/9]

template<typename S >
FCL_EXPORT bool fcl::detail::sphereTriangleDistance ( const Sphere< S > &  sp,
const Transform3< S > &  tf,
const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3,
S *  dist 
)

Definition at line 225 of file sphere_triangle-inl.h.

◆ sphereTriangleDistance() [5/9]

template<typename S >
bool fcl::detail::sphereTriangleDistance ( const Sphere< S > &  sp,
const Transform3< S > &  tf,
const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3,
S *  dist 
)

Definition at line 225 of file sphere_triangle-inl.h.

◆ sphereTriangleDistance() [6/9]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

Definition at line 468 of file sphere_triangle-inl.h.

◆ sphereTriangleDistance() [7/9]

template<typename S >
bool fcl::detail::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 
)

Definition at line 468 of file sphere_triangle-inl.h.

◆ sphereTriangleDistance() [8/9]

template<typename S >
FCL_EXPORT bool fcl::detail::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 
)

Definition at line 498 of file sphere_triangle-inl.h.

◆ sphereTriangleDistance() [9/9]

template<typename S >
bool fcl::detail::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 
)

Definition at line 498 of file sphere_triangle-inl.h.

◆ sphereTriangleIntersect() [1/3]

template bool fcl::detail::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_ 
)

◆ sphereTriangleIntersect() [2/3]

template<typename S >
FCL_EXPORT bool fcl::detail::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_ 
)

Definition at line 139 of file sphere_triangle-inl.h.

◆ sphereTriangleIntersect() [3/3]

template<typename S >
bool fcl::detail::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_ 
)

Definition at line 139 of file sphere_triangle-inl.h.

◆ supportBox()

static void fcl::detail::supportBox ( const void *  obj,
const ccd_vec3_t *  dir_,
ccd_vec3_t *  v 
)
inlinestatic

Support functions

Definition at line 2340 of file gjk_libccd-inl.h.

◆ supportCap()

static void fcl::detail::supportCap ( const void *  obj,
const ccd_vec3_t *  dir_,
ccd_vec3_t *  v 
)
inlinestatic

Definition at line 2362 of file gjk_libccd-inl.h.

◆ supportCone()

static void fcl::detail::supportCone ( const void *  obj,
const ccd_vec3_t *  dir_,
ccd_vec3_t *  v 
)
inlinestatic

Definition at line 2418 of file gjk_libccd-inl.h.

◆ supportConvex()

template<typename S >
static void fcl::detail::supportConvex ( const void *  obj,
const ccd_vec3_t *  dir_,
ccd_vec3_t *  v 
)
static

Definition at line 2494 of file gjk_libccd-inl.h.

◆ supportCyl()

static void fcl::detail::supportCyl ( const void *  obj,
const ccd_vec3_t *  dir_,
ccd_vec3_t *  v 
)
inlinestatic

Definition at line 2390 of file gjk_libccd-inl.h.

◆ supportEllipsoid()

static void fcl::detail::supportEllipsoid ( const void *  obj,
const ccd_vec3_t *  dir_,
ccd_vec3_t *  v 
)
inlinestatic

Definition at line 2468 of file gjk_libccd-inl.h.

◆ supportSphere()

static void fcl::detail::supportSphere ( const void *  obj,
const ccd_vec3_t *  dir_,
ccd_vec3_t *  v 
)
inlinestatic

Definition at line 2450 of file gjk_libccd-inl.h.

◆ supportTriangle()

static void fcl::detail::supportTriangle ( const void *  obj,
const ccd_vec3_t *  dir_,
ccd_vec3_t *  v 
)
static

Definition at line 2520 of file gjk_libccd-inl.h.

◆ TEST_F() [1/8]

fcl::detail::TEST_F ( ExtractClosestPoint  ,
ExtractFrom1Simplex   
)

◆ TEST_F() [2/8]

fcl::detail::TEST_F ( ExtractClosestPoint  ,
ExtractFrom1SimplexSupport   
)

◆ TEST_F() [3/8]

fcl::detail::TEST_F ( ExtractClosestPoint  ,
ExtractFrom2Simplex   
)

◆ TEST_F() [4/8]

fcl::detail::TEST_F ( ExtractClosestPoint  ,
ExtractFrom2SimplexDegenerate   
)

◆ TEST_F() [5/8]

fcl::detail::TEST_F ( ExtractClosestPoint  ,
ExtractFrom2SimplexSupport   
)

◆ TEST_F() [6/8]

fcl::detail::TEST_F ( ExtractClosestPoint  ,
ExtractFrom3SimplesDegenerateCoincident   
)

◆ TEST_F() [7/8]

fcl::detail::TEST_F ( ExtractClosestPoint  ,
ExtractFrom3SimplesDegenerateColinear   
)

◆ TEST_F() [8/8]

fcl::detail::TEST_F ( ExtractClosestPoint  ,
ExtractFrom3Simplex   
)

◆ TestBoxes()

template<typename S >
void fcl::detail::TestBoxes ( )

Definition at line 408 of file test_gjk_libccd-inl_signed_distance.cpp.

◆ TestBoxesInFrameF()

template<typename S >
void fcl::detail::TestBoxesInFrameF ( const Transform3< S > &  X_WF)

Definition at line 247 of file test_gjk_libccd-inl_signed_distance.cpp.

◆ TestCollidingSphereGJKSignedDistance()

template<typename S >
void fcl::detail::TestCollidingSphereGJKSignedDistance ( )

Definition at line 190 of file test_gjk_libccd-inl_signed_distance.cpp.

◆ TestNonCollidingSphereGJKSignedDistance()

template<typename S >
void fcl::detail::TestNonCollidingSphereGJKSignedDistance ( )

Definition at line 152 of file test_gjk_libccd-inl_signed_distance.cpp.

◆ TestSimplexToPolytope3()

template<typename S >
void fcl::detail::TestSimplexToPolytope3 ( )

Definition at line 1572 of file test_gjk_libccd-inl_epa.cpp.

◆ TestSimplexToPolytope3InGivenFrame()

template<typename S >
void fcl::detail::TestSimplexToPolytope3InGivenFrame ( const Transform3< S > &  X_WF)

Definition at line 1376 of file test_gjk_libccd-inl_epa.cpp.

◆ TestSphereToSphereGJKSignedDistance()

template<typename S >
void fcl::detail::TestSphereToSphereGJKSignedDistance ( radius1,
radius2,
const Vector3< S > &  p_F1,
const Vector3< S > &  p_F2,
solver_tolerance,
test_tol,
min_distance_expected 
)

Definition at line 64 of file test_gjk_libccd-inl_signed_distance.cpp.

◆ TetrahedronColinearVertices()

std::array<Vector3<ccd_real_t>, 4> fcl::detail::TetrahedronColinearVertices ( )

Definition at line 146 of file test_gjk_libccd-inl_epa.cpp.

◆ TetrahedronSmallFaceVertices()

std::array<Vector3<ccd_real_t>, 4> fcl::detail::TetrahedronSmallFaceVertices ( )

Definition at line 155 of file test_gjk_libccd-inl_epa.cpp.

◆ ThrowDetailedConfiguration()

template<typename Shape1 , typename Shape2 , typename Solver , typename S >
void fcl::detail::ThrowDetailedConfiguration ( const Shape1 &  s1,
const Transform3< S > &  X_FS1,
const Shape2 &  s2,
const Transform3< S > &  X_FS2,
const Solver solver,
const std::exception &  e 
)

Helper class for propagating a low-level exception upwards but with configuration-specific details appended. The parameters

Parameters
s1The first shape in the query.
X_FS1The pose of the first shape in frame F.
s2The second shape in the query.
X_FS2The pose of the second shape in frame F.
solverThe solver.
eThe original exception.
Template Parameters
Shape1The type of shape for shape 1.
Shape2The type of shape for shape 2.
SolverThe solver type (with scalar type erase).
PoseThe pose type (a Transform with scalar type erased).

Definition at line 142 of file failed_at_this_configuration.h.

◆ ThrowFailedAtThisConfiguration()

void fcl::detail::ThrowFailedAtThisConfiguration ( const std::string &  message,
const char *  func,
const char *  file,
int  line 
)

Helper function for dispatching an FailedAtThisConfiguration. Because this exception is designed to be caught and repackaged, we lose the automatic association with file and line number. This wraps them into the message of the exception so it can be preserved in the re-wrapping.

Parameters
messageThe error message itself.
funcThe name of the invoking function.
fileThe name of the file associated with the exception.
lineThe line number where the exception is thrown.

Definition at line 8 of file failed_at_this_configuration.cpp.

◆ ToCcdVec3()

template<typename S >
ccd_vec3_t fcl::detail::ToCcdVec3 ( const Eigen::Ref< const Vector3< S >> &  v)

Definition at line 1367 of file test_gjk_libccd-inl_epa.cpp.

◆ ToEigenVector()

template<typename S >
Vector3<S> fcl::detail::ToEigenVector ( const ccd_vec3_t &  v)

Definition at line 1362 of file test_gjk_libccd-inl_epa.cpp.

◆ triangle_area_is_zero()

bool fcl::detail::triangle_area_is_zero ( const Vector3d a,
const Vector3d b,
const Vector3d c 
)

◆ TriangleMatch()

bool fcl::detail::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 
)

Definition at line 844 of file test_gjk_libccd-inl_epa.cpp.

◆ triCreateGJKObject() [1/6]

template<typename S >
FCL_EXPORT void* fcl::detail::triCreateGJKObject ( const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3 
)

Definition at line 2919 of file gjk_libccd-inl.h.

◆ triCreateGJKObject() [2/6]

template<typename S >
void* fcl::detail::triCreateGJKObject ( const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3 
)

Definition at line 2919 of file gjk_libccd-inl.h.

◆ triCreateGJKObject() [3/6]

template<typename S >
FCL_EXPORT void* fcl::detail::triCreateGJKObject ( const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3,
const Transform3< S > &  tf 
)

Definition at line 2938 of file gjk_libccd-inl.h.

◆ triCreateGJKObject() [4/6]

template<typename S >
void* fcl::detail::triCreateGJKObject ( const Vector3< S > &  P1,
const Vector3< S > &  P2,
const Vector3< S > &  P3,
const Transform3< S > &  tf 
)

Definition at line 2938 of file gjk_libccd-inl.h.

◆ triCreateGJKObject() [5/6]

template void * fcl::detail::triCreateGJKObject ( const Vector3d P1,
const Vector3d P2,
const Vector3d P3 
)

◆ triCreateGJKObject() [6/6]

template void * fcl::detail::triCreateGJKObject ( const Vector3d P1,
const Vector3d P2,
const Vector3d P3,
const Transform3d tf 
)

◆ triDeleteGJKObject()

FCL_EXPORT void fcl::detail::triDeleteGJKObject ( void *  o_)
inline

Definition at line 2958 of file gjk_libccd-inl.h.

◆ triGetCenterFunction()

FCL_EXPORT GJKCenterFunction fcl::detail::triGetCenterFunction ( )
inline

Definition at line 2913 of file gjk_libccd-inl.h.

◆ triGetSupportFunction()

FCL_EXPORT GJKSupportFunction fcl::detail::triGetSupportFunction ( )
inline

initialize GJK Triangle

Definition at line 2908 of file gjk_libccd-inl.h.

◆ updateFrontList()

void fcl::detail::updateFrontList ( BVHFrontList front_list,
int  b1,
int  b2 
)

Add new front node into the front list.

Definition at line 54 of file BVH_front.cpp.

◆ ValidateRepresentation()

template<typename Shape >
::testing::AssertionResult fcl::detail::ValidateRepresentation ( const Shape &  shape,
const std::string &  code_string 
)

Definition at line 74 of file representation_util.h.

◆ VertexPositionCoincide()

bool fcl::detail::VertexPositionCoincide ( const ccd_pt_vertex_t v1,
const ccd_pt_vertex_t v2,
ccd_real_t  tol 
)

Definition at line 819 of file test_gjk_libccd-inl_epa.cpp.

◆ WriteCommaSeparated()

template<typename S >
void fcl::detail::WriteCommaSeparated ( std::stringstream *  sstream,
const Transform3< S > &  p 
)

Works in conjuction with ThrowDetailedConfiguration() to format the pose in a more python-like repr() way (facilitating error reproduction). In this case, just doing comma-delimited print outs makes copying-and-pasting the error message contents into code easier.

The intention is that the matrix is printed out as:

 a, b, c, d,
 e, f, g, h,
 i, j, k, l,
 m, n, o, p;

so, that it can easily be copied and pasted into code like this:

Transform3 X; X.matrix() << a, b, c, d, e, f, g, h, i, j, k, l, m, n, o, p;

Definition at line 109 of file failed_at_this_configuration.h.

◆ z_axis()

template<typename S >
Vector3<S> fcl::detail::z_axis ( const Transform3< S > &  X_AB)

Definition at line 154 of file capsule_capsule-inl.h.

Variable Documentation

◆ CollisionTraversalNodeBase< double >

template class FCL_EXPORT fcl::detail::CollisionTraversalNodeBase< double >

◆ ConvertBVImpl< double, AABB< double >, AABB< double > >

template class FCL_EXPORT fcl::detail::ConvertBVImpl< double, AABB< double >, AABB< double > >

◆ ConvertBVImpl< double, AABB< double >, OBB< double > >

template class FCL_EXPORT fcl::detail::ConvertBVImpl< double, AABB< double >, OBB< double > >

◆ ConvertBVImpl< double, AABB< double >, RSS< double > >

template class FCL_EXPORT fcl::detail::ConvertBVImpl< double, AABB< double >, RSS< double > >

◆ ConvertBVImpl< double, OBB< double >, OBB< double > >

template class FCL_EXPORT fcl::detail::ConvertBVImpl< double, OBB< double >, OBB< double > >

◆ ConvertBVImpl< double, OBB< double >, RSS< double > >

template class FCL_EXPORT fcl::detail::ConvertBVImpl< double, OBB< double >, RSS< double > >

◆ ConvertBVImpl< double, OBBRSS< double >, OBB< double > >

template class FCL_EXPORT fcl::detail::ConvertBVImpl< double, OBBRSS< double >, OBB< double > >

◆ ConvertBVImpl< double, OBBRSS< double >, RSS< double > >

template class FCL_EXPORT fcl::detail::ConvertBVImpl< double, OBBRSS< double >, RSS< double > >

◆ ConvertBVImpl< double, RSS< double >, OBB< double > >

template class FCL_EXPORT fcl::detail::ConvertBVImpl< double, RSS< double >, OBB< double > >

◆ ConvertBVImpl< double, RSS< double >, RSS< double > >

template class FCL_EXPORT fcl::detail::ConvertBVImpl< double, RSS< double >, RSS< double > >

◆ DistanceTraversalNodeBase< double >

template class FCL_EXPORT fcl::detail::DistanceTraversalNodeBase< double >

◆ GJKInitializer< double, Box< double > >

template class FCL_EXPORT fcl::detail::GJKInitializer< double, Box< double > >

◆ GJKInitializer< double, Capsule< double > >

template class FCL_EXPORT fcl::detail::GJKInitializer< double, Capsule< double > >

◆ GJKInitializer< double, Cone< double > >

template class FCL_EXPORT fcl::detail::GJKInitializer< double, Cone< double > >

◆ GJKInitializer< double, Convex< double > >

template class FCL_EXPORT fcl::detail::GJKInitializer< double, Convex< double > >

◆ GJKInitializer< double, Cylinder< double > >

template class FCL_EXPORT fcl::detail::GJKInitializer< double, Cylinder< double > >

◆ GJKInitializer< double, Ellipsoid< double > >

template class FCL_EXPORT fcl::detail::GJKInitializer< double, Ellipsoid< double > >

◆ GJKInitializer< double, Sphere< double > >

template class FCL_EXPORT fcl::detail::GJKInitializer< double, Sphere< double > >

◆ Intersect< double >

template class FCL_EXPORT fcl::detail::Intersect< double >

◆ IntervalTree

template<typename S >
class FCL_EXPORT fcl::detail::IntervalTree

Definition at line 51 of file interval_tree_node.h.

◆ IntervalTreeNode< double >

template class FCL_EXPORT fcl::detail::IntervalTreeNode< double >

◆ MeshCollisionTraversalNodekIOS< double >

template class FCL_EXPORT fcl::detail::MeshCollisionTraversalNodekIOS< double >

◆ MeshCollisionTraversalNodeOBB< double >

template class FCL_EXPORT fcl::detail::MeshCollisionTraversalNodeOBB< double >

◆ MeshCollisionTraversalNodeOBBRSS< double >

template class FCL_EXPORT fcl::detail::MeshCollisionTraversalNodeOBBRSS< double >

◆ MeshCollisionTraversalNodeRSS< double >

template class FCL_EXPORT fcl::detail::MeshCollisionTraversalNodeRSS< double >

◆ MeshConservativeAdvancementTraversalNodeOBBRSS< double >

◆ MeshConservativeAdvancementTraversalNodeRSS< double >

template class FCL_EXPORT fcl::detail::MeshConservativeAdvancementTraversalNodeRSS< double >

◆ MeshDistanceTraversalNodekIOS< double >

template class FCL_EXPORT fcl::detail::MeshDistanceTraversalNodekIOS< double >

◆ MeshDistanceTraversalNodeOBBRSS< double >

template class FCL_EXPORT fcl::detail::MeshDistanceTraversalNodeOBBRSS< double >

◆ MeshDistanceTraversalNodeRSS< double >

template class FCL_EXPORT fcl::detail::MeshDistanceTraversalNodeRSS< double >

◆ PolySolver< double >

template class FCL_EXPORT fcl::detail::PolySolver< double >

◆ Project< double >

template class FCL_EXPORT fcl::detail::Project< double >

◆ TraversalNodeBase< double >

template class FCL_EXPORT fcl::detail::TraversalNodeBase< double >

◆ TriangleDistance< double >

template class FCL_EXPORT fcl::detail::TriangleDistance< double >


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:50