All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
fcl Namespace Reference

Main namespace. More...

Namespaces

 details
 FCL internals.
 
 implementation_array
 
 time
 Namespace containing time datatypes and time operations.
 
 tools
 

Classes

class  AABB
 A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points. More...
 
class  BallEulerJoint
 
class  Box
 Center at zero point, axis aligned box. More...
 
class  BroadPhaseCollisionManager
 Base class for broad phase collision. It helps to accelerate the collision/distance between N objects. Also support self collision, self distance and collision/distance with another M objects. More...
 
class  BroadPhaseContinuousCollisionManager
 Base class for broad phase continuous collision. It helps to accelerate the continuous collision/distance between N objects. Also support self collision, self distance and collision/distance with another M objects. More...
 
class  BVFitter
 The class for the default algorithm fitting a bounding volume to a set of points. More...
 
class  BVFitter< kIOS >
 Specification of BVFitter for kIOS bounding volume. More...
 
class  BVFitter< OBB >
 Specification of BVFitter for OBB bounding volume. More...
 
class  BVFitter< OBBRSS >
 Specification of BVFitter for OBBRSS bounding volume. More...
 
class  BVFitter< RSS >
 Specification of BVFitter for RSS bounding volume. More...
 
class  BVFitterBase
 Interface for fitting a bv given the triangles or points inside it. More...
 
class  BVHCollisionTraversalNode
 Traversal node for collision between BVH models. More...
 
struct  BVHContinuousCollisionPair
 Traversal node for continuous collision between BVH models. More...
 
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. More...
 
class  BVHModel
 A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh) More...
 
class  BVHShapeCollisionTraversalNode
 Traversal node for collision between BVH and shape. More...
 
class  BVHShapeDistanceTraversalNode
 Traversal node for distance computation between BVH and shape. More...
 
class  BVMotionBoundVisitor
 Compute the motion bound for a bounding volume, given the closest direction n between two query objects. More...
 
struct  BVNode
 A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and also the geometry data provided in BV template parameter. More...
 
struct  BVNodeBase
 BVNodeBase encodes the tree structure for BVH. More...
 
class  BVSplitter
 A class describing the split rule that splits each BV node. More...
 
class  BVSplitterBase
 Base interface for BV splitting algorithm. More...
 
class  Capsule
 Center at zero point capsule. More...
 
struct  CollisionFunctionMatrix
 collision matrix stores the functions for collision between different types of objects and provides a uniform call interface More...
 
class  CollisionGeometry
 The geometry for the object for collision or distance computation. More...
 
class  CollisionObject
 the object for collision or distance computation, contains the geometry and the transform information More...
 
struct  CollisionRequest
 request to the collision algorithm More...
 
struct  CollisionResult
 collision result More...
 
class  CollisionTraversalNodeBase
 Node structure encoding the information required for collision traversal. More...
 
class  Cone
 Center at zero cone. More...
 
struct  ConservativeAdvancementFunctionMatrix
 
struct  ConservativeAdvancementStackData
 
struct  Contact
 Contact information returned by collision. More...
 
class  ContinuousCollisionObject
 the object for continuous collision or distance computation, contains the geometry and the motion information More...
 
struct  ContinuousCollisionRequest
 
struct  ContinuousCollisionResult
 continuous collision result More...
 
class  Convex
 Convex polytope. More...
 
struct  CostSource
 Cost source describes an area with a cost. The area is described by an AABB region. More...
 
class  Cylinder
 Center at zero cylinder. More...
 
struct  DistanceFunctionMatrix
 distance matrix stores the functions for distance between different types of objects and provides a uniform call interface More...
 
struct  DistanceRequest
 request to the distance computation More...
 
struct  DistanceResult
 distance result More...
 
class  DistanceTraversalNodeBase
 Node structure encoding the information required for distance traversal. More...
 
class  DynamicAABBTreeCollisionManager
 
class  DynamicAABBTreeCollisionManager_Array
 
class  Exception
 
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  GreedyKCenters
 An instance of this class can be used to greedily select a given number of representatives from a set of data points that are all far apart from each other. More...
 
class  Halfspace
 Half Space: this is equivalent to the Plane in ODE. More...
 
class  HierarchyTree
 Class for hierarchy tree structure. More...
 
struct  IMatrix3
 
class  InterpMotion
 Linear interpolation motion Each Motion is assumed to have constant linear velocity and angular velocity The motion is R(t)(p - p_ref) + p_ref + T(t) Therefore, R(0) = R0, R(1) = R1 T(0) = T0 + R0 p_ref - p_ref T(1) = T1 + R1 p_ref - p_ref. More...
 
class  Interpolation
 
class  InterpolationFactory
 
class  InterpolationLinear
 
class  Intersect
 CCD intersect kernel among primitives. More...
 
struct  Interval
 Interval class for [a, b]. More...
 
class  IntervalTree
 Interval tree. More...
 
class  IntervalTreeCollisionManager
 Collision manager based on interval tree. More...
 
class  IntervalTreeNode
 The node for interval tree. More...
 
struct  Item
 
struct  IVector3
 
class  Joint
 Base Joint. More...
 
class  JointConfig
 
class  KDOP
 KDOP class describes the KDOP collision structures. More...
 
class  kIOS
 A class describing the kIOS collision structure, which is a set of spheres. More...
 
class  Link
 
class  Matrix3fX
 Matrix2 class wrapper. the core data is in the template parameter class. 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...
 
class  Model
 
class  ModelConfig
 
class  ModelParseError
 
struct  morton_functor
 Functor to compute the morton code for a given AABB. More...
 
struct  morton_functor< boost::dynamic_bitset<> >
 Functor to compute n bit morton code for a given AABB. More...
 
struct  morton_functor< FCL_UINT32 >
 Functor to compute 30 bit morton code for a given AABB. More...
 
struct  morton_functor< FCL_UINT64 >
 Functor to compute 60 bit morton code for a given AABB. More...
 
class  MotionBase
 
class  NaiveCollisionManager
 Brute force N-body collision manager. More...
 
class  NearestNeighbors
 Abstract representation of a container that can perform nearest neighbors queries. More...
 
class  NearestNeighborsGNAT
 Geometric Near-neighbor Access Tree (GNAT), a data structure for nearest neighbor search. More...
 
class  NearestNeighborsLinear
 A nearest neighbors datastructure that uses linear search. More...
 
class  NearestNeighborsSqrtApprox
 A nearest neighbors datastructure that uses linear search. More...
 
struct  NodeBase
 dynamic AABB tree node More...
 
class  OBB
 Oriented bounding box class. More...
 
class  OBBRSS
 Class merging the OBB and RSS, can handle collision and distance simultaneously. More...
 
class  OcTree
 Octree is one type of collision geometry which can encode uncertainty information in the sensor data. 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...
 
struct  PenetrationDepthRequest
 
struct  PenetrationDepthResult
 
class  Plane
 Infinite plane. More...
 
class  PolySolver
 A class solves polynomial degree (1,2,3) equations. More...
 
struct  PredictResult
 
class  PrismaticJoint
 
class  Project
 Project functions. More...
 
class  Quaternion3f
 Quaternion used locally by InterpMotion. More...
 
class  RevoluteJoint
 
class  RNG
 Random number generation. More...
 
class  RSS
 A class for rectangle sphere-swept bounding volume. More...
 
class  SamplerBase
 
class  SamplerR
 
class  SamplerSE2
 
class  SamplerSE2_disk
 
class  SamplerSE3Euler
 
class  SamplerSE3Euler_ball
 
class  SamplerSE3Quat
 
class  SamplerSE3Quat_ball
 
class  SaPCollisionManager
 Rigorous SAP collision manager. More...
 
struct  Scaler
 
class  ScrewMotion
 
class  ShapeBase
 Base class for all basic geometric shapes. More...
 
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
 
class  ShapeDistanceTraversalNode
 Traversal node for distance between two shapes. More...
 
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...
 
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...
 
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...
 
class  SpatialHashingCollisionManager
 spatial hashing collision mananger More...
 
class  Sphere
 Center at zero point sphere. More...
 
class  SplineMotion
 
class  SSaPCollisionManager
 Simple SAP collision manager. More...
 
class  SVMClassifier
 
class  TaylorModel
 TaylorModel implements a third order Taylor model, i.e., a cubic approximation of a function over a time interval, with an interval remainder. More...
 
class  TBVMotionBoundVisitor
 
struct  TimeInterval
 
class  TMatrix3
 
class  Transform3f
 Simple transform class used locally by InterpMotion. More...
 
class  TranslationMotion
 
class  TraversalNodeBase
 Node structure encoding the information required for traversal. More...
 
class  Triangle
 Triangle with 3 indices for points. More...
 
class  TriangleDistance
 Triangle distance functions. More...
 
class  TriangleMotionBoundVisitor
 
class  TriangleP
 Triangle stores the points instead of only indices of points. More...
 
class  TVector3
 
class  unordered_map_hash_table
 
class  Variance3f
 Class for variance matrix in 3d. More...
 
class  Vec3fX
 Vector3 class wrapper. The core data is in the template parameter class. More...
 
class  Vec_n
 
class  Vecnf
 

Typedefs

typedef bool(* CollisionCallBack )(CollisionObject *o1, CollisionObject *o2, void *cdata)
 Callback for collision between two objects. Return value is whether can stop now. More...
 
typedef bool(* DistanceCallBack )(CollisionObject *o1, CollisionObject *o2, void *cdata, FCL_REAL &dist)
 Callback for distance between two objects, Return value is whether can stop now, also return the minimum distance till now. More...
 
typedef bool(* ContinuousCollisionCallBack )(ContinuousCollisionObject *o1, ContinuousCollisionObject *o2, void *cdata)
 Callback for continuous collision between two objects. Return value is whether can stop now. More...
 
typedef bool(* ContinuousDistanceCallBack )(ContinuousCollisionObject *o1, ContinuousCollisionObject *o2, void *cdata, FCL_REAL &dist)
 Callback for continuous distance between two objects, Return value is whether can stop now, also return the minimum distance till now. More...
 
typedef std::list< BVHFrontNodeBVHFrontList
 BVH front list is a list of front nodes. More...
 
typedef boost::shared_ptr
< MotionBase
MotionBasePtr
 
typedef double FCL_REAL
 
typedef boost::uint64_t FCL_INT64
 
typedef boost::int64_t FCL_UINT64
 
typedef boost::uint32_t FCL_UINT32
 
typedef boost::int32_t FCL_INT32
 
typedef boost::shared_ptr
< CollisionObject
CollisionObjectPtr_t
 
typedef boost::shared_ptr
< const CollisionObject
CollisionObjectConstPtr_t
 
typedef boost::shared_ptr
< CollisionGeometry
CollisionGeometryPtr_t
 
typedef boost::shared_ptr
< const CollisionGeometry
CollisionGeometryConstPtr_t
 
typedef Matrix3fX
< details::Matrix3Data
< FCL_REAL > > 
Matrix3f
 
typedef Vec3fX
< details::Vec3Data< FCL_REAL > > 
Vec3f
 

Enumerations

enum  JointType {
  JT_UNKNOWN,
  JT_PRISMATIC,
  JT_REVOLUTE,
  JT_BALLEULER
}
 
enum  SplitMethodType {
  SPLIT_METHOD_MEAN,
  SPLIT_METHOD_MEDIAN,
  SPLIT_METHOD_BV_CENTER
}
 Three types of split algorithms are provided in FCL as default. More...
 
enum  BVHBuildState {
  BVH_BUILD_STATE_EMPTY,
  BVH_BUILD_STATE_BEGUN,
  BVH_BUILD_STATE_PROCESSED,
  BVH_BUILD_STATE_UPDATE_BEGUN,
  BVH_BUILD_STATE_UPDATED,
  BVH_BUILD_STATE_REPLACE_BEGUN
}
 States for BVH construction empty->begun->processed ->replace_begun->processed -> ...... More...
 
enum  BVHReturnCode {
  BVH_OK = 0,
  BVH_ERR_MODEL_OUT_OF_MEMORY = -1,
  BVH_ERR_BUILD_OUT_OF_SEQUENCE = -2,
  BVH_ERR_BUILD_EMPTY_MODEL = -3,
  BVH_ERR_BUILD_EMPTY_PREVIOUS_FRAME = -4,
  BVH_ERR_UNSUPPORTED_FUNCTION = -5,
  BVH_ERR_UNUPDATED_MODEL = -6,
  BVH_ERR_INCORRECT_DATA = -7,
  BVH_ERR_UNKNOWN = -8
}
 Error code for BVH. More...
 
enum  BVHModelType {
  BVH_MODEL_UNKNOWN,
  BVH_MODEL_TRIANGLES,
  BVH_MODEL_POINTCLOUD
}
 BVH model type. More...
 
enum  InterpolationType {
  LINEAR,
  STANDARD
}
 
enum  GJKSolverType {
  GST_LIBCCD,
  GST_INDEP
}
 Type of narrow phase GJK solver. More...
 
enum  CCDMotionType {
  CCDM_TRANS,
  CCDM_LINEAR,
  CCDM_SCREW,
  CCDM_SPLINE
}
 
enum  CCDSolverType {
  CCDC_NAIVE,
  CCDC_CONSERVATIVE_ADVANCEMENT,
  CCDC_RAY_SHOOTING,
  CCDC_POLYNOMIAL_SOLVER
}
 
enum  PenetrationDepthType {
  PDT_TRANSLATIONAL,
  PDT_GENERAL_EULER,
  PDT_GENERAL_QUAT,
  PDT_GENERAL_EULER_BALL,
  PDT_GENERAL_QUAT_BALL
}
 
enum  KNNSolverType {
  KNN_LINEAR,
  KNN_GNAT,
  KNN_SQRTAPPROX
}
 
enum  OBJECT_TYPE {
  OT_UNKNOWN,
  OT_BVH,
  OT_GEOM,
  OT_OCTREE,
  OT_COUNT
}
 object type: BVH (mesh, points), basic geometry, octree More...
 
enum  NODE_TYPE {
  BV_UNKNOWN,
  BV_AABB,
  BV_OBB,
  BV_RSS,
  BV_kIOS,
  BV_OBBRSS,
  BV_KDOP16,
  BV_KDOP18,
  BV_KDOP24,
  GEOM_BOX,
  GEOM_SPHERE,
  GEOM_CAPSULE,
  GEOM_CONE,
  GEOM_CYLINDER,
  GEOM_CONVEX,
  GEOM_PLANE,
  GEOM_HALFSPACE,
  GEOM_TRIANGLE,
  GEOM_OCTREE,
  NODE_COUNT
}
 traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, capsule, cone, cylinder, convex, plane, triangle), and octree More...
 

Functions

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 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<>
size_t select (const NodeBase< AABB > &node, const NodeBase< AABB > &node1, const NodeBase< AABB > &node2)
 
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<>
size_t select (const AABB &query, const NodeBase< AABB > &node1, const NodeBase< AABB > &node2)
 
static AABB translate (const AABB &aabb, const Vec3f &t)
 translate the center of AABB by t More...
 
template<typename BV1 , typename BV2 >
static void convertBV (const BV1 &bv1, const Transform3f &tf1, BV2 &bv2)
 Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity configuration. More...
 
template<size_t N>
KDOP< N > translate (const KDOP< N > &bv, const Vec3f &t)
 translate the KDOP BV More...
 
kIOS translate (const kIOS &bv, const Vec3f &t)
 Translate the kIOS BV. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2)
 Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
FCL_REAL distance (const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
 Approximate distance between two kIOS bounding volumes. More...
 
OBB translate (const OBB &bv, const Vec3f &t)
 Translate the OBB bv. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const OBB &b1, const OBB &b2)
 Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const OBB &b1, const OBB &b2, FCL_REAL &sqrDistLowerBound)
 Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
bool obbDisjoint (const Matrix3f &B, const Vec3f &T, const Vec3f &a, const Vec3f &b)
 Check collision between two boxes. More...
 
OBBRSS translate (const OBBRSS &bv, const Vec3f &t)
 Translate the OBBRSS bv. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const OBBRSS &b1, const OBBRSS &b2)
 Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const OBBRSS &b1, const OBBRSS &b2, FCL_REAL &sqrDistLowerBound)
 Check collision between two OBBRSS. More...
 
FCL_REAL distance (const Matrix3f &R0, const Vec3f &T0, const OBBRSS &b1, const OBBRSS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
 Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not NULL, returns the nearest points. More...
 
RSS translate (const RSS &bv, const Vec3f &t)
 Translate the RSS bv. More...
 
FCL_REAL distance (const Matrix3f &R0, const Vec3f &T0, const RSS &b1, const RSS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
 distance between two RSS bounding volumes P and Q (optional return values) are the closest points in the rectangles, not the RSS. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const RSS &b1, const RSS &b2)
 Check collision between two RSSs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
template<typename BV >
void fit (Vec3f *ps, int n, BV &bv)
 Compute a bounding volume that fits a set of n points. More...
 
template<>
void fit< OBB > (Vec3f *ps, int n, OBB &bv)
 
template<>
void fit< RSS > (Vec3f *ps, int n, RSS &bv)
 
template<>
void fit< kIOS > (Vec3f *ps, int n, kIOS &bv)
 
template<>
void fit< OBBRSS > (Vec3f *ps, int n, OBBRSS &bv)
 
void updateFrontList (BVHFrontList *front_list, int b1, int b2)
 Add new front node into the front list. More...
 
template<typename BV >
void BVHExpand (BVHModel< BV > &model, const Variance3f *ucs, FCL_REAL r)
 Expand the BVH bounding boxes according to the variance matrix corresponding to the data stored within each BV node. More...
 
void BVHExpand (BVHModel< OBB > &model, const Variance3f *ucs, FCL_REAL r)
 Expand the BVH bounding boxes according to the corresponding variance information, for OBB. More...
 
void BVHExpand (BVHModel< RSS > &model, const Variance3f *ucs, FCL_REAL r)
 Expand the BVH bounding boxes according to the corresponding variance information, for RSS. More...
 
void getCovariance (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, Matrix3f &M)
 Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to points directly; otherwise refer to triangles. More...
 
void getRadiusAndOriginAndRectangleSize (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, Vec3f axis[3], Vec3f &origin, FCL_REAL l[2], FCL_REAL &r)
 Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises. More...
 
void getExtentAndCenter (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, Vec3f axis[3], Vec3f &center, Vec3f &extent)
 Compute the bounding volume extent and center for a set or subset of points, given the BV axises. More...
 
void circumCircleComputation (const Vec3f &a, const Vec3f &b, const Vec3f &c, Vec3f &center, FCL_REAL &radius)
 Compute the center and radius for a triangle's circumcircle. More...
 
FCL_REAL maximumDistance (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, const Vec3f &query)
 Compute the maximum distance from a given center point to a point cloud. More...
 
Interval bound (const Interval &i, FCL_REAL v)
 
Interval bound (const Interval &i, const Interval &other)
 
IMatrix3 rotationConstrain (const IMatrix3 &m)
 
IVector3 bound (const IVector3 &i, const Vec3f &v)
 
IVector3 bound (const IVector3 &i, const IVector3 &v)
 
TMatrix3 rotationConstrain (const TMatrix3 &m)
 
TMatrix3 operator* (const Matrix3f &m, const TaylorModel &a)
 
TMatrix3 operator* (const TaylorModel &a, const Matrix3f &m)
 
TMatrix3 operator* (const TaylorModel &a, const TMatrix3 &m)
 
TMatrix3 operator* (FCL_REAL d, const TMatrix3 &m)
 
TMatrix3 operator+ (const Matrix3f &m1, const TMatrix3 &m2)
 
TMatrix3 operator- (const Matrix3f &m1, const TMatrix3 &m2)
 
TaylorModel operator* (FCL_REAL d, const TaylorModel &a)
 
TaylorModel operator+ (FCL_REAL d, const TaylorModel &a)
 
TaylorModel operator- (FCL_REAL d, const TaylorModel &a)
 
void generateTaylorModelForCosFunc (TaylorModel &tm, FCL_REAL w, FCL_REAL q0)
 Generate Taylor model for cos(w t + q0) More...
 
void generateTaylorModelForSinFunc (TaylorModel &tm, FCL_REAL w, FCL_REAL q0)
 Generate Taylor model for sin(w t + q0) More...
 
void generateTaylorModelForLinearFunc (TaylorModel &tm, FCL_REAL p, FCL_REAL v)
 Generate Taylor model for p + v t. More...
 
void generateTVector3ForLinearFunc (TVector3 &v, const Vec3f &position, const Vec3f &velocity)
 
TVector3 operator* (const Vec3f &v, const TaylorModel &a)
 
TVector3 operator+ (const Vec3f &v1, const TVector3 &v2)
 
TVector3 operator- (const Vec3f &v1, const TVector3 &v2)
 
std::size_t collide (const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
 Main collision interface: given two collision objects, and the requirements for contacts, including num of max contacts, whether perform exhaustive collision (i.e., returning returning all the contact points), whether return detailed contact information (i.e., normal, contact point, depth; otherwise only contact primitive id is returned), this function performs the collision between them. More...
 
std::size_t collide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 
void collide (CollisionTraversalNodeBase *node, FCL_REAL &sqrDistLowerBound, BVHFrontList *front_list=NULL)
 collision on collision traversal node More...
 
void selfCollide (CollisionTraversalNodeBase *node, BVHFrontList *front_list=NULL)
 self collision on collision traversal node; can use front list to accelerate More...
 
void distance (DistanceTraversalNodeBase *node, BVHFrontList *front_list=NULL, int qsize=2)
 distance computation on distance traversal node; can use front list to accelerate More...
 
void collide2 (MeshCollisionTraversalNodeOBB *node, BVHFrontList *front_list=NULL)
 special collision on OBB traversal node More...
 
void collide2 (MeshCollisionTraversalNodeRSS *node, BVHFrontList *front_list=NULL)
 special collision on RSS traversal node More...
 
FCL_REAL continuousCollide (const CollisionGeometry *o1, const Transform3f &tf1_beg, const Transform3f &tf1_end, const CollisionGeometry *o2, const Transform3f &tf2_beg, const Transform3f &tf2_end, const ContinuousCollisionRequest &request, ContinuousCollisionResult &result)
 continous collision checking between two objects More...
 
FCL_REAL continuousCollide (const CollisionObject *o1, const Transform3f &tf1_end, const CollisionObject *o2, const Transform3f &tf2_end, const ContinuousCollisionRequest &request, ContinuousCollisionResult &result)
 
FCL_REAL collide (const ContinuousCollisionObject *o1, const ContinuousCollisionObject *o2, const ContinuousCollisionRequest &request, ContinuousCollisionResult &result)
 
FCL_REAL distance (const CollisionObject *o1, const CollisionObject *o2, const DistanceRequest &request, DistanceResult &result)
 Main distance interface: given two collision objects, and the requirements for contacts, including whether return the nearest points, this function performs the distance between them. More...
 
FCL_REAL distance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 
template<std::size_t N>
Scaler< N > computeScaler (const std::vector< Item< N > > &data)
 
template<std::size_t N>
Scaler< N > computeScaler (const std::vector< Vecnf< N > > &data)
 
template<typename T >
void hat (Matrix3fX< T > &mat, const Vec3fX< typename T::vector_type > &vec)
 
template<typename T >
void relativeTransform (const Matrix3fX< T > &R1, const Vec3fX< typename T::vector_type > &t1, const Matrix3fX< T > &R2, const Vec3fX< typename T::vector_type > &t2, Matrix3fX< T > &R, Vec3fX< typename T::vector_type > &t)
 
template<typename T >
void eigen (const Matrix3fX< T > &m, typename T::meta_type dout[3], Vec3fX< typename T::vector_type > vout[3])
 compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors More...
 
template<typename T >
Matrix3fX< T > abs (const Matrix3fX< T > &R)
 
template<typename T >
Matrix3fX< T > transpose (const Matrix3fX< T > &R)
 
template<typename T >
Matrix3fX< T > inverse (const Matrix3fX< T > &R)
 
template<typename T >
T::meta_type quadraticForm (const Matrix3fX< T > &R, const Vec3fX< typename T::vector_type > &v)
 
static std::ostream & operator<< (std::ostream &o, const Matrix3f &m)
 
Quaternion3f conj (const Quaternion3f &q)
 conjugate of quaternion More...
 
Quaternion3f inverse (const Quaternion3f &q)
 inverse of quaternion More...
 
Transform3f inverse (const Transform3f &tf)
 inverse the transform More...
 
void relativeTransform (const Transform3f &tf1, const Transform3f &tf2, Transform3f &tf)
 compute the relative transform between two transforms: tf2 = tf1 * tf (relative to the local coordinate system in tf1) More...
 
void relativeTransform2 (const Transform3f &tf1, const Transform3f &tf2, Transform3f &tf)
 compute the relative transform between two transforms: tf2 = tf * tf1 (relative to the global coordinate system) More...
 
template<typename T >
static Vec3fX< T > normalize (const Vec3fX< T > &v)
 
template<typename T >
static T::meta_type triple (const Vec3fX< T > &x, const Vec3fX< T > &y, const Vec3fX< T > &z)
 
template<typename T >
std::ostream & operator<< (std::ostream &out, const Vec3fX< T > &x)
 
template<typename T >
static Vec3fX< T > min (const Vec3fX< T > &x, const Vec3fX< T > &y)
 
template<typename T >
static Vec3fX< T > max (const Vec3fX< T > &x, const Vec3fX< T > &y)
 
template<typename T >
static Vec3fX< T > abs (const Vec3fX< T > &x)
 
template<typename T >
void generateCoordinateSystem (const Vec3fX< T > &w, Vec3fX< T > &u, Vec3fX< T > &v)
 
static std::ostream & operator<< (std::ostream &o, const Vec3f &v)
 
template<typename T >
Vec3fX< T > operator* (const typename Vec3fX< T >::U &t, const Vec3fX< T > &v)
 
template<typename T1 , std::size_t N1, typename T2 , std::size_t N2>
void repack (const Vec_n< T1, N1 > &input, Vec_n< T2, N2 > &output)
 
template<typename T , std::size_t N>
Vec_n< T, N > operator* (T t, const Vec_n< T, N > &v)
 
template<typename T , std::size_t N, std::size_t M>
Vec_n< T, M+N > combine (const Vec_n< T, N > &v1, const Vec_n< T, M > &v2)
 
template<typename T , std::size_t N>
std::ostream & operator<< (std::ostream &o, const Vec_n< T, N > &v)
 
static void computeChildBV (const AABB &root_bv, unsigned int i, AABB &child_bv)
 compute the bounding volume of an octree node's i-th child More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Box &shape, const Transform3f &pose)
 Generate BVH model from box. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Sphere &shape, const Transform3f &pose, unsigned int seg, unsigned int ring)
 Generate BVH model from sphere, given the number of segments along longitude and number of rings along latitude. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Sphere &shape, const Transform3f &pose, unsigned int n_faces_for_unit_sphere)
 Generate BVH model from sphere The difference between generateBVHModel is that it gives the number of triangles faces N for a sphere with unit radius. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Cylinder &shape, const Transform3f &pose, unsigned int tot, unsigned int h_num)
 Generate BVH model from cylinder, given the number of segments along circle and the number of segments along axis. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Cylinder &shape, const Transform3f &pose, unsigned int tot_for_unit_cylinder)
 Generate BVH model from cylinder Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Cone &shape, const Transform3f &pose, unsigned int tot, unsigned int h_num)
 Generate BVH model from cone, given the number of segments along circle and the number of segments along axis. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Cone &shape, const Transform3f &pose, unsigned int tot_for_unit_cone)
 Generate BVH model from cone Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius. More...
 
template<typename BV , typename S >
void computeBV (const S &s, const Transform3f &tf, BV &bv)
 calculate a bounding volume for a shape in a specific configuration More...
 
template<>
void computeBV< AABB, Box > (const Box &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Sphere > (const Sphere &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Capsule > (const Capsule &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Cone > (const Cone &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Cylinder > (const Cylinder &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Convex > (const Convex &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, TriangleP > (const TriangleP &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Halfspace > (const Halfspace &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Plane > (const Plane &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< OBB, Box > (const Box &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Sphere > (const Sphere &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Capsule > (const Capsule &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Cone > (const Cone &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Cylinder > (const Cylinder &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Convex > (const Convex &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Halfspace > (const Halfspace &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Plane > (const Plane &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< RSS, Plane > (const Plane &s, const Transform3f &tf, RSS &bv)
 
template<>
void computeBV< OBBRSS, Plane > (const Plane &s, const Transform3f &tf, OBBRSS &bv)
 
template<>
void computeBV< kIOS, Plane > (const Plane &s, const Transform3f &tf, kIOS &bv)
 
template<>
void computeBV< KDOP< 16 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 16 > &bv)
 
template<>
void computeBV< KDOP< 18 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 18 > &bv)
 
template<>
void computeBV< KDOP< 24 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 24 > &bv)
 
void constructBox (const AABB &bv, Box &box, Transform3f &tf)
 construct a box shape (with a configuration) from a given bounding volume More...
 
void constructBox (const OBB &bv, Box &box, Transform3f &tf)
 
void constructBox (const OBBRSS &bv, Box &box, Transform3f &tf)
 
void constructBox (const kIOS &bv, Box &box, Transform3f &tf)
 
void constructBox (const RSS &bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 16 > &bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 18 > &bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 24 > &bv, Box &box, Transform3f &tf)
 
void constructBox (const AABB &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const OBB &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const OBBRSS &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const kIOS &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const RSS &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 16 > &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 18 > &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 24 > &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
Halfspace transform (const Halfspace &a, const Transform3f &tf)
 
Plane transform (const Plane &a, const Transform3f &tf)
 
static __m128 sse_four_spheres_intersect (const Vec3f &o1, FCL_REAL r1, const Vec3f &o2, FCL_REAL r2, const Vec3f &o3, FCL_REAL r3, const Vec3f &o4, FCL_REAL r4, const Vec3f &o5, FCL_REAL r5, const Vec3f &o6, FCL_REAL r6, const Vec3f &o7, FCL_REAL r7, const Vec3f &o8, FCL_REAL r8)
 
static __m128 sse_four_spheres_four_AABBs_intersect (const Vec3f &o1, FCL_REAL r1, const Vec3f &o2, FCL_REAL r2, const Vec3f &o3, FCL_REAL r3, const Vec3f &o4, FCL_REAL r4, const Vec3f &min1, const Vec3f &max1, const Vec3f &min2, const Vec3f &max2, const Vec3f &min3, const Vec3f &max3, const Vec3f &min4, const Vec3f &max4)
 
static __m128 sse_four_AABBs_intersect (const Vec3f &min1, const Vec3f &max1, const Vec3f &min2, const Vec3f &max2, const Vec3f &min3, const Vec3f &max3, const Vec3f &min4, const Vec3f &max4, const Vec3f &min5, const Vec3f &max5, const Vec3f &min6, const Vec3f &max6, const Vec3f &min7, const Vec3f &max7, const Vec3f &min8, const Vec3f &max8)
 
static bool four_spheres_intersect_and (const Vec3f &o1, FCL_REAL r1, const Vec3f &o2, FCL_REAL r2, const Vec3f &o3, FCL_REAL r3, const Vec3f &o4, FCL_REAL r4, const Vec3f &o5, FCL_REAL r5, const Vec3f &o6, FCL_REAL r6, const Vec3f &o7, FCL_REAL r7, const Vec3f &o8, FCL_REAL r8)
 
static bool four_spheres_intersect_or (const Vec3f &o1, FCL_REAL r1, const Vec3f &o2, FCL_REAL r2, const Vec3f &o3, FCL_REAL r3, const Vec3f &o4, FCL_REAL r4, const Vec3f &o5, FCL_REAL r5, const Vec3f &o6, FCL_REAL r6, const Vec3f &o7, FCL_REAL r7, const Vec3f &o8, FCL_REAL r8)
 
static bool four_spheres_four_AABBs_intersect_and (const Vec3f &o1, FCL_REAL r1, const Vec3f &o2, FCL_REAL r2, const Vec3f &o3, FCL_REAL r3, const Vec3f &o4, FCL_REAL r4, const Vec3f &min1, const Vec3f &max1, const Vec3f &min2, const Vec3f &max2, const Vec3f &min3, const Vec3f &max3, const Vec3f &min4, const Vec3f &max4)
 four spheres versus four AABBs SIMD test More...
 
static bool four_spheres_four_AABBs_intersect_or (const Vec3f &o1, FCL_REAL r1, const Vec3f &o2, FCL_REAL r2, const Vec3f &o3, FCL_REAL r3, const Vec3f &o4, FCL_REAL r4, const Vec3f &min1, const Vec3f &max1, const Vec3f &min2, const Vec3f &max2, const Vec3f &min3, const Vec3f &max3, const Vec3f &min4, const Vec3f &max4)
 
static bool four_AABBs_intersect_and (const Vec3f &min1, const Vec3f &max1, const Vec3f &min2, const Vec3f &max2, const Vec3f &min3, const Vec3f &max3, const Vec3f &min4, const Vec3f &max4, const Vec3f &min5, const Vec3f &max5, const Vec3f &min6, const Vec3f &max6, const Vec3f &min7, const Vec3f &max7, const Vec3f &min8, const Vec3f &max8)
 four AABBs versus four AABBs SIMD test More...
 
static bool four_AABBs_intersect_or (const Vec3f &min1, const Vec3f &max1, const Vec3f &min2, const Vec3f &max2, const Vec3f &min3, const Vec3f &max3, const Vec3f &min4, const Vec3f &max4, const Vec3f &min5, const Vec3f &max5, const Vec3f &min6, const Vec3f &max6, const Vec3f &min7, const Vec3f &max7, const Vec3f &min8, const Vec3f &max8)
 
template<typename S1 , typename S2 , typename NarrowPhaseSolver >
bool initialize (ShapeCollisionTraversalNode< S1, S2, NarrowPhaseSolver > &node, const S1 &shape1, const Transform3f &tf1, const S2 &shape2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 Initialize traversal node for collision between two geometric shapes, given current object transform. More...
 
template<typename BV , typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeCollisionTraversalNode< BV, S, NarrowPhaseSolver > &node, BVHModel< BV > &model1, Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &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 S , typename BV , typename NarrowPhaseSolver >
bool initialize (ShapeMeshCollisionTraversalNode< S, BV, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, BVHModel< BV > &model2, Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &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 S , typename NarrowPhaseSolver >
bool initialize (MeshShapeCollisionTraversalNodeOBB< S, NarrowPhaseSolver > &node, const BVHModel< OBB > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 Initialize the traversal node for collision between one mesh and one shape, specialized for OBB type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeCollisionTraversalNodeRSS< S, NarrowPhaseSolver > &node, const BVHModel< RSS > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 Initialize the traversal node for collision between one mesh and one shape, specialized for RSS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeCollisionTraversalNodekIOS< S, NarrowPhaseSolver > &node, const BVHModel< kIOS > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 Initialize the traversal node for collision between one mesh and one shape, specialized for kIOS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeCollisionTraversalNodeOBBRSS< S, NarrowPhaseSolver > &node, const BVHModel< OBBRSS > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (ShapeMeshCollisionTraversalNodeOBB< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< OBB > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 Initialize the traversal node for collision between one mesh and one shape, specialized for OBB type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (ShapeMeshCollisionTraversalNodeRSS< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< RSS > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 Initialize the traversal node for collision between one mesh and one shape, specialized for RSS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (ShapeMeshCollisionTraversalNodekIOS< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< kIOS > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 Initialize the traversal node for collision between one mesh and one shape, specialized for kIOS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (ShapeMeshCollisionTraversalNodeOBBRSS< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< OBBRSS > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS type. More...
 
template<typename BV >
bool initialize (MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3f &tf1, BVHModel< BV > &model2, Transform3f &tf2, const CollisionRequest &request, CollisionResult &result, bool use_refit=false, bool refit_bottomup=false)
 Initialize traversal node for collision between two meshes, given the current transforms. More...
 
bool initialize (MeshCollisionTraversalNodeOBB &node, const BVHModel< OBB > &model1, const Transform3f &tf1, const BVHModel< OBB > &model2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 Initialize traversal node for collision between two meshes, specialized for OBB type. More...
 
bool initialize (MeshCollisionTraversalNodeRSS &node, const BVHModel< RSS > &model1, const Transform3f &tf1, const BVHModel< RSS > &model2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 Initialize traversal node for collision between two meshes, specialized for RSS type. More...
 
bool initialize (MeshCollisionTraversalNodeOBBRSS &node, const BVHModel< OBBRSS > &model1, const Transform3f &tf1, const BVHModel< OBBRSS > &model2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 Initialize traversal node for collision between two meshes, specialized for OBBRSS type. More...
 
bool initialize (MeshCollisionTraversalNodekIOS &node, const BVHModel< kIOS > &model1, const Transform3f &tf1, const BVHModel< kIOS > &model2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 Initialize traversal node for collision between two meshes, specialized for kIOS type. More...
 
template<typename S1 , typename S2 , typename NarrowPhaseSolver >
bool initialize (ShapeDistanceTraversalNode< S1, S2, NarrowPhaseSolver > &node, const S1 &shape1, const Transform3f &tf1, const S2 &shape2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance between two geometric shapes. More...
 
template<typename BV >
bool initialize (MeshDistanceTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3f &tf1, BVHModel< BV > &model2, Transform3f &tf2, const DistanceRequest &request, DistanceResult &result, bool use_refit=false, bool refit_bottomup=false)
 Initialize traversal node for distance computation between two meshes, given the current transforms. More...
 
bool initialize (MeshDistanceTraversalNodeRSS &node, const BVHModel< RSS > &model1, const Transform3f &tf1, const BVHModel< RSS > &model2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance computation between two meshes, specialized for RSS type. More...
 
bool initialize (MeshDistanceTraversalNodekIOS &node, const BVHModel< kIOS > &model1, const Transform3f &tf1, const BVHModel< kIOS > &model2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance computation between two meshes, specialized for kIOS type. More...
 
bool initialize (MeshDistanceTraversalNodeOBBRSS &node, const BVHModel< OBBRSS > &model1, const Transform3f &tf1, const BVHModel< OBBRSS > &model2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance computation between two meshes, specialized for OBBRSS type. More...
 
template<typename BV , typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeDistanceTraversalNode< BV, S, NarrowPhaseSolver > &node, BVHModel< BV > &model1, Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &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 S , typename BV , typename NarrowPhaseSolver >
bool initialize (ShapeMeshDistanceTraversalNode< S, BV, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, BVHModel< BV > &model2, Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &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 S , typename NarrowPhaseSolver >
bool initialize (MeshShapeDistanceTraversalNodeRSS< S, NarrowPhaseSolver > &node, const BVHModel< RSS > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance computation between one mesh and one shape, specialized for RSS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeDistanceTraversalNodekIOS< S, NarrowPhaseSolver > &node, const BVHModel< kIOS > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance computation between one mesh and one shape, specialized for kIOS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeDistanceTraversalNodeOBBRSS< S, NarrowPhaseSolver > &node, const BVHModel< OBBRSS > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance computation between one mesh and one shape, specialized for OBBRSS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (ShapeMeshDistanceTraversalNodeRSS< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< RSS > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance computation between one shape and one mesh, specialized for RSS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (ShapeMeshDistanceTraversalNodekIOS< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< kIOS > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance computation between one shape and one mesh, specialized for kIOS type. More...
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (ShapeMeshDistanceTraversalNodeOBBRSS< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< OBBRSS > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 Initialize traversal node for distance computation between one shape and one mesh, specialized for OBBRSS type. More...
 
template<typename BV >
bool initialize (MeshContinuousCollisionTraversalNode< BV > &node, const BVHModel< BV > &model1, const Transform3f &tf1, const BVHModel< BV > &model2, const Transform3f &tf2, const CollisionRequest &request)
 Initialize traversal node for continuous collision detection between two meshes. More...
 
template<typename BV >
bool initialize (MeshConservativeAdvancementTraversalNode< BV > &node, BVHModel< BV > &model1, const Transform3f &tf1, BVHModel< BV > &model2, const Transform3f &tf2, FCL_REAL 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...
 
bool initialize (MeshConservativeAdvancementTraversalNodeRSS &node, const BVHModel< RSS > &model1, const Transform3f &tf1, const BVHModel< RSS > &model2, const Transform3f &tf2, FCL_REAL w=1)
 Initialize traversal node for conservative advancement computation between two meshes, given the current transforms, specialized for RSS. More...
 
bool initialize (MeshConservativeAdvancementTraversalNodeOBBRSS &node, const BVHModel< OBBRSS > &model1, const Transform3f &tf1, const BVHModel< OBBRSS > &model2, const Transform3f &tf2, FCL_REAL w=1)
 
template<typename S1 , typename S2 , typename NarrowPhaseSolver >
bool initialize (ShapeConservativeAdvancementTraversalNode< S1, S2, NarrowPhaseSolver > &node, const S1 &shape1, const Transform3f &tf1, const S2 &shape2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver)
 
template<typename BV , typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeConservativeAdvancementTraversalNode< BV, S, NarrowPhaseSolver > &node, BVHModel< BV > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, FCL_REAL w=1, bool use_refit=false, bool refit_bottomup=false)
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeConservativeAdvancementTraversalNodeRSS< S, NarrowPhaseSolver > &node, const BVHModel< RSS > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, FCL_REAL w=1)
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (MeshShapeConservativeAdvancementTraversalNodeOBBRSS< S, NarrowPhaseSolver > &node, const BVHModel< OBBRSS > &model1, const Transform3f &tf1, const S &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, FCL_REAL w=1)
 
template<typename S , typename BV , typename NarrowPhaseSolver >
bool initialize (ShapeMeshConservativeAdvancementTraversalNode< S, BV, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, BVHModel< BV > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, FCL_REAL w=1, bool use_refit=false, bool refit_bottomup=false)
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (ShapeMeshConservativeAdvancementTraversalNodeRSS< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< RSS > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, FCL_REAL w=1)
 
template<typename S , typename NarrowPhaseSolver >
bool initialize (ShapeMeshConservativeAdvancementTraversalNodeOBBRSS< S, NarrowPhaseSolver > &node, const S &model1, const Transform3f &tf1, const BVHModel< OBBRSS > &model2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, FCL_REAL w=1)
 
void collisionRecurse (CollisionTraversalNodeBase *node, int b1, int b2, BVHFrontList *front_list, FCL_REAL &sqrDistLowerBound)
 Recurse function for collision. More...
 
void collisionRecurse (MeshCollisionTraversalNodeOBB *node, int b1, int b2, const Matrix3f &R, const Vec3f &T, BVHFrontList *front_list)
 Recurse function for collision, specialized for OBB type. More...
 
void collisionRecurse (MeshCollisionTraversalNodeRSS *node, int b1, int b2, const Matrix3f &R, const Vec3f &T, BVHFrontList *front_list)
 Recurse function for collision, specialized for RSS type. More...
 
void selfCollisionRecurse (CollisionTraversalNodeBase *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...
 
void distanceRecurse (DistanceTraversalNodeBase *node, int b1, int b2, BVHFrontList *front_list)
 Recurse function for distance. More...
 
void distanceQueueRecurse (DistanceTraversalNodeBase *node, int b1, int b2, BVHFrontList *front_list, int qsize)
 Recurse function for distance, using queue acceleration. More...
 
void propagateBVHFrontListCollisionRecurse (CollisionTraversalNodeBase *node, BVHFrontList *front_list, FCL_REAL &sqrDistLowerBound)
 Recurse function for front list propagation. More...
 
bool obbDisjointAndLowerBoundDistance (const Matrix3f &B, const Vec3f &T, const Vec3f &a, const Vec3f &b, FCL_REAL &squaredLowerBoundDistance)
 
template<typename T_SH1 , typename T_SH2 , typename NarrowPhaseSolver >
FCL_REAL ShapeShapeDistance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 
template<typename T_SH1 , typename T_SH2 , typename NarrowPhaseSolver >
std::size_t ShapeShapeCollide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
 

Detailed Description

Main namespace.

collision and distance function on traversal nodes. these functions provide a higher level abstraction for collision functions provided in collision_func_matrix

Author
Dalibor Matura, Jia Pan
Jia Pan
Florent Lamiraux

Typedef Documentation

typedef std::list<BVHFrontNode> fcl::BVHFrontList

BVH front list is a list of front nodes.

typedef bool(* fcl::CollisionCallBack)(CollisionObject *o1, CollisionObject *o2, void *cdata)

Callback for collision between two objects. Return value is whether can stop now.

typedef boost::shared_ptr<const CollisionGeometry> fcl::CollisionGeometryConstPtr_t
typedef boost::shared_ptr<CollisionGeometry> fcl::CollisionGeometryPtr_t
typedef boost::shared_ptr< const CollisionObject> fcl::CollisionObjectConstPtr_t
typedef boost::shared_ptr<CollisionObject> fcl::CollisionObjectPtr_t
typedef bool(* fcl::ContinuousCollisionCallBack)(ContinuousCollisionObject *o1, ContinuousCollisionObject *o2, void *cdata)

Callback for continuous collision between two objects. Return value is whether can stop now.

typedef bool(* fcl::ContinuousDistanceCallBack)(ContinuousCollisionObject *o1, ContinuousCollisionObject *o2, void *cdata, FCL_REAL &dist)

Callback for continuous distance between two objects, Return value is whether can stop now, also return the minimum distance till now.

typedef bool(* fcl::DistanceCallBack)(CollisionObject *o1, CollisionObject *o2, void *cdata, FCL_REAL &dist)

Callback for distance between two objects, Return value is whether can stop now, also return the minimum distance till now.

typedef boost::int32_t fcl::FCL_INT32
typedef boost::uint64_t fcl::FCL_INT64
typedef double fcl::FCL_REAL
typedef boost::uint32_t fcl::FCL_UINT32
typedef boost::int64_t fcl::FCL_UINT64
typedef boost::shared_ptr<MotionBase> fcl::MotionBasePtr

Enumeration Type Documentation

States for BVH construction empty->begun->processed ->replace_begun->processed -> ......

| |-> update_begun -> updated -> .....

Enumerator
BVH_BUILD_STATE_EMPTY 
BVH_BUILD_STATE_BEGUN 

empty state, immediately after constructor

BVH_BUILD_STATE_PROCESSED 

after beginModel(), state for adding geometry primitives

BVH_BUILD_STATE_UPDATE_BEGUN 

after tree has been build, ready for cd use

BVH_BUILD_STATE_UPDATED 

after beginUpdateModel(), state for updating geometry primitives

BVH_BUILD_STATE_REPLACE_BEGUN 

after tree has been build for updated geometry, ready for ccd use

BVH model type.

Enumerator
BVH_MODEL_UNKNOWN 
BVH_MODEL_TRIANGLES 

unknown model type

BVH_MODEL_POINTCLOUD 

triangle model

point cloud model

Error code for BVH.

Enumerator
BVH_OK 
BVH_ERR_MODEL_OUT_OF_MEMORY 

BVH is valid.

BVH_ERR_BUILD_OUT_OF_SEQUENCE 

Cannot allocate memory for vertices and triangles.

BVH_ERR_BUILD_EMPTY_MODEL 

BVH construction does not follow correct sequence.

BVH_ERR_BUILD_EMPTY_PREVIOUS_FRAME 

BVH geometry is not prepared.

BVH_ERR_UNSUPPORTED_FUNCTION 

BVH geometry in previous frame is not prepared.

BVH_ERR_UNUPDATED_MODEL 

BVH funtion is not supported.

BVH_ERR_INCORRECT_DATA 

BVH model update failed.

BVH_ERR_UNKNOWN 

BVH data is not valid.

Enumerator
CCDM_TRANS 
CCDM_LINEAR 
CCDM_SCREW 
CCDM_SPLINE 
Enumerator
CCDC_NAIVE 
CCDC_CONSERVATIVE_ADVANCEMENT 
CCDC_RAY_SHOOTING 
CCDC_POLYNOMIAL_SOLVER 

Type of narrow phase GJK solver.

Enumerator
GST_LIBCCD 
GST_INDEP 
Enumerator
LINEAR 
STANDARD 
Enumerator
JT_UNKNOWN 
JT_PRISMATIC 
JT_REVOLUTE 
JT_BALLEULER 
Enumerator
KNN_LINEAR 
KNN_GNAT 
KNN_SQRTAPPROX 

traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, capsule, cone, cylinder, convex, plane, triangle), and octree

Enumerator
BV_UNKNOWN 
BV_AABB 
BV_OBB 
BV_RSS 
BV_kIOS 
BV_OBBRSS 
BV_KDOP16 
BV_KDOP18 
BV_KDOP24 
GEOM_BOX 
GEOM_SPHERE 
GEOM_CAPSULE 
GEOM_CONE 
GEOM_CYLINDER 
GEOM_CONVEX 
GEOM_PLANE 
GEOM_HALFSPACE 
GEOM_TRIANGLE 
GEOM_OCTREE 
NODE_COUNT 

object type: BVH (mesh, points), basic geometry, octree

Enumerator
OT_UNKNOWN 
OT_BVH 
OT_GEOM 
OT_OCTREE 
OT_COUNT 
Enumerator
PDT_TRANSLATIONAL 
PDT_GENERAL_EULER 
PDT_GENERAL_QUAT 
PDT_GENERAL_EULER_BALL 
PDT_GENERAL_QUAT_BALL 

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

Enumerator
SPLIT_METHOD_MEAN 
SPLIT_METHOD_MEDIAN 
SPLIT_METHOD_BV_CENTER 

Function Documentation

template<typename T >
static Vec3fX<T> fcl::abs ( const Vec3fX< T > &  x)
inlinestatic
template<typename T >
Matrix3fX<T> fcl::abs ( const Matrix3fX< T > &  R)

References fcl::Matrix3fX< T >::data.

Referenced by eigen().

IVector3 fcl::bound ( const IVector3 &  i,
const Vec3f &  v 
)
IVector3 fcl::bound ( const IVector3 &  i,
const IVector3 &  v 
)
Interval fcl::bound ( const Interval &  i,
const Interval &  other 
)
template<typename BV >
void fcl::BVHExpand ( BVHModel< BV > &  model,
const Variance3f *  ucs,
FCL_REAL  r 
)

Expand the BVH bounding boxes according to the variance matrix corresponding to the data stored within each BV node.

References fcl::Variance3f::axis, fcl::BVNode< BV >::bv, fcl::BVNodeBase::first_primitive, fcl::BVHModel< BV >::getBV(), fcl::BVNodeBase::num_primitives, fcl::Variance3f::sigma, v, and fcl::BVHModel< BV >::vertices.

void fcl::BVHExpand ( BVHModel< OBB > &  model,
const Variance3f *  ucs,
FCL_REAL  r 
)

Expand the BVH bounding boxes according to the corresponding variance information, for OBB.

void fcl::BVHExpand ( BVHModel< RSS > &  model,
const Variance3f *  ucs,
FCL_REAL  r 
)

Expand the BVH bounding boxes according to the corresponding variance information, for RSS.

void fcl::circumCircleComputation ( const Vec3f &  a,
const Vec3f &  b,
const Vec3f &  c,
Vec3f &  center,
FCL_REAL &  radius 
)

Compute the center and radius for a triangle's circumcircle.

FCL_REAL fcl::collide ( const ContinuousCollisionObject *  o1,
const ContinuousCollisionObject *  o2,
const ContinuousCollisionRequest &  request,
ContinuousCollisionResult &  result 
)
std::size_t fcl::collide ( const CollisionObject *  o1,
const CollisionObject *  o2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Main collision interface: given two collision objects, and the requirements for contacts, including num of max contacts, whether perform exhaustive collision (i.e., returning returning all the contact points), whether return detailed contact information (i.e., normal, contact point, depth; otherwise only contact primitive id is returned), this function performs the collision between them.

Return value is the number of contacts generated between the two objects.

Referenced by fcl::SpatialHashingCollisionManager< HashTable >::collide().

std::size_t fcl::collide ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)
void fcl::collide ( CollisionTraversalNodeBase *  node,
FCL_REAL &  sqrDistLowerBound,
BVHFrontList *  front_list = NULL 
)

collision on collision traversal node

Parameters
nodenode containing both objects to test,
Return values
squaredlower bound to the distance between the objects if they do not collide.
Parameters
front_listlist of nodes visited by the query, can be used to accelerate computation
void fcl::collide2 ( MeshCollisionTraversalNodeOBB *  node,
BVHFrontList *  front_list = NULL 
)

special collision on OBB traversal node

void fcl::collide2 ( MeshCollisionTraversalNodeRSS *  node,
BVHFrontList *  front_list = NULL 
)

special collision on RSS traversal node

void fcl::collisionRecurse ( CollisionTraversalNodeBase *  node,
int  b1,
int  b2,
BVHFrontList *  front_list,
FCL_REAL &  sqrDistLowerBound 
)

Recurse function for collision.

Parameters
nodecollision node,
b1,b2ids of bounding volume nodes for object 1 and object 2
Return values
sqrDistLowerBoundsquared lower bound on distance between objects.
void fcl::collisionRecurse ( MeshCollisionTraversalNodeOBB *  node,
int  b1,
int  b2,
const Matrix3f &  R,
const Vec3f &  T,
BVHFrontList *  front_list 
)

Recurse function for collision, specialized for OBB type.

void fcl::collisionRecurse ( MeshCollisionTraversalNodeRSS *  node,
int  b1,
int  b2,
const Matrix3f &  R,
const Vec3f &  T,
BVHFrontList *  front_list 
)

Recurse function for collision, specialized for RSS type.

template<typename T , std::size_t N, std::size_t M>
Vec_n<T, M+N> fcl::combine ( const Vec_n< T, N > &  v1,
const Vec_n< T, M > &  v2 
)

References v.

template<typename BV , typename S >
void fcl::computeBV ( const S &  s,
const Transform3f &  tf,
BV &  bv 
)

calculate a bounding volume for a shape in a specific configuration

References fit().

Referenced by initialize(), and fcl::details::setupShapeMeshDistanceOrientedNode().

template<>
void fcl::computeBV< AABB, Box > ( const Box &  s,
const Transform3f &  tf,
AABB &  bv 
)
template<>
void fcl::computeBV< AABB, Capsule > ( const Capsule &  s,
const Transform3f &  tf,
AABB &  bv 
)
template<>
void fcl::computeBV< AABB, Cone > ( const Cone &  s,
const Transform3f &  tf,
AABB &  bv 
)
template<>
void fcl::computeBV< AABB, Convex > ( const Convex &  s,
const Transform3f &  tf,
AABB &  bv 
)
template<>
void fcl::computeBV< AABB, Cylinder > ( const Cylinder &  s,
const Transform3f &  tf,
AABB &  bv 
)
template<>
void fcl::computeBV< AABB, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
AABB &  bv 
)
template<>
void fcl::computeBV< AABB, Plane > ( const Plane &  s,
const Transform3f &  tf,
AABB &  bv 
)
template<>
void fcl::computeBV< AABB, Sphere > ( const Sphere &  s,
const Transform3f &  tf,
AABB &  bv 
)
template<>
void fcl::computeBV< AABB, TriangleP > ( const TriangleP &  s,
const Transform3f &  tf,
AABB &  bv 
)
template<>
void fcl::computeBV< KDOP< 16 >, Plane > ( const Plane &  s,
const Transform3f &  tf,
KDOP< 16 > &  bv 
)
template<>
void fcl::computeBV< KDOP< 18 >, Plane > ( const Plane &  s,
const Transform3f &  tf,
KDOP< 18 > &  bv 
)
template<>
void fcl::computeBV< KDOP< 24 >, Plane > ( const Plane &  s,
const Transform3f &  tf,
KDOP< 24 > &  bv 
)
template<>
void fcl::computeBV< kIOS, Plane > ( const Plane &  s,
const Transform3f &  tf,
kIOS &  bv 
)
template<>
void fcl::computeBV< OBB, Box > ( const Box &  s,
const Transform3f &  tf,
OBB &  bv 
)
template<>
void fcl::computeBV< OBB, Capsule > ( const Capsule &  s,
const Transform3f &  tf,
OBB &  bv 
)
template<>
void fcl::computeBV< OBB, Cone > ( const Cone &  s,
const Transform3f &  tf,
OBB &  bv 
)
template<>
void fcl::computeBV< OBB, Convex > ( const Convex &  s,
const Transform3f &  tf,
OBB &  bv 
)
template<>
void fcl::computeBV< OBB, Cylinder > ( const Cylinder &  s,
const Transform3f &  tf,
OBB &  bv 
)
template<>
void fcl::computeBV< OBB, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
OBB &  bv 
)
template<>
void fcl::computeBV< OBB, Plane > ( const Plane &  s,
const Transform3f &  tf,
OBB &  bv 
)
template<>
void fcl::computeBV< OBB, Sphere > ( const Sphere &  s,
const Transform3f &  tf,
OBB &  bv 
)
template<>
void fcl::computeBV< OBBRSS, Plane > ( const Plane &  s,
const Transform3f &  tf,
OBBRSS &  bv 
)
template<>
void fcl::computeBV< RSS, Plane > ( const Plane &  s,
const Transform3f &  tf,
RSS &  bv 
)
static void fcl::computeChildBV ( const AABB &  root_bv,
unsigned int  i,
AABB &  child_bv 
)
inlinestatic

compute the bounding volume of an octree node's i-th child

References fcl::AABB::max_, and fcl::AABB::min_.

template<std::size_t N>
Scaler<N> fcl::computeScaler ( const std::vector< Item< N > > &  data)

References fcl::details::max().

template<std::size_t N>
Scaler<N> fcl::computeScaler ( const std::vector< Vecnf< N > > &  data)

References fcl::details::max().

Quaternion3f fcl::conj ( const Quaternion3f &  q)

conjugate of quaternion

Referenced by fcl::Transform3f::inverseTimes().

void fcl::constructBox ( const AABB &  bv,
Box &  box,
Transform3f &  tf 
)

construct a box shape (with a configuration) from a given bounding volume

void fcl::constructBox ( const OBB &  bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const OBBRSS &  bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const kIOS &  bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const RSS &  bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const KDOP< 16 > &  bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const KDOP< 18 > &  bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const KDOP< 24 > &  bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const AABB &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const OBB &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const OBBRSS &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const kIOS &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const RSS &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const KDOP< 16 > &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const KDOP< 18 > &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)
void fcl::constructBox ( const KDOP< 24 > &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)
FCL_REAL fcl::continuousCollide ( const CollisionGeometry *  o1,
const Transform3f &  tf1_beg,
const Transform3f &  tf1_end,
const CollisionGeometry *  o2,
const Transform3f &  tf2_beg,
const Transform3f &  tf2_end,
const ContinuousCollisionRequest &  request,
ContinuousCollisionResult &  result 
)

continous collision checking between two objects

FCL_REAL fcl::continuousCollide ( const CollisionObject *  o1,
const Transform3f &  tf1_end,
const CollisionObject *  o2,
const Transform3f &  tf2_end,
const ContinuousCollisionRequest &  request,
ContinuousCollisionResult &  result 
)
template<typename BV1 , typename BV2 >
static void fcl::convertBV ( const BV1 &  bv1,
const Transform3f &  tf1,
BV2 &  bv2 
)
inlinestatic

Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity configuration.

Referenced by fcl::OcTreeSolver< NarrowPhaseSolver >::OcTreeShapeIntersect(), and fcl::OcTreeSolver< NarrowPhaseSolver >::ShapeOcTreeIntersect().

FCL_REAL fcl::distance ( const CollisionObject *  o1,
const CollisionObject *  o2,
const DistanceRequest &  request,
DistanceResult &  result 
)

Main distance interface: given two collision objects, and the requirements for contacts, including whether return the nearest points, this function performs the distance between them.

Return value is the minimum distance generated between the two objects.

FCL_REAL fcl::distance ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const DistanceRequest &  request,
DistanceResult &  result 
)
void fcl::distance ( DistanceTraversalNodeBase *  node,
BVHFrontList *  front_list = NULL,
int  qsize = 2 
)

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

FCL_REAL fcl::distance ( const Matrix3f &  R0,
const Vec3f &  T0,
const RSS &  b1,
const RSS &  b2,
Vec3f *  P = NULL,
Vec3f *  Q = NULL 
)

distance between two RSS bounding volumes P and Q (optional return values) are the closest points in the rectangles, not the RSS.

But the direction P - Q is the correct direction for cloest points Notice that P and Q are both in the local frame of the first RSS (not global frame and not even the local frame of object 1)

FCL_REAL fcl::distance ( const Matrix3f &  R0,
const Vec3f &  T0,
const kIOS &  b1,
const kIOS &  b2,
Vec3f *  P = NULL,
Vec3f *  Q = NULL 
)
FCL_REAL fcl::distance ( const Matrix3f &  R0,
const Vec3f &  T0,
const OBBRSS &  b1,
const OBBRSS &  b2,
Vec3f *  P = NULL,
Vec3f *  Q = NULL 
)

Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not NULL, returns the nearest points.

void fcl::distanceQueueRecurse ( DistanceTraversalNodeBase *  node,
int  b1,
int  b2,
BVHFrontList *  front_list,
int  qsize 
)

Recurse function for distance, using queue acceleration.

void fcl::distanceRecurse ( DistanceTraversalNodeBase *  node,
int  b1,
int  b2,
BVHFrontList *  front_list 
)

Recurse function for distance.

template<typename T >
void fcl::eigen ( const Matrix3fX< T > &  m,
typename T::meta_type  dout[3],
Vec3fX< typename T::vector_type >  vout[3] 
)

compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors

References abs(), fcl::Vec3fX< T >::setValue(), and v.

Referenced by fcl::Variance3f::init().

template<typename BV >
void fcl::fit ( Vec3f *  ps,
int  n,
BV &  bv 
)

Compute a bounding volume that fits a set of n points.

Referenced by computeBV().

template<>
void fcl::fit< kIOS > ( Vec3f *  ps,
int  n,
kIOS &  bv 
)
template<>
void fcl::fit< OBB > ( Vec3f *  ps,
int  n,
OBB &  bv 
)
template<>
void fcl::fit< OBBRSS > ( Vec3f *  ps,
int  n,
OBBRSS &  bv 
)
template<>
void fcl::fit< RSS > ( Vec3f *  ps,
int  n,
RSS &  bv 
)
static bool fcl::four_AABBs_intersect_and ( const Vec3f &  min1,
const Vec3f &  max1,
const Vec3f &  min2,
const Vec3f &  max2,
const Vec3f &  min3,
const Vec3f &  max3,
const Vec3f &  min4,
const Vec3f &  max4,
const Vec3f &  min5,
const Vec3f &  max5,
const Vec3f &  min6,
const Vec3f &  max6,
const Vec3f &  min7,
const Vec3f &  max7,
const Vec3f &  min8,
const Vec3f &  max8 
)
static

four AABBs versus four AABBs SIMD test

static bool fcl::four_AABBs_intersect_or ( const Vec3f &  min1,
const Vec3f &  max1,
const Vec3f &  min2,
const Vec3f &  max2,
const Vec3f &  min3,
const Vec3f &  max3,
const Vec3f &  min4,
const Vec3f &  max4,
const Vec3f &  min5,
const Vec3f &  max5,
const Vec3f &  min6,
const Vec3f &  max6,
const Vec3f &  min7,
const Vec3f &  max7,
const Vec3f &  min8,
const Vec3f &  max8 
)
static
static bool fcl::four_spheres_four_AABBs_intersect_and ( const Vec3f &  o1,
FCL_REAL  r1,
const Vec3f &  o2,
FCL_REAL  r2,
const Vec3f &  o3,
FCL_REAL  r3,
const Vec3f &  o4,
FCL_REAL  r4,
const Vec3f &  min1,
const Vec3f &  max1,
const Vec3f &  min2,
const Vec3f &  max2,
const Vec3f &  min3,
const Vec3f &  max3,
const Vec3f &  min4,
const Vec3f &  max4 
)
static

four spheres versus four AABBs SIMD test

static bool fcl::four_spheres_four_AABBs_intersect_or ( const Vec3f &  o1,
FCL_REAL  r1,
const Vec3f &  o2,
FCL_REAL  r2,
const Vec3f &  o3,
FCL_REAL  r3,
const Vec3f &  o4,
FCL_REAL  r4,
const Vec3f &  min1,
const Vec3f &  max1,
const Vec3f &  min2,
const Vec3f &  max2,
const Vec3f &  min3,
const Vec3f &  max3,
const Vec3f &  min4,
const Vec3f &  max4 
)
static
static bool fcl::four_spheres_intersect_and ( const Vec3f &  o1,
FCL_REAL  r1,
const Vec3f &  o2,
FCL_REAL  r2,
const Vec3f &  o3,
FCL_REAL  r3,
const Vec3f &  o4,
FCL_REAL  r4,
const Vec3f &  o5,
FCL_REAL  r5,
const Vec3f &  o6,
FCL_REAL  r6,
const Vec3f &  o7,
FCL_REAL  r7,
const Vec3f &  o8,
FCL_REAL  r8 
)
static
static bool fcl::four_spheres_intersect_or ( const Vec3f &  o1,
FCL_REAL  r1,
const Vec3f &  o2,
FCL_REAL  r2,
const Vec3f &  o3,
FCL_REAL  r3,
const Vec3f &  o4,
FCL_REAL  r4,
const Vec3f &  o5,
FCL_REAL  r5,
const Vec3f &  o6,
FCL_REAL  r6,
const Vec3f &  o7,
FCL_REAL  r7,
const Vec3f &  o8,
FCL_REAL  r8 
)
static
template<typename BV >
void fcl::generateBVHModel ( BVHModel< BV > &  model,
const Box &  shape,
const Transform3f &  pose 
)
template<typename BV >
void fcl::generateBVHModel ( BVHModel< BV > &  model,
const Sphere &  shape,
const Transform3f &  pose,
unsigned int  seg,
unsigned int  ring 
)

Generate BVH model from sphere, given the number of segments along longitude and number of rings along latitude.

References fcl::BVHModel< BV >::addSubModel(), fcl::BVHModel< BV >::beginModel(), fcl::BVHModel< BV >::computeLocalAABB(), fcl::BVHModel< BV >::endModel(), fcl::Sphere::radius, and fcl::Transform3f::transform().

template<typename BV >
void fcl::generateBVHModel ( BVHModel< BV > &  model,
const Sphere &  shape,
const Transform3f &  pose,
unsigned int  n_faces_for_unit_sphere 
)

Generate BVH model from sphere The difference between generateBVHModel is that it gives the number of triangles faces N for a sphere with unit radius.

For sphere of radius r, then the number of triangles is r * r * N so that the area represented by a single triangle is approximately the same.s

References generateBVHModel(), and fcl::Sphere::radius.

template<typename BV >
void fcl::generateBVHModel ( BVHModel< BV > &  model,
const Cylinder &  shape,
const Transform3f &  pose,
unsigned int  tot,
unsigned int  h_num 
)

Generate BVH model from cylinder, given the number of segments along circle and the number of segments along axis.

References fcl::BVHModel< BV >::addSubModel(), fcl::BVHModel< BV >::beginModel(), fcl::BVHModel< BV >::computeLocalAABB(), fcl::BVHModel< BV >::endModel(), fcl::Cylinder::lz, fcl::Cylinder::radius, and fcl::Transform3f::transform().

template<typename BV >
void fcl::generateBVHModel ( BVHModel< BV > &  model,
const Cylinder &  shape,
const Transform3f &  pose,
unsigned int  tot_for_unit_cylinder 
)

Generate BVH model from cylinder Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius.

For cylinder with larger radius, the number of circle split number is r * tot.

References generateBVHModel(), fcl::Cylinder::lz, and fcl::Cylinder::radius.

template<typename BV >
void fcl::generateBVHModel ( BVHModel< BV > &  model,
const Cone &  shape,
const Transform3f &  pose,
unsigned int  tot,
unsigned int  h_num 
)

Generate BVH model from cone, given the number of segments along circle and the number of segments along axis.

References fcl::BVHModel< BV >::addSubModel(), fcl::BVHModel< BV >::beginModel(), fcl::BVHModel< BV >::computeLocalAABB(), fcl::BVHModel< BV >::endModel(), fcl::Cone::lz, fcl::Cone::radius, and fcl::Transform3f::transform().

template<typename BV >
void fcl::generateBVHModel ( BVHModel< BV > &  model,
const Cone &  shape,
const Transform3f &  pose,
unsigned int  tot_for_unit_cone 
)

Generate BVH model from cone Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius.

For cone with larger radius, the number of circle split number is r * tot.

References generateBVHModel(), fcl::Cone::lz, and fcl::Cone::radius.

template<typename T >
void fcl::generateCoordinateSystem ( const Vec3fX< T > &  w,
Vec3fX< T > &  u,
Vec3fX< T > &  v 
)

References abs().

void fcl::generateTaylorModelForCosFunc ( TaylorModel &  tm,
FCL_REAL  w,
FCL_REAL  q0 
)

Generate Taylor model for cos(w t + q0)

Referenced by fcl::ScrewMotion::getTaylorModel(), and fcl::InterpMotion::getTaylorModel().

void fcl::generateTaylorModelForLinearFunc ( TaylorModel &  tm,
FCL_REAL  p,
FCL_REAL  v 
)

Generate Taylor model for p + v t.

Referenced by fcl::ScrewMotion::getTaylorModel(), and fcl::InterpMotion::getTaylorModel().

void fcl::generateTaylorModelForSinFunc ( TaylorModel &  tm,
FCL_REAL  w,
FCL_REAL  q0 
)

Generate Taylor model for sin(w t + q0)

Referenced by fcl::ScrewMotion::getTaylorModel(), and fcl::InterpMotion::getTaylorModel().

void fcl::generateTVector3ForLinearFunc ( TVector3 &  v,
const Vec3f &  position,
const Vec3f &  velocity 
)
void fcl::getCovariance ( Vec3f *  ps,
Vec3f *  ps2,
Triangle *  ts,
unsigned int *  indices,
int  n,
Matrix3f &  M 
)

Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to points directly; otherwise refer to triangles.

void fcl::getExtentAndCenter ( Vec3f *  ps,
Vec3f *  ps2,
Triangle *  ts,
unsigned int *  indices,
int  n,
Vec3f  axis[3],
Vec3f &  center,
Vec3f &  extent 
)

Compute the bounding volume extent and center for a set or subset of points, given the BV axises.

void fcl::getRadiusAndOriginAndRectangleSize ( Vec3f *  ps,
Vec3f *  ps2,
Triangle *  ts,
unsigned int *  indices,
int  n,
Vec3f  axis[3],
Vec3f &  origin,
FCL_REAL  l[2],
FCL_REAL &  r 
)

Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises.

template<typename T >
void fcl::hat ( Matrix3fX< T > &  mat,
const Vec3fX< typename T::vector_type > &  vec 
)
template<typename S1 , typename S2 , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeCollisionTraversalNode< S1, S2, NarrowPhaseSolver > &  node,
const S1 &  shape1,
const Transform3f &  tf1,
const S2 &  shape2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)
template<typename BV , typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeCollisionTraversalNode< BV, S, NarrowPhaseSolver > &  node,
BVHModel< BV > &  model1,
Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result,
bool  use_refit = false,
bool  refit_bottomup = false 
)
template<typename S , typename BV , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshCollisionTraversalNode< S, BV, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
BVHModel< BV > &  model2,
Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result,
bool  use_refit = false,
bool  refit_bottomup = false 
)
template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeCollisionTraversalNodeOBB< S, NarrowPhaseSolver > &  node,
const BVHModel< OBB > &  model1,
const Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize the traversal node for collision between one mesh and one shape, specialized for OBB type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeCollisionTraversalNodeRSS< S, NarrowPhaseSolver > &  node,
const BVHModel< RSS > &  model1,
const Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize the traversal node for collision between one mesh and one shape, specialized for RSS type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeCollisionTraversalNodekIOS< S, NarrowPhaseSolver > &  node,
const BVHModel< kIOS > &  model1,
const Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize the traversal node for collision between one mesh and one shape, specialized for kIOS type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeCollisionTraversalNodeOBBRSS< S, NarrowPhaseSolver > &  node,
const BVHModel< OBBRSS > &  model1,
const Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshCollisionTraversalNodeOBB< S, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
const BVHModel< OBB > &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize the traversal node for collision between one mesh and one shape, specialized for OBB type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshCollisionTraversalNodeRSS< S, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
const BVHModel< RSS > &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize the traversal node for collision between one mesh and one shape, specialized for RSS type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshCollisionTraversalNodekIOS< S, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
const BVHModel< kIOS > &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize the traversal node for collision between one mesh and one shape, specialized for kIOS type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshCollisionTraversalNodeOBBRSS< S, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
const BVHModel< OBBRSS > &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS type.

bool fcl::initialize ( MeshCollisionTraversalNodeOBB &  node,
const BVHModel< OBB > &  model1,
const Transform3f &  tf1,
const BVHModel< OBB > &  model2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize traversal node for collision between two meshes, specialized for OBB type.

bool fcl::initialize ( MeshCollisionTraversalNodeRSS &  node,
const BVHModel< RSS > &  model1,
const Transform3f &  tf1,
const BVHModel< RSS > &  model2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize traversal node for collision between two meshes, specialized for RSS type.

bool fcl::initialize ( MeshCollisionTraversalNodeOBBRSS &  node,
const BVHModel< OBBRSS > &  model1,
const Transform3f &  tf1,
const BVHModel< OBBRSS > &  model2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize traversal node for collision between two meshes, specialized for OBBRSS type.

bool fcl::initialize ( MeshCollisionTraversalNodekIOS &  node,
const BVHModel< kIOS > &  model1,
const Transform3f &  tf1,
const BVHModel< kIOS > &  model2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Initialize traversal node for collision between two meshes, specialized for kIOS type.

template<typename S1 , typename S2 , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeDistanceTraversalNode< S1, S2, NarrowPhaseSolver > &  node,
const S1 &  shape1,
const Transform3f &  tf1,
const S2 &  shape2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)
bool fcl::initialize ( MeshDistanceTraversalNodeRSS &  node,
const BVHModel< RSS > &  model1,
const Transform3f &  tf1,
const BVHModel< RSS > &  model2,
const Transform3f &  tf2,
const DistanceRequest &  request,
DistanceResult &  result 
)

Initialize traversal node for distance computation between two meshes, specialized for RSS type.

bool fcl::initialize ( MeshDistanceTraversalNodekIOS &  node,
const BVHModel< kIOS > &  model1,
const Transform3f &  tf1,
const BVHModel< kIOS > &  model2,
const Transform3f &  tf2,
const DistanceRequest &  request,
DistanceResult &  result 
)

Initialize traversal node for distance computation between two meshes, specialized for kIOS type.

bool fcl::initialize ( MeshDistanceTraversalNodeOBBRSS &  node,
const BVHModel< OBBRSS > &  model1,
const Transform3f &  tf1,
const BVHModel< OBBRSS > &  model2,
const Transform3f &  tf2,
const DistanceRequest &  request,
DistanceResult &  result 
)

Initialize traversal node for distance computation between two meshes, specialized for OBBRSS type.

template<typename BV , typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeDistanceTraversalNode< BV, S, NarrowPhaseSolver > &  node,
BVHModel< BV > &  model1,
Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result,
bool  use_refit = false,
bool  refit_bottomup = false 
)
template<typename S , typename BV , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshDistanceTraversalNode< S, BV, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
BVHModel< BV > &  model2,
Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result,
bool  use_refit = false,
bool  refit_bottomup = false 
)
template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeDistanceTraversalNodeRSS< S, NarrowPhaseSolver > &  node,
const BVHModel< RSS > &  model1,
const Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)

Initialize traversal node for distance computation between one mesh and one shape, specialized for RSS type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeDistanceTraversalNodekIOS< S, NarrowPhaseSolver > &  node,
const BVHModel< kIOS > &  model1,
const Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)

Initialize traversal node for distance computation between one mesh and one shape, specialized for kIOS type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeDistanceTraversalNodeOBBRSS< S, NarrowPhaseSolver > &  node,
const BVHModel< OBBRSS > &  model1,
const Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)

Initialize traversal node for distance computation between one mesh and one shape, specialized for OBBRSS type.

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshDistanceTraversalNodeRSS< S, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
const BVHModel< RSS > &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)

Initialize traversal node for distance computation between one shape and one mesh, specialized for RSS type.

References fcl::details::setupShapeMeshDistanceOrientedNode().

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshDistanceTraversalNodekIOS< S, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
const BVHModel< kIOS > &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)

Initialize traversal node for distance computation between one shape and one mesh, specialized for kIOS type.

References fcl::details::setupShapeMeshDistanceOrientedNode().

template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshDistanceTraversalNodeOBBRSS< S, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
const BVHModel< OBBRSS > &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)

Initialize traversal node for distance computation between one shape and one mesh, specialized for OBBRSS type.

References fcl::details::setupShapeMeshDistanceOrientedNode().

template<typename BV >
bool fcl::initialize ( MeshConservativeAdvancementTraversalNode< BV > &  node,
BVHModel< BV > &  model1,
const Transform3f &  tf1,
BVHModel< BV > &  model2,
const Transform3f &  tf2,
FCL_REAL  w = 1,
bool  use_refit = false,
bool  refit_bottomup = false 
)
bool fcl::initialize ( MeshConservativeAdvancementTraversalNodeRSS &  node,
const BVHModel< RSS > &  model1,
const Transform3f &  tf1,
const BVHModel< RSS > &  model2,
const Transform3f &  tf2,
FCL_REAL  w = 1 
)

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

bool fcl::initialize ( MeshConservativeAdvancementTraversalNodeOBBRSS &  node,
const BVHModel< OBBRSS > &  model1,
const Transform3f &  tf1,
const BVHModel< OBBRSS > &  model2,
const Transform3f &  tf2,
FCL_REAL  w = 1 
)
template<typename S1 , typename S2 , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeConservativeAdvancementTraversalNode< S1, S2, NarrowPhaseSolver > &  node,
const S1 &  shape1,
const Transform3f &  tf1,
const S2 &  shape2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver 
)
template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeConservativeAdvancementTraversalNodeRSS< S, NarrowPhaseSolver > &  node,
const BVHModel< RSS > &  model1,
const Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
FCL_REAL  w = 1 
)
template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( MeshShapeConservativeAdvancementTraversalNodeOBBRSS< S, NarrowPhaseSolver > &  node,
const BVHModel< OBBRSS > &  model1,
const Transform3f &  tf1,
const S &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
FCL_REAL  w = 1 
)
template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshConservativeAdvancementTraversalNodeRSS< S, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
const BVHModel< RSS > &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
FCL_REAL  w = 1 
)
template<typename S , typename NarrowPhaseSolver >
bool fcl::initialize ( ShapeMeshConservativeAdvancementTraversalNodeOBBRSS< S, NarrowPhaseSolver > &  node,
const S &  model1,
const Transform3f &  tf1,
const BVHModel< OBBRSS > &  model2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
FCL_REAL  w = 1 
)
Quaternion3f fcl::inverse ( const Quaternion3f &  q)

inverse of quaternion

Transform3f fcl::inverse ( const Transform3f &  tf)

inverse the transform

template<typename T >
static Vec3fX<T> fcl::max ( const Vec3fX< T > &  x,
const Vec3fX< T > &  y 
)
inlinestatic
FCL_REAL fcl::maximumDistance ( Vec3f *  ps,
Vec3f *  ps2,
Triangle *  ts,
unsigned int *  indices,
int  n,
const Vec3f &  query 
)

Compute the maximum distance from a given center point to a point cloud.

template<typename T >
static Vec3fX<T> fcl::min ( const Vec3fX< T > &  x,
const Vec3fX< T > &  y 
)
inlinestatic
template<typename BV >
bool fcl::nodeBaseLess ( NodeBase< BV > *  a,
NodeBase< BV > *  b,
int  d 
)

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

References fcl::NodeBase< BV >::bv.

template<typename T >
static Vec3fX<T> fcl::normalize ( const Vec3fX< T > &  v)
inlinestatic
bool fcl::obbDisjoint ( const Matrix3f &  B,
const Vec3f &  T,
const Vec3f &  a,
const Vec3f &  b 
)

Check collision between two boxes.

Parameters
B,Torientation and position of first box,
ahalf dimensions of first box,
bhalf dimensions of second box. The second box is in identity configuration.
bool fcl::obbDisjointAndLowerBoundDistance ( const Matrix3f &  B,
const Vec3f &  T,
const Vec3f &  a,
const Vec3f &  b,
FCL_REAL &  squaredLowerBoundDistance 
)
TVector3 fcl::operator* ( const Vec3f &  v,
const TaylorModel &  a 
)
TMatrix3 fcl::operator* ( const Matrix3f &  m,
const TaylorModel &  a 
)
TMatrix3 fcl::operator* ( const TaylorModel &  a,
const Matrix3f &  m 
)
TMatrix3 fcl::operator* ( const TaylorModel &  a,
const TMatrix3 &  m 
)
TMatrix3 fcl::operator* ( FCL_REAL  d,
const TMatrix3 &  m 
)
TaylorModel fcl::operator* ( FCL_REAL  d,
const TaylorModel &  a 
)
template<typename T , std::size_t N>
Vec_n<T, N> fcl::operator* ( t,
const Vec_n< T, N > &  v 
)
template<typename T >
Vec3fX<T> fcl::operator* ( const typename Vec3fX< T >::U &  t,
const Vec3fX< T > &  v 
)
inline
TVector3 fcl::operator+ ( const Vec3f &  v1,
const TVector3 &  v2 
)
TMatrix3 fcl::operator+ ( const Matrix3f &  m1,
const TMatrix3 &  m2 
)
TaylorModel fcl::operator+ ( FCL_REAL  d,
const TaylorModel &  a 
)
TVector3 fcl::operator- ( const Vec3f &  v1,
const TVector3 &  v2 
)
TMatrix3 fcl::operator- ( const Matrix3f &  m1,
const TMatrix3 &  m2 
)
TaylorModel fcl::operator- ( FCL_REAL  d,
const TaylorModel &  a 
)
template<typename T >
std::ostream& fcl::operator<< ( std::ostream &  out,
const Vec3fX< T > &  x 
)
template<typename T , std::size_t N>
std::ostream& fcl::operator<< ( std::ostream &  o,
const Vec_n< T, N > &  v 
)

References v.

static std::ostream& fcl::operator<< ( std::ostream &  o,
const Vec3f &  v 
)
inlinestatic
static std::ostream& fcl::operator<< ( std::ostream &  o,
const Matrix3f &  m 
)
inlinestatic
bool fcl::overlap ( const Matrix3f &  R0,
const Vec3f &  T0,
const OBB &  b1,
const OBB &  b2 
)

Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity.

bool fcl::overlap ( const Matrix3f &  R0,
const Vec3f &  T0,
const OBB &  b1,
const OBB &  b2,
FCL_REAL &  sqrDistLowerBound 
)

Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity.

bool fcl::overlap ( const Matrix3f &  R0,
const Vec3f &  T0,
const RSS &  b1,
const RSS &  b2 
)

Check collision between two RSSs, b1 is in configuration (R0, T0) and b2 is in identity.

bool fcl::overlap ( const Matrix3f &  R0,
const Vec3f &  T0,
const OBBRSS &  b1,
const OBBRSS &  b2 
)

Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity.

bool fcl::overlap ( const Matrix3f &  R0,
const Vec3f &  T0,
const OBBRSS &  b1,
const OBBRSS &  b2,
FCL_REAL &  sqrDistLowerBound 
)

Check collision between two OBBRSS.

Parameters
b1first OBBRSS in configuration (R0, T0)
b2second OBBRSS in identity position
Return values
squaredlower bound on the distance if OBBRSS do not overlap.
void fcl::propagateBVHFrontListCollisionRecurse ( CollisionTraversalNodeBase *  node,
BVHFrontList *  front_list,
FCL_REAL &  sqrDistLowerBound 
)

Recurse function for front list propagation.

template<typename T >
T::meta_type fcl::quadraticForm ( const Matrix3fX< T > &  R,
const Vec3fX< typename T::vector_type > &  v 
)
template<typename T >
void fcl::relativeTransform ( const Matrix3fX< T > &  R1,
const Vec3fX< typename T::vector_type > &  t1,
const Matrix3fX< T > &  R2,
const Vec3fX< typename T::vector_type > &  t2,
Matrix3fX< T > &  R,
Vec3fX< typename T::vector_type > &  t 
)
void fcl::relativeTransform ( const Transform3f &  tf1,
const Transform3f &  tf2,
Transform3f &  tf 
)

compute the relative transform between two transforms: tf2 = tf1 * tf (relative to the local coordinate system in tf1)

void fcl::relativeTransform2 ( const Transform3f &  tf1,
const Transform3f &  tf2,
Transform3f &  tf 
)

compute the relative transform between two transforms: tf2 = tf * tf1 (relative to the global coordinate system)

template<typename T1 , std::size_t N1, typename T2 , std::size_t N2>
void fcl::repack ( const Vec_n< T1, N1 > &  input,
Vec_n< T2, N2 > &  output 
)

References fcl::details::min().

IMatrix3 fcl::rotationConstrain ( const IMatrix3 &  m)
TMatrix3 fcl::rotationConstrain ( const TMatrix3 &  m)
template<typename BV >
size_t fcl::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

template<>
size_t fcl::select ( const NodeBase< AABB > &  node,
const NodeBase< AABB > &  node1,
const NodeBase< AABB > &  node2 
)
template<typename BV >
size_t fcl::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

template<>
size_t fcl::select ( const AABB &  query,
const NodeBase< AABB > &  node1,
const NodeBase< AABB > &  node2 
)
void fcl::selfCollide ( CollisionTraversalNodeBase *  node,
BVHFrontList *  front_list = NULL 
)

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

void fcl::selfCollisionRecurse ( CollisionTraversalNodeBase *  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.

template<typename T_SH1 , typename T_SH2 , typename NarrowPhaseSolver >
std::size_t fcl::ShapeShapeCollide ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)
template<typename T_SH1 , typename T_SH2 , typename NarrowPhaseSolver >
FCL_REAL fcl::ShapeShapeDistance ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)
static __m128 fcl::sse_four_AABBs_intersect ( const Vec3f &  min1,
const Vec3f &  max1,
const Vec3f &  min2,
const Vec3f &  max2,
const Vec3f &  min3,
const Vec3f &  max3,
const Vec3f &  min4,
const Vec3f &  max4,
const Vec3f &  min5,
const Vec3f &  max5,
const Vec3f &  min6,
const Vec3f &  max6,
const Vec3f &  min7,
const Vec3f &  max7,
const Vec3f &  min8,
const Vec3f &  max8 
)
inlinestatic
static __m128 fcl::sse_four_spheres_four_AABBs_intersect ( const Vec3f &  o1,
FCL_REAL  r1,
const Vec3f &  o2,
FCL_REAL  r2,
const Vec3f &  o3,
FCL_REAL  r3,
const Vec3f &  o4,
FCL_REAL  r4,
const Vec3f &  min1,
const Vec3f &  max1,
const Vec3f &  min2,
const Vec3f &  max2,
const Vec3f &  min3,
const Vec3f &  max3,
const Vec3f &  min4,
const Vec3f &  max4 
)
inlinestatic
static __m128 fcl::sse_four_spheres_intersect ( const Vec3f &  o1,
FCL_REAL  r1,
const Vec3f &  o2,
FCL_REAL  r2,
const Vec3f &  o3,
FCL_REAL  r3,
const Vec3f &  o4,
FCL_REAL  r4,
const Vec3f &  o5,
FCL_REAL  r5,
const Vec3f &  o6,
FCL_REAL  r6,
const Vec3f &  o7,
FCL_REAL  r7,
const Vec3f &  o8,
FCL_REAL  r8 
)
inlinestatic
Halfspace fcl::transform ( const Halfspace &  a,
const Transform3f &  tf 
)
Plane fcl::transform ( const Plane &  a,
const Transform3f &  tf 
)
OBB fcl::translate ( const OBB &  bv,
const Vec3f &  t 
)

Translate the OBB bv.

RSS fcl::translate ( const RSS &  bv,
const Vec3f &  t 
)

Translate the RSS bv.

kIOS fcl::translate ( const kIOS &  bv,
const Vec3f &  t 
)

Translate the kIOS BV.

OBBRSS fcl::translate ( const OBBRSS &  bv,
const Vec3f &  t 
)

Translate the OBBRSS bv.

template<size_t N>
KDOP<N> fcl::translate ( const KDOP< N > &  bv,
const Vec3f &  t 
)

translate the KDOP BV

static AABB fcl::translate ( const AABB &  aabb,
const Vec3f &  t 
)
inlinestatic

translate the center of AABB by t

References fcl::AABB::max_, and fcl::AABB::min_.

Referenced by fcl::CollisionObject::computeAABB().

template<typename T >
Matrix3fX<T> fcl::transpose ( const Matrix3fX< T > &  R)
template<typename T >
static T::meta_type fcl::triple ( const Vec3fX< T > &  x,
const Vec3fX< T > &  y,
const Vec3fX< T > &  z 
)
inlinestatic
void fcl::updateFrontList ( BVHFrontList *  front_list,
int  b1,
int  b2 
)
inline

Add new front node into the front list.