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

Main namespace. More...

Namespaces

namespace  details
 

FCL internals. Ignore this :) unless you are God.


namespace  implementation_array
namespace  kIOS_fit_functions
namespace  OBB_fit_functions
namespace  OBBRSS_fit_functions
namespace  RSS_fit_functions
namespace  time
 

Namespace containing time datatypes and time operations.


namespace  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  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. The front list reflects the subset of a BVTT that is traversed for that particular proximity query. 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...
struct  BVHShapeCollider
struct  BVHShapeCollider< kIOS, T_SH, NarrowPhaseSolver >
struct  BVHShapeCollider< OBB, T_SH, NarrowPhaseSolver >
struct  BVHShapeCollider< OBBRSS, T_SH, NarrowPhaseSolver >
struct  BVHShapeCollider< RSS, T_SH, NarrowPhaseSolver >
class  BVHShapeCollisionTraversalNode
 Traversal node for collision between BVH and shape. More...
struct  BVHShapeDistancer
struct  BVHShapeDistancer< kIOS, T_SH, NarrowPhaseSolver >
struct  BVHShapeDistancer< OBBRSS, T_SH, NarrowPhaseSolver >
struct  BVHShapeDistancer< RSS, T_SH, NarrowPhaseSolver >
class  BVHShapeDistanceTraversalNode
 Traversal node for distance computation between BVH and shape. 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...
struct  BVT
 Bounding volume test structure. More...
struct  BVT_Comparer
 Comparer between two BVT. More...
struct  BVTQ
class  Capsule
 Center at zero point capsule. More...
struct  CollisionData
 Collision data stores the collision request and the result given by collision algorithm. 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  ConservativeAdvancementStackData
struct  Contact
 Contact information returned by collision. 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  DistanceData
 Distance data stores the distance request and the result given by distance algorithm. 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  DistanceRes
 @ brief Structure for minimum distance between two meshes and the corresponding nearest point pair More...
struct  DistanceResult
 distance result More...
class  DistanceTraversalNodeBase
 Node structure encoding the information required for distance traversal. More...
class  DummyCollisionObject
 Dummy collision object with a point AABB. More...
class  DynamicAABBTreeCollisionManager
class  DynamicAABBTreeCollisionManager_Array
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  Halfspace
 Half Space: this is equivalent to the Plane in ODE. The separation plane is defined as n * x = d; Points in the negative side of the separation plane (i.e. {x | n * x < d}) are inside the half space and points in the positive side of the separation plane (i.e. {x | n * x > d}) are outside the half space. 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  it_recursion_node
 Class describes the information needed when we take the right branch in searching for intervals but possibly come back and check the left branch as well. More...
struct  IVector3
class  Joint
 Base Joint. More...
class  JointConfig
class  KDOP
 KDOP class describes the KDOP collision structures. K is set as the template parameter, which should be 16, 18, or 24 The KDOP structure is defined by some pairs of parallel planes defined by some axes. For K = 16, the planes are 6 AABB planes and 10 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 8 (0,-1,0) and (0,1,0) -> indices 1 and 9 (0,0,-1) and (0,0,1) -> indices 2 and 10 (-1,-1,0) and (1,1,0) -> indices 3 and 11 (-1,0,-1) and (1,0,1) -> indices 4 and 12 (0,-1,-1) and (0,1,1) -> indices 5 and 13 (-1,1,0) and (1,-1,0) -> indices 6 and 14 (-1,0,1) and (1,0,-1) -> indices 7 and 15 For K = 18, the planes are 6 AABB planes and 12 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 9 (0,-1,0) and (0,1,0) -> indices 1 and 10 (0,0,-1) and (0,0,1) -> indices 2 and 11 (-1,-1,0) and (1,1,0) -> indices 3 and 12 (-1,0,-1) and (1,0,1) -> indices 4 and 13 (0,-1,-1) and (0,1,1) -> indices 5 and 14 (-1,1,0) and (1,-1,0) -> indices 6 and 15 (-1,0,1) and (1,0,-1) -> indices 7 and 16 (0,-1,1) and (0,1,-1) -> indices 8 and 17 For K = 18, the planes are 6 AABB planes and 18 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 12 (0,-1,0) and (0,1,0) -> indices 1 and 13 (0,0,-1) and (0,0,1) -> indices 2 and 14 (-1,-1,0) and (1,1,0) -> indices 3 and 15 (-1,0,-1) and (1,0,1) -> indices 4 and 16 (0,-1,-1) and (0,1,1) -> indices 5 and 17 (-1,1,0) and (1,-1,0) -> indices 6 and 18 (-1,0,1) and (1,0,-1) -> indices 7 and 19 (0,-1,1) and (0,1,-1) -> indices 8 and 20 (-1, -1, 1) and (1, 1, -1) --> indices 9 and 21 (-1, 1, -1) and (1, -1, 1) --> indices 10 and 22 (1, -1, -1) and (-1, 1, 1) --> indices 11 and 23. 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  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  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...
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...
class  Plane
 Infinite plane. More...
class  PolySolver
 A class solves polynomial degree (1,2,3) equations. More...
class  PrismaticJoint
class  Quaternion3f
 Quaternion used locally by InterpMotion. More...
class  RevoluteJoint
class  RSS
 A class for rectangle sphere-swept bounding volume. More...
class  SaPCollisionManager
 Rigorous SAP collision manager. More...
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  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  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. Can be replaced in part by boost::icl::interval_set, which is only supported after boost 1.46 and does not support delete node routine. More...
struct  SortByXLow
 Functor sorting objects according to the AABB lower x bound. More...
struct  SortByYLow
 Functor sorting objects according to the AABB lower y bound. More...
struct  SortByZLow
 Functor sorting objects according to the AABB lower z bound. 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...
struct  TaylorModel
 TaylorModel implements a third order Taylor model, i.e., a cubic approximation of a function over a time interval, with an interval remainder. All the operations on two Taylor models assume their time intervals are the same. More...
struct  TimeInterval
class  Timer
struct  TMatrix3
class  Transform3f
 Simple transform class used locally by InterpMotion. More...
class  TraversalNodeBase
 Node structure encoding the information required for traversal. More...
class  Triangle
 Triangle with 3 indices for points. More...
class  Triangle2
 Triangle stores the points instead of only indices of points. More...
class  TriangleDistance
struct  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...

Typedefs

typedef std::list< BVHFrontNodeBVHFrontList
 BVH front list is a list of front nodes.
typedef bool(* CollisionCallBack )(CollisionObject *o1, CollisionObject *o2, void *cdata)
 Callback for collision between two objects. Return value is whether can stop now.
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.
typedef int32_t FCL_INT32
typedef uint64_t FCL_INT64
typedef double FCL_REAL
typedef uint32_t FCL_UINT32
typedef int64_t FCL_UINT64
typedef Matrix3fX
< details::Matrix3Data
< FCL_REAL > > 
Matrix3f
typedef Vec3fX
< details::Vec3Data< FCL_REAL > > 
Vec3f

Enumerations

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 -> ...... | |-> update_begun -> updated -> ..... More...
enum  BVHModelType { BVH_MODEL_UNKNOWN, BVH_MODEL_TRIANGLES, BVH_MODEL_POINTCLOUD }
 BVH model type. 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  InterpolationType { LINEAR, STANDARD }
enum  JointType { JT_UNKNOWN, JT_PRISMATIC, JT_REVOLUTE, JT_BALLEULER }
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...
enum  OBJECT_TYPE {
  OT_UNKNOWN, OT_BVH, OT_GEOM, OT_OCTREE,
  OT_COUNT
}
 object type: BVH (mesh, points), basic geometry, octree More...
enum  SplitMethodType { SPLIT_METHOD_MEAN, SPLIT_METHOD_MEDIAN, SPLIT_METHOD_BV_CENTER }
 Three types of split algorithms are provided in FCL as default. More...

Functions

template<typename T >
static Vec3fX< T > abs (const Vec3fX< T > &x)
template<typename T >
Matrix3fX< T > abs (const Matrix3fX< T > &R)
static void axisFromEigen (Vec3f eigenV[3], Matrix3f::U eigenS[3], Vec3f axis[3])
IVector3 bound (const IVector3 &i, const Vec3f &v)
IVector3 bound (const IVector3 &i, const IVector3 &v)
Interval bound (const Interval &i, FCL_REAL v)
Interval bound (const Interval &i, const Interval &other)
template<typename T_BVH >
std::size_t BVHCollide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
template<typename T_BVH , typename NarrowPhaseSolver >
std::size_t BVHCollide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
template<>
std::size_t BVHCollide< kIOS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
template<>
std::size_t BVHCollide< OBB > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
template<>
std::size_t BVHCollide< OBBRSS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
template<typename T_BVH >
FCL_REAL BVHDistance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
template<typename T_BVH , typename NarrowPhaseSolver >
FCL_REAL BVHDistance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
template<>
FCL_REAL BVHDistance< kIOS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
template<>
FCL_REAL BVHDistance< OBBRSS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
template<>
FCL_REAL BVHDistance< RSS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
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.
void BVHExpand (BVHModel< OBB > &model, const Variance3f *ucs, FCL_REAL r)
 Expand the BVH bounding boxes according to the corresponding variance information, for OBB.
void BVHExpand (BVHModel< RSS > &model, const Variance3f *ucs, FCL_REAL r)
 Expand the BVH bounding boxes according to the corresponding variance information, for RSS.
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.
void clipToRange (FCL_REAL &val, FCL_REAL a, FCL_REAL b)
 Clip value between a and b.
void collide (CollisionTraversalNodeBase *node, BVHFrontList *front_list=NULL)
 collision on collision traversal node; can use front list to accelerate
template<typename NarrowPhaseSolver >
std::size_t collide (const CollisionObject *o1, const CollisionObject *o2, const NarrowPhaseSolver *nsolver, 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.
template<typename NarrowPhaseSolver >
std::size_t collide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest &request, CollisionResult &result)
std::size_t collide (const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
std::size_t collide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
template std::size_t collide (const CollisionObject *o1, const CollisionObject *o2, const GJKSolver_libccd *nsolver, const CollisionRequest &request, CollisionResult &result)
template std::size_t collide (const CollisionObject *o1, const CollisionObject *o2, const GJKSolver_indep *nsolver, const CollisionRequest &request, CollisionResult &result)
template std::size_t collide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver_libccd *nsolver, const CollisionRequest &request, CollisionResult &result)
template std::size_t collide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver_indep *nsolver, const CollisionRequest &request, CollisionResult &result)
void collide2 (MeshCollisionTraversalNodeOBB *node, BVHFrontList *front_list=NULL)
 special collision on OBB traversal node
void collide2 (MeshCollisionTraversalNodeRSS *node, BVHFrontList *front_list=NULL)
 special collision on RSS traversal node
void collisionRecurse (CollisionTraversalNodeBase *node, int b1, int b2, BVHFrontList *front_list)
 Recurse function for collision.
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.
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.
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
template<>
void computeBV< AABB, Box > (const Box &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, Convex > (const Convex &s, const Transform3f &tf, AABB &bv)
template<>
void computeBV< AABB, Cylinder > (const Cylinder &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< AABB, Sphere > (const Sphere &s, const Transform3f &tf, AABB &bv)
template<>
void computeBV< AABB, Triangle2 > (const Triangle2 &s, const Transform3f &tf, AABB &bv)
template<>
void computeBV< KDOP< 16 >, Halfspace > (const Halfspace &s, const Transform3f &tf, KDOP< 16 > &bv)
template<>
void computeBV< KDOP< 16 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 16 > &bv)
template<>
void computeBV< KDOP< 18 >, Halfspace > (const Halfspace &s, const Transform3f &tf, KDOP< 18 > &bv)
template<>
void computeBV< KDOP< 18 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 18 > &bv)
template<>
void computeBV< KDOP< 24 >, Halfspace > (const Halfspace &s, const Transform3f &tf, KDOP< 24 > &bv)
template<>
void computeBV< KDOP< 24 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 24 > &bv)
template<>
void computeBV< kIOS, Halfspace > (const Halfspace &s, const Transform3f &tf, kIOS &bv)
template<>
void computeBV< kIOS, Plane > (const Plane &s, const Transform3f &tf, kIOS &bv)
template<>
void computeBV< OBB, Box > (const Box &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, Convex > (const Convex &s, const Transform3f &tf, OBB &bv)
template<>
void computeBV< OBB, Cylinder > (const Cylinder &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< OBB, Sphere > (const Sphere &s, const Transform3f &tf, OBB &bv)
template<>
void computeBV< OBBRSS, Halfspace > (const Halfspace &s, const Transform3f &tf, OBBRSS &bv)
template<>
void computeBV< OBBRSS, Plane > (const Plane &s, const Transform3f &tf, OBBRSS &bv)
template<>
void computeBV< RSS, Halfspace > (const Halfspace &s, const Transform3f &tf, RSS &bv)
template<>
void computeBV< RSS, Plane > (const Plane &s, const Transform3f &tf, RSS &bv)
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
template<typename BV >
void computeSplitValue_bvcenter (const BV &bv, FCL_REAL &split_value)
template<typename BV >
void computeSplitValue_mean (const BV &bv, Vec3f *vertices, Triangle *triangles, unsigned int *primitive_indices, int num_primitives, BVHModelType type, const Vec3f &split_vector, FCL_REAL &split_value)
template<typename BV >
void computeSplitValue_median (const BV &bv, Vec3f *vertices, Triangle *triangles, unsigned int *primitive_indices, int num_primitives, BVHModelType type, const Vec3f &split_vector, FCL_REAL &split_value)
template<typename BV >
void computeSplitVector (const BV &bv, Vec3f &split_vector)
template<>
void computeSplitVector< kIOS > (const kIOS &bv, Vec3f &split_vector)
template<>
void computeSplitVector< OBBRSS > (const OBBRSS &bv, Vec3f &split_vector)
void computeVertices (const OBB &b, Vec3f vertices[8])
 Compute the 8 vertices of a OBB.
Quaternion3f conj (const Quaternion3f &q)
 conjugate of quaternion
template<typename BV >
int conservativeAdvancement (const CollisionGeometry *o1, MotionBase< BV > *motion1, const CollisionGeometry *o2, MotionBase< BV > *motion2, const CollisionRequest &request, CollisionResult &result, FCL_REAL &toc)
template int conservativeAdvancement< RSS > (const CollisionGeometry *o1, MotionBase< RSS > *motion1, const CollisionGeometry *o2, MotionBase< RSS > *motion2, const CollisionRequest &request, CollisionResult &result, FCL_REAL &toc)
void constructBox (const AABB &bv, Box &box, Transform3f &tf)
 construct a box shape (with a configuration) from a given bounding volume
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)
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.
bool defaultCollisionFunction (CollisionObject *o1, CollisionObject *o2, void *cdata)
 Default collision callback for two objects o1 and o2 in broad phase. return value means whether the broad phase can stop now.
bool defaultDistanceFunction (CollisionObject *o1, CollisionObject *o2, void *cdata, FCL_REAL &dist)
 Default distance callback for two objects o1 and o2 in broad phase. return value means whether the broad phase can stop now. also return dist, i.e. the bmin distance till now.
template<typename NarrowPhaseSolver >
FCL_REAL distance (const CollisionObject *o1, const CollisionObject *o2, const NarrowPhaseSolver *nsolver, 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.
template<typename NarrowPhaseSolver >
FCL_REAL distance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
void distance (DistanceTraversalNodeBase *node, BVHFrontList *front_list=NULL, int qsize=2)
 distance computation on distance traversal node; can use front list to accelerate
FCL_REAL distance (const CollisionObject *o1, const CollisionObject *o2, const DistanceRequest &request, DistanceResult &result)
FCL_REAL distance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
template FCL_REAL distance (const CollisionObject *o1, const CollisionObject *o2, const GJKSolver_libccd *nsolver, const DistanceRequest &request, DistanceResult &result)
template FCL_REAL distance (const CollisionObject *o1, const CollisionObject *o2, const GJKSolver_indep *nsolver, const DistanceRequest &request, DistanceResult &result)
template FCL_REAL distance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver_libccd *nsolver, const DistanceRequest &request, DistanceResult &result)
template FCL_REAL distance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver_indep *nsolver, const DistanceRequest &request, DistanceResult &result)
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. 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 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.
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.
void distanceQueueRecurse (DistanceTraversalNodeBase *node, int b1, int b2, BVHFrontList *front_list, int qsize)
 Recurse function for distance, using queue acceleration.
void distanceRecurse (DistanceTraversalNodeBase *node, int b1, int b2, BVHFrontList *front_list)
 Recurse function for distance.
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
void eulerToMatrix (FCL_REAL a, FCL_REAL b, FCL_REAL c, Matrix3f &R)
template<typename BV >
void fit (Vec3f *ps, int n, BV &bv)
 Compute a bounding volume that fits a set of n points.
template<>
void fit (Vec3f *ps, int n, OBB &bv)
template<>
void fit (Vec3f *ps, int n, RSS &bv)
template<>
void fit (Vec3f *ps, int n, kIOS &bv)
template<>
void fit (Vec3f *ps, int n, OBBRSS &bv)
template<>
void fit< kIOS > (Vec3f *ps, int n, kIOS &bv)
template<>
void fit< OBB > (Vec3f *ps, int n, OBB &bv)
template<>
void fit< OBBRSS > (Vec3f *ps, int n, OBBRSS &bv)
template<>
void fit< RSS > (Vec3f *ps, int n, RSS &bv)
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
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)
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
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_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)
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Box &shape, const Transform3f &pose)
 Generate BVH model from box.
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.
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. 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.
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.
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. For cylinder with larger radius, the number of circle split number is r * tot.
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.
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. For cone with larger radius, the number of circle split number is r * tot.
template<typename T >
void generateCoordinateSystem (const Vec3fX< T > &w, Vec3fX< T > &u, Vec3fX< T > &v)
void generateRandomTransform (FCL_REAL extents[6], Transform3f &transform)
 Generate one random transform whose translation is constrained by extents and rotation without constraints. The translation is (x, y, z), and extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <= z <= extents[5].
void generateRandomTransform_ccd (FCL_REAL extents[6], std::vector< Transform3f > &transforms, std::vector< Transform3f > &transforms2, FCL_REAL delta_trans[3], FCL_REAL delta_rot, std::size_t n, const std::vector< Vec3f > &vertices1, const std::vector< Triangle > &triangles1, const std::vector< Vec3f > &vertices2, const std::vector< Triangle > &triangles2)
void generateRandomTransforms (FCL_REAL extents[6], std::vector< Transform3f > &transforms, std::size_t n)
 Generate n random transforms whose translations are constrained by extents.
void generateRandomTransforms (FCL_REAL extents[6], FCL_REAL delta_trans[3], FCL_REAL delta_rot, std::vector< Transform3f > &transforms, std::vector< Transform3f > &transforms2, std::size_t n)
 Generate n random transforms whose translations are constrained by extents. Also generate another transforms2 which have additional random translation & rotation to the transforms generated.
void generateRandomTransforms_ccd (FCL_REAL extents[6], std::vector< Transform3f > &transforms, std::vector< Transform3f > &transforms2, FCL_REAL delta_trans[3], FCL_REAL delta_rot, std::size_t n, const std::vector< Vec3f > &vertices1, const std::vector< Triangle > &triangles1, const std::vector< Vec3f > &vertices2, const std::vector< Triangle > &triangles2)
 Generate n random tranforms and transform2 with addtional random translation/rotation. The transforms and transform2 are used as initial and goal configurations for the first mesh. The second mesh is in I. This is used for continuous collision detection checking.
void generateTaylorModelForCosFunc (TaylorModel &tm, FCL_REAL w, FCL_REAL q0)
void generateTaylorModelForLinearFunc (TaylorModel &tm, FCL_REAL p, FCL_REAL v)
void generateTaylorModelForSinFunc (TaylorModel &tm, FCL_REAL w, FCL_REAL q0)
void generateTVector3ForLinearFunc (TVector3 &v, const Vec3f &position, const Vec3f &velocity)
template<typename GJKSolver >
CollisionFunctionMatrix
< GJKSolver > & 
getCollisionFunctionLookTable ()
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.
template<typename GJKSolver >
DistanceFunctionMatrix
< GJKSolver > & 
getDistanceFunctionLookTable ()
template<std::size_t N>
void getDistances (const Vec3f &p, FCL_REAL *d)
 Compute the distances to planes with normals from KDOP vectors except those of AABB face planes.
template<>
void getDistances< 5 > (const Vec3f &p, FCL_REAL *d)
 Specification of getDistances.
template<>
void getDistances< 6 > (const Vec3f &p, FCL_REAL *d)
template<>
void getDistances< 9 > (const Vec3f &p, FCL_REAL *d)
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.
static void getExtentAndCenter_mesh (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. The bounding volume axes are known.
static void getExtentAndCenter_pointcloud (Vec3f *ps, Vec3f *ps2, 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. The bounding volume axes are known.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
template<typename BV >
bool initialize (MeshConservativeAdvancementTraversalNode< BV > &node, BVHModel< BV > &model1, BVHModel< BV > &model2, const Matrix3f &R1, const Vec3f &T1, const Matrix3f &R2, const Vec3f &T2, 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.
bool initialize (MeshConservativeAdvancementTraversalNodeRSS &node, const BVHModel< RSS > &model1, const BVHModel< RSS > &model2, const Matrix3f &R1, const Vec3f &T1, const Matrix3f &R2, const Vec3f &T2, FCL_REAL w=1)
 Initialize traversal node for conservative advancement computation between two meshes, given the current transforms, specialized for RSS.
Quaternion3f inverse (const Quaternion3f &q)
 inverse of quaternion
Transform3f inverse (const Transform3f &tf)
 inverse the transform
template<typename T >
Matrix3fX< T > inverse (const Matrix3fX< T > &R)
bool inVoronoi (FCL_REAL a, FCL_REAL b, FCL_REAL Anorm_dot_B, FCL_REAL Anorm_dot_T, FCL_REAL A_dot_B, FCL_REAL A_dot_T, FCL_REAL B_dot_T)
 Returns whether the nearest point on rectangle edge Pb + B*u, 0 <= u <= b, to the rectangle edge, Pa + A*t, 0 <= t <= a, is within the half space determined by the point Pa and the direction Anorm. A,B, and Anorm are unit vectors. T is the vector between Pa and Pb.
void loadOBJFile (const char *filename, std::vector< Vec3f > &points, std::vector< Triangle > &triangles)
 Load an obj mesh file.
template<typename T >
static Vec3fX< T > max (const Vec3fX< T > &x, const Vec3fX< T > &y)
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.
static FCL_REAL maximumDistance_mesh (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, const Vec3f &query)
static FCL_REAL maximumDistance_pointcloud (Vec3f *ps, Vec3f *ps2, unsigned int *indices, int n, const Vec3f &query)
OBB merge_largedist (const OBB &b1, const OBB &b2)
 OBB merge method when the centers of two smaller OBB are far away.
OBB merge_smalldist (const OBB &b1, const OBB &b2)
 OBB merge method when the centers of two smaller OBB are close.
template<typename T >
static Vec3fX< T > min (const Vec3fX< T > &x, const Vec3fX< T > &y)
void minmax (FCL_REAL a, FCL_REAL b, FCL_REAL &minv, FCL_REAL &maxv)
 Find the smaller and larger one of two values.
void minmax (FCL_REAL p, FCL_REAL &minv, FCL_REAL &maxv)
 Merge the interval [minv, maxv] and value p/.
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.
template<typename T >
static Vec3fX< T > normalize (const Vec3fX< T > &v)
bool obbDisjoint (const Matrix3f &B, const Vec3f &T, const Vec3f &a, const Vec3f &b)
 Check collision between two boxes: the first box is in configuration (R, T) and its half dimension is set by a; the second box is in identity configuration and its half dimension is set by b.
template<typename T >
std::ostream & operator<< (std::ostream &out, const Vec3fX< T > &x)
static std::ostream & operator<< (std::ostream &o, const Vec3f &v)
static std::ostream & operator<< (std::ostream &o, const Matrix3f &m)
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.
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.
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.
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.
bool overlap (double a1, double a2, double b1, double b2)
 returns 1 if the intervals overlap, and 0 otherwise
void propagateBVHFrontListCollisionRecurse (CollisionTraversalNodeBase *node, BVHFrontList *front_list)
 Recurse function for front list propagation.
template<typename T >
T::meta_type quadraticForm (const Matrix3fX< T > &R, const Vec3fX< typename T::vector_type > &v)
FCL_REAL rand_interval (FCL_REAL rmin, FCL_REAL rmax)
FCL_REAL rectDistance (const Matrix3f &Rab, Vec3f const &Tab, const FCL_REAL a[2], const FCL_REAL b[2], Vec3f *P=NULL, Vec3f *Q=NULL)
 Distance between two oriented rectangles; P and Q (optional return values) are the closest points in the rectangles, both are in the local frame of the first rectangle.
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)
void relativeTransform (const Transform3f &tf1, const Transform3f &tf2, Transform3f &tf)
 compute the relative transform between two transforms: tf2 = tf * tf1
TMatrix3 rotationConstrain (const TMatrix3 &m)
IMatrix3 rotationConstrain (const IMatrix3 &m)
void segCoords (FCL_REAL &t, FCL_REAL &u, FCL_REAL a, FCL_REAL b, FCL_REAL A_dot_B, FCL_REAL A_dot_T, FCL_REAL B_dot_T)
 Finds the parameters t & u corresponding to the two closest points on a pair of line segments. The first segment is defined as Pa + A*t, 0 <= t <= a, where "Pa" is one endpoint of the segment, "A" is a unit vector pointing to the other endpoint, and t is a scalar that produces all the points between the two endpoints. Since "A" is a unit vector, "a" is the segment's length. The second segment is defined as Pb + B*u, 0 <= u <= b. Many of the terms needed by the algorithm are already computed for other purposes,so we just pass these terms into the function instead of complete specifications of each segment. "T" in the dot products is the vector betweeen Pa and Pb. Reference: "On fast computation of distance between line segments." Vladimir J. Lumelsky, in Information Processing Letters, no. 21, pages 55-61, 1985.
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
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
template<>
size_t select (const AABB &query, const NodeBase< AABB > &node1, const NodeBase< AABB > &node2)
void selfCollide (CollisionTraversalNodeBase *node, BVHFrontList *front_list=NULL)
 self collision on collision traversal node; can use front list to accelerate
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.
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)
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)
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 __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_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)
Halfspace transform (const Halfspace &a, const Transform3f &tf)
Plane transform (const Plane &a, const Transform3f &tf)
OBB translate (const OBB &bv, const Vec3f &t)
 Translate the OBB bv.
RSS translate (const RSS &bv, const Vec3f &t)
 Translate the RSS bv.
OBBRSS translate (const OBBRSS &bv, const Vec3f &t)
 Translate the OBBRSS bv.
kIOS translate (const kIOS &bv, const Vec3f &t)
 Translate the kIOS BV.
template<size_t N>
KDOP< N > translate (const KDOP< N > &bv, const Vec3f &t)
 translate the KDOP BV
static AABB translate (const AABB &aabb, const Vec3f &t)
 translate the center of AABB by t
template KDOP< 16 > translate< 16 > (const KDOP< 16 > &, const Vec3f &)
template KDOP< 18 > translate< 18 > (const KDOP< 18 > &, const Vec3f &)
template KDOP< 24 > translate< 24 > (const KDOP< 24 > &, const Vec3f &)
template<typename T >
Matrix3fX< T > transpose (const Matrix3fX< T > &R)
template<typename T >
static T::meta_type triple (const Vec3fX< T > &x, const Vec3fX< T > &y, const Vec3fX< T > &z)
void updateFrontList (BVHFrontList *front_list, int b1, int b2)
 Add new front node into the front list.

Variables

static const double cosA = sqrt(3.0) / 2.0
InterpolationType interpolation_linear_type = LINEAR
static const double invCosA = 2.0 / sqrt(3.0)
static const double invSinA = 2
static const double kIOS_RATIO = 1.5
static const double sinA = 0.5

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

Typedef Documentation

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

BVH front list is a list of front nodes.

Definition at line 66 of file BVH_front.h.

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

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

Definition at line 51 of file broadphase.h.

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.

Definition at line 54 of file broadphase.h.

typedef int32_t fcl::FCL_INT32

Definition at line 50 of file data_types.h.

typedef uint64_t fcl::FCL_INT64

Definition at line 47 of file data_types.h.

typedef double fcl::FCL_REAL

Definition at line 46 of file data_types.h.

typedef uint32_t fcl::FCL_UINT32

Definition at line 49 of file data_types.h.

typedef int64_t fcl::FCL_UINT64

Definition at line 48 of file data_types.h.

Definition at line 449 of file matrix_3f.h.

Definition at line 224 of file vec_3f.h.


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

Definition at line 49 of file BVH_internal.h.

BVH model type.

Enumerator:
BVH_MODEL_UNKNOWN 
BVH_MODEL_TRIANGLES 

unknown model type

BVH_MODEL_POINTCLOUD 

triangle model

point cloud model

Definition at line 74 of file BVH_internal.h.

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.

Definition at line 60 of file BVH_internal.h.

Enumerator:
LINEAR 
STANDARD 

Definition at line 45 of file interpolation.h.

Enumerator:
JT_UNKNOWN 
JT_PRISMATIC 
JT_REVOLUTE 
JT_BALLEULER 

Definition at line 56 of file joint.h.

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 

Definition at line 52 of file collision_object.h.

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

Enumerator:
OT_UNKNOWN 
OT_BVH 
OT_GEOM 
OT_OCTREE 
OT_COUNT 

Definition at line 49 of file collision_object.h.

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

Enumerator:
SPLIT_METHOD_MEAN 
SPLIT_METHOD_MEDIAN 
SPLIT_METHOD_BV_CENTER 

Definition at line 69 of file BV_splitter.h.


Function Documentation

template<typename T >
static Vec3fX<T> fcl::abs ( const Vec3fX< T > &  x) [inline, static]

Definition at line 189 of file vec_3f.h.

template<typename T >
Matrix3fX<T> fcl::abs ( const Matrix3fX< T > &  R)

Definition at line 422 of file matrix_3f.h.

static void fcl::axisFromEigen ( Vec3f  eigenV[3],
Matrix3f::U  eigenS[3],
Vec3f  axis[3] 
) [inline, static]

Definition at line 51 of file BV_fitter.cpp.

IVector3 fcl::bound ( const IVector3 &  i,
const Vec3f &  v 
)

Definition at line 169 of file interval_vector.cpp.

IVector3 fcl::bound ( const IVector3 &  i,
const IVector3 &  v 
)

Definition at line 155 of file interval_vector.cpp.

Interval fcl::bound ( const Interval &  i,
FCL_REAL  v 
)

Definition at line 43 of file interval.cpp.

Interval fcl::bound ( const Interval &  i,
const Interval &  other 
)

Definition at line 51 of file interval.cpp.

template<typename T_BVH >
std::size_t fcl::BVHCollide ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Definition at line 364 of file collision_func_matrix.cpp.

template<typename T_BVH , typename NarrowPhaseSolver >
std::size_t fcl::BVHCollide ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Definition at line 425 of file collision_func_matrix.cpp.

template<>
std::size_t fcl::BVHCollide< kIOS > ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Definition at line 418 of file collision_func_matrix.cpp.

template<>
std::size_t fcl::BVHCollide< OBB > ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Definition at line 405 of file collision_func_matrix.cpp.

template<>
std::size_t fcl::BVHCollide< OBBRSS > ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Definition at line 411 of file collision_func_matrix.cpp.

template<typename T_BVH >
FCL_REAL fcl::BVHDistance ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const DistanceRequest &  request,
DistanceResult &  result 
)

Definition at line 218 of file distance_func_matrix.cpp.

template<typename T_BVH , typename NarrowPhaseSolver >
FCL_REAL fcl::BVHDistance ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)

Definition at line 279 of file distance_func_matrix.cpp.

template<>
FCL_REAL fcl::BVHDistance< kIOS > ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const DistanceRequest &  request,
DistanceResult &  result 
)

Definition at line 263 of file distance_func_matrix.cpp.

template<>
FCL_REAL fcl::BVHDistance< OBBRSS > ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const DistanceRequest &  request,
DistanceResult &  result 
)

Definition at line 271 of file distance_func_matrix.cpp.

template<>
FCL_REAL fcl::BVHDistance< RSS > ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const DistanceRequest &  request,
DistanceResult &  result 
)

Definition at line 256 of file distance_func_matrix.cpp.

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.

Definition at line 48 of file BVH_utility.h.

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

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

Definition at line 43 of file BVH_utility.cpp.

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

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

Definition at line 74 of file BVH_utility.cpp.

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.

Definition at line 605 of file BVH_utility.cpp.

void fcl::clipToRange ( FCL_REAL &  val,
FCL_REAL  a,
FCL_REAL  b 
)

Clip value between a and b.

Definition at line 44 of file RSS.cpp.

void fcl::collide ( CollisionTraversalNodeBase *  node,
BVHFrontList *  front_list = NULL 
)

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

Definition at line 44 of file collision_node.cpp.

template<typename NarrowPhaseSolver >
std::size_t fcl::collide ( const CollisionObject *  o1,
const CollisionObject *  o2,
const NarrowPhaseSolver *  nsolver,
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.

Definition at line 55 of file collision.cpp.

template<typename NarrowPhaseSolver >
std::size_t fcl::collide ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)

Definition at line 65 of file collision.cpp.

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

Definition at line 124 of file collision.cpp.

std::size_t fcl::collide ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const CollisionRequest &  request,
CollisionResult &  result 
)

Definition at line 131 of file collision.cpp.

template std::size_t fcl::collide ( const CollisionObject *  o1,
const CollisionObject *  o2,
const GJKSolver_libccd *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)
template std::size_t fcl::collide ( const CollisionObject *  o1,
const CollisionObject *  o2,
const GJKSolver_indep *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)
template std::size_t fcl::collide ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const GJKSolver_libccd *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)
template std::size_t fcl::collide ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const GJKSolver_indep *  nsolver,
const CollisionRequest &  request,
CollisionResult &  result 
)
void fcl::collide2 ( MeshCollisionTraversalNodeOBB *  node,
BVHFrontList *  front_list = NULL 
)

special collision on OBB traversal node

Definition at line 56 of file collision_node.cpp.

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

special collision on RSS traversal node

Definition at line 76 of file collision_node.cpp.

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

Recurse function for collision.

Definition at line 42 of file traversal_recurse.cpp.

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.

Definition at line 89 of file traversal_recurse.cpp.

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.

Definition at line 169 of file traversal_recurse.cpp.

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

Definition at line 65 of file geometric_shapes_utility.h.

template<>
void fcl::computeBV< AABB, Box > ( const Box &  s,
const Transform3f &  tf,
AABB &  bv 
)

Definition at line 250 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< AABB, Capsule > ( const Capsule &  s,
const Transform3f &  tf,
AABB &  bv 
)

Definition at line 275 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< AABB, Cone > ( const Cone &  s,
const Transform3f &  tf,
AABB &  bv 
)

Definition at line 290 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< AABB, Convex > ( const Convex &  s,
const Transform3f &  tf,
AABB &  bv 
)

Definition at line 320 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< AABB, Cylinder > ( const Cylinder &  s,
const Transform3f &  tf,
AABB &  bv 
)

Definition at line 305 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< AABB, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
AABB &  bv 
)

Definition at line 343 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< AABB, Plane > ( const Plane &  s,
const Transform3f &  tf,
AABB &  bv 
)

Definition at line 375 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< AABB, Sphere > ( const Sphere &  s,
const Transform3f &  tf,
AABB &  bv 
)

Definition at line 265 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< AABB, Triangle2 > ( const Triangle2 &  s,
const Transform3f &  tf,
AABB &  bv 
)

Definition at line 336 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< KDOP< 16 >, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
KDOP< 16 > &  bv 
)

Definition at line 525 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< KDOP< 16 >, Plane > ( const Plane &  s,
const Transform3f &  tf,
KDOP< 16 > &  bv 
)

Definition at line 765 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< KDOP< 18 >, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
KDOP< 18 > &  bv 
)

Definition at line 580 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< KDOP< 18 >, Plane > ( const Plane &  s,
const Transform3f &  tf,
KDOP< 18 > &  bv 
)

Definition at line 816 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< KDOP< 24 >, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
KDOP< 24 > &  bv 
)

Definition at line 641 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< KDOP< 24 >, Plane > ( const Plane &  s,
const Transform3f &  tf,
KDOP< 24 > &  bv 
)

Definition at line 871 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< kIOS, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
kIOS &  bv 
)

Definition at line 516 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< kIOS, Plane > ( const Plane &  s,
const Transform3f &  tf,
kIOS &  bv 
)

Definition at line 756 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBB, Box > ( const Box &  s,
const Transform3f &  tf,
OBB &  bv 
)

Definition at line 408 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBB, Capsule > ( const Capsule &  s,
const Transform3f &  tf,
OBB &  bv 
)

Definition at line 433 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBB, Cone > ( const Cone &  s,
const Transform3f &  tf,
OBB &  bv 
)

Definition at line 446 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBB, Convex > ( const Convex &  s,
const Transform3f &  tf,
OBB &  bv 
)

Definition at line 472 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBB, Cylinder > ( const Cylinder &  s,
const Transform3f &  tf,
OBB &  bv 
)

Definition at line 459 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBB, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
OBB &  bv 
)

Half space can only have very rough OBB

Half space can only have very rough OBB

Definition at line 487 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBB, Plane > ( const Plane &  s,
const Transform3f &  tf,
OBB &  bv 
)

n'd' = R * n * (d + (R * n) * T) = R * (n * d) + T

n'd' = R * n * (d + (R * n) * T) = R * (n * d) + T

Definition at line 719 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBB, Sphere > ( const Sphere &  s,
const Transform3f &  tf,
OBB &  bv 
)

Definition at line 421 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBBRSS, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
OBBRSS &  bv 
)

Definition at line 509 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< OBBRSS, Plane > ( const Plane &  s,
const Transform3f &  tf,
OBBRSS &  bv 
)

Definition at line 749 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< RSS, Halfspace > ( const Halfspace &  s,
const Transform3f &  tf,
RSS &  bv 
)

Half space can only have very rough RSS

Definition at line 498 of file geometric_shapes_utility.cpp.

template<>
void fcl::computeBV< RSS, Plane > ( const Plane &  s,
const Transform3f &  tf,
RSS &  bv 
)

Definition at line 732 of file geometric_shapes_utility.cpp.

static void fcl::computeChildBV ( const AABB &  root_bv,
unsigned int  i,
AABB &  child_bv 
) [inline, static]

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

Definition at line 201 of file octree.h.

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

Definition at line 90 of file BV_splitter.cpp.

template<typename BV >
void fcl::computeSplitValue_mean ( const BV &  bv,
Vec3f *  vertices,
Triangle *  triangles,
unsigned int *  primitive_indices,
int  num_primitives,
BVHModelType  type,
const Vec3f &  split_vector,
FCL_REAL &  split_value 
)

Definition at line 97 of file BV_splitter.cpp.

template<typename BV >
void fcl::computeSplitValue_median ( const BV &  bv,
Vec3f *  vertices,
Triangle *  triangles,
unsigned int *  primitive_indices,
int  num_primitives,
BVHModelType  type,
const Vec3f &  split_vector,
FCL_REAL &  split_value 
)

Definition at line 131 of file BV_splitter.cpp.

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

Definition at line 44 of file BV_splitter.cpp.

template<>
void fcl::computeSplitVector< kIOS > ( const kIOS &  bv,
Vec3f &  split_vector 
)

Definition at line 50 of file BV_splitter.cpp.

template<>
void fcl::computeSplitVector< OBBRSS > ( const OBBRSS &  bv,
Vec3f &  split_vector 
)

Definition at line 84 of file BV_splitter.cpp.

void fcl::computeVertices ( const OBB &  b,
Vec3f  vertices[8] 
) [inline]

Compute the 8 vertices of a OBB.

Definition at line 48 of file OBB.cpp.

Quaternion3f fcl::conj ( const Quaternion3f &  q)

conjugate of quaternion

Definition at line 318 of file transform.cpp.

template<typename BV >
int fcl::conservativeAdvancement ( const CollisionGeometry *  o1,
MotionBase< BV > *  motion1,
const CollisionGeometry *  o2,
MotionBase< BV > *  motion2,
const CollisionRequest &  request,
CollisionResult &  result,
FCL_REAL &  toc 
)

Definition at line 51 of file conservative_advancement.cpp.

template int fcl::conservativeAdvancement< RSS > ( const CollisionGeometry *  o1,
MotionBase< RSS > *  motion1,
const CollisionGeometry *  o2,
MotionBase< RSS > *  motion2,
const CollisionRequest &  request,
CollisionResult &  result,
FCL_REAL &  toc 
)
void fcl::constructBox ( const AABB &  bv,
Box &  box,
Transform3f &  tf 
)

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

Definition at line 938 of file geometric_shapes_utility.cpp.

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

Definition at line 944 of file geometric_shapes_utility.cpp.

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

Definition at line 952 of file geometric_shapes_utility.cpp.

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

Definition at line 960 of file geometric_shapes_utility.cpp.

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

Definition at line 968 of file geometric_shapes_utility.cpp.

void fcl::constructBox ( const KDOP< 16 > &  bv,
Box &  box,
Transform3f &  tf 
)

Definition at line 976 of file geometric_shapes_utility.cpp.

void fcl::constructBox ( const KDOP< 18 > &  bv,
Box &  box,
Transform3f &  tf 
)

Definition at line 982 of file geometric_shapes_utility.cpp.

void fcl::constructBox ( const KDOP< 24 > &  bv,
Box &  box,
Transform3f &  tf 
)

Definition at line 988 of file geometric_shapes_utility.cpp.

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

Definition at line 996 of file geometric_shapes_utility.cpp.

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

Definition at line 1002 of file geometric_shapes_utility.cpp.

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

Definition at line 1010 of file geometric_shapes_utility.cpp.

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

Definition at line 1018 of file geometric_shapes_utility.cpp.

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

Definition at line 1026 of file geometric_shapes_utility.cpp.

void fcl::constructBox ( const KDOP< 16 > &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)

Definition at line 1034 of file geometric_shapes_utility.cpp.

void fcl::constructBox ( const KDOP< 18 > &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)

Definition at line 1040 of file geometric_shapes_utility.cpp.

void fcl::constructBox ( const KDOP< 24 > &  bv,
const Transform3f &  tf_bv,
Box &  box,
Transform3f &  tf 
)

Definition at line 1046 of file geometric_shapes_utility.cpp.

template<typename BV1 , typename BV2 >
static void fcl::convertBV ( const BV1 &  bv1,
const Transform3f &  tf1,
BV2 &  bv2 
) [inline, static]

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

Definition at line 298 of file BV.h.

bool fcl::defaultCollisionFunction ( CollisionObject *  o1,
CollisionObject *  o2,
void *  cdata_ 
)

Default collision callback for two objects o1 and o2 in broad phase. return value means whether the broad phase can stop now.

Definition at line 327 of file test_fcl_utility.cpp.

bool fcl::defaultDistanceFunction ( CollisionObject *  o1,
CollisionObject *  o2,
void *  cdata_,
FCL_REAL &  dist 
)

Default distance callback for two objects o1 and o2 in broad phase. return value means whether the broad phase can stop now. also return dist, i.e. the bmin distance till now.

Definition at line 343 of file test_fcl_utility.cpp.

template<typename NarrowPhaseSolver >
FCL_REAL fcl::distance ( const CollisionObject *  o1,
const CollisionObject *  o2,
const NarrowPhaseSolver *  nsolver,
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.

Definition at line 54 of file distance.cpp.

template<typename NarrowPhaseSolver >
FCL_REAL fcl::distance ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const NarrowPhaseSolver *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)

Definition at line 62 of file distance.cpp.

void fcl::distance ( DistanceTraversalNodeBase *  node,
BVHFrontList *  front_list = NULL,
int  qsize = 2 
)

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

Definition at line 103 of file collision_node.cpp.

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

Definition at line 114 of file distance.cpp.

FCL_REAL fcl::distance ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const DistanceRequest &  request,
DistanceResult &  result 
)

Definition at line 120 of file distance.cpp.

template FCL_REAL fcl::distance ( const CollisionObject *  o1,
const CollisionObject *  o2,
const GJKSolver_libccd *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)
template FCL_REAL fcl::distance ( const CollisionObject *  o1,
const CollisionObject *  o2,
const GJKSolver_indep *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)
template FCL_REAL fcl::distance ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const GJKSolver_libccd *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)
template FCL_REAL fcl::distance ( const CollisionGeometry *  o1,
const Transform3f &  tf1,
const CollisionGeometry *  o2,
const Transform3f &  tf2,
const GJKSolver_indep *  nsolver,
const DistanceRequest &  request,
DistanceResult &  result 
)
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)

Definition at line 1120 of file RSS.cpp.

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.

Definition at line 47 of file OBBRSS.cpp.

FCL_REAL fcl::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.

Todo:
P and Q is not returned, need implementation

Definition at line 187 of file kIOS.cpp.

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

Recurse function for distance, using queue acceleration.

Definition at line 315 of file traversal_recurse.cpp.

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

Recurse function for distance.

Definition at line 195 of file traversal_recurse.cpp.

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

Definition at line 334 of file matrix_3f.h.

void fcl::eulerToMatrix ( FCL_REAL  a,
FCL_REAL  b,
FCL_REAL  c,
Matrix3f &  R 
)

Definition at line 187 of file test_fcl_utility.cpp.

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

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

Definition at line 51 of file BV_fitter.h.

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

Definition at line 439 of file BV_fitter.cpp.

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

Definition at line 462 of file BV_fitter.cpp.

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

Definition at line 481 of file BV_fitter.cpp.

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

Definition at line 500 of file BV_fitter.cpp.

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

Definition at line 214 of file simd_intersect.h.

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]

Definition at line 227 of file simd_intersect.h.

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

Definition at line 187 of file simd_intersect.h.

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]

Definition at line 200 of file simd_intersect.h.

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]

Definition at line 160 of file simd_intersect.h.

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]

Definition at line 173 of file simd_intersect.h.

template<typename BV >
void fcl::generateBVHModel ( BVHModel< BV > &  model,
const Box &  shape,
const Transform3f &  pose 
)

Generate BVH model from box.

Definition at line 50 of file geometric_shape_to_BVH_model.h.

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.

Definition at line 92 of file geometric_shape_to_BVH_model.h.

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.

Definition at line 159 of file geometric_shape_to_BVH_model.h.

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.

Definition at line 172 of file geometric_shape_to_BVH_model.h.

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.

Definition at line 246 of file geometric_shape_to_BVH_model.h.

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.

Definition at line 264 of file geometric_shape_to_BVH_model.h.

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.

Definition at line 336 of file geometric_shape_to_BVH_model.h.

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

Definition at line 195 of file vec_3f.h.

void fcl::generateRandomTransform ( FCL_REAL  extents[6],
Transform3f &  transform 
)

Generate one random transform whose translation is constrained by extents and rotation without constraints. The translation is (x, y, z), and extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <= z <= extents[5].

Definition at line 201 of file test_fcl_utility.cpp.

void fcl::generateRandomTransform_ccd ( FCL_REAL  extents[6],
std::vector< Transform3f > &  transforms,
std::vector< Transform3f > &  transforms2,
FCL_REAL  delta_trans[3],
FCL_REAL  delta_rot,
std::size_t  n,
const std::vector< Vec3f > &  vertices1,
const std::vector< Triangle > &  triangles1,
const std::vector< Vec3f > &  vertices2,
const std::vector< Triangle > &  triangles2 
)

Definition at line 282 of file test_fcl_utility.cpp.

void fcl::generateRandomTransforms ( FCL_REAL  extents[6],
std::vector< Transform3f > &  transforms,
std::size_t  n 
)

Generate n random transforms whose translations are constrained by extents.

Definition at line 219 of file test_fcl_utility.cpp.

void fcl::generateRandomTransforms ( FCL_REAL  extents[6],
FCL_REAL  delta_trans[3],
FCL_REAL  delta_rot,
std::vector< Transform3f > &  transforms,
std::vector< Transform3f > &  transforms2,
std::size_t  n 
)

Generate n random transforms whose translations are constrained by extents. Also generate another transforms2 which have additional random translation & rotation to the transforms generated.

Definition at line 243 of file test_fcl_utility.cpp.

void fcl::generateRandomTransforms_ccd ( FCL_REAL  extents[6],
std::vector< Transform3f > &  transforms,
std::vector< Transform3f > &  transforms2,
FCL_REAL  delta_trans[3],
FCL_REAL  delta_rot,
std::size_t  n,
const std::vector< Vec3f > &  vertices1,
const std::vector< Triangle > &  triangles1,
const std::vector< Vec3f > &  vertices2,
const std::vector< Triangle > &  triangles2 
)

Generate n random tranforms and transform2 with addtional random translation/rotation. The transforms and transform2 are used as initial and goal configurations for the first mesh. The second mesh is in I. This is used for continuous collision detection checking.

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

Definition at line 335 of file taylor_model.cpp.

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

Definition at line 474 of file taylor_model.cpp.

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

Definition at line 404 of file taylor_model.cpp.

void fcl::generateTVector3ForLinearFunc ( TVector3 &  v,
const Vec3f &  position,
const Vec3f &  velocity 
)

Definition at line 210 of file taylor_vector.cpp.

template<typename GJKSolver >
CollisionFunctionMatrix<GJKSolver>& fcl::getCollisionFunctionLookTable ( )

Definition at line 48 of file collision.cpp.

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.

Definition at line 106 of file BVH_utility.cpp.

template<typename GJKSolver >
DistanceFunctionMatrix<GJKSolver>& fcl::getDistanceFunctionLookTable ( )

Definition at line 47 of file distance.cpp.

template<std::size_t N>
void fcl::getDistances ( const Vec3f &  p,
FCL_REAL *  d 
)

Compute the distances to planes with normals from KDOP vectors except those of AABB face planes.

Definition at line 68 of file kDOP.cpp.

template<>
void fcl::getDistances< 5 > ( const Vec3f &  p,
FCL_REAL *  d 
) [inline]

Specification of getDistances.

Definition at line 72 of file kDOP.cpp.

template<>
void fcl::getDistances< 6 > ( const Vec3f &  p,
FCL_REAL *  d 
) [inline]

Definition at line 82 of file kDOP.cpp.

template<>
void fcl::getDistances< 9 > ( const Vec3f &  p,
FCL_REAL *  d 
) [inline]

Definition at line 93 of file kDOP.cpp.

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.

Definition at line 597 of file BVH_utility.cpp.

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

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

Definition at line 532 of file BVH_utility.cpp.

static void fcl::getExtentAndCenter_pointcloud ( Vec3f *  ps,
Vec3f *  ps2,
unsigned int *  indices,
int  n,
Vec3f  axis[3],
Vec3f &  center,
Vec3f &  extent 
) [inline, static]

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

Definition at line 474 of file BVH_utility.cpp.

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.

Compute the RSS bounding volume parameters: radius, rectangle size and the origin. The bounding volume axes are known.

Definition at line 194 of file BVH_utility.cpp.

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 
)

Initialize traversal node for collision between two geometric shapes, given current object transform.

Definition at line 291 of file traversal_node_setup.h.

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 
)

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

Definition at line 314 of file traversal_node_setup.h.

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 
)

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

Definition at line 364 of file traversal_node_setup.h.

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.

Definition at line 452 of file traversal_node_setup.h.

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.

Definition at line 464 of file traversal_node_setup.h.

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.

Definition at line 476 of file traversal_node_setup.h.

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.

Definition at line 488 of file traversal_node_setup.h.

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.

Definition at line 536 of file traversal_node_setup.h.

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.

Definition at line 548 of file traversal_node_setup.h.

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.

Definition at line 560 of file traversal_node_setup.h.

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.

Definition at line 572 of file traversal_node_setup.h.

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

Definition at line 587 of file traversal_node_setup.h.

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.

Definition at line 80 of file traversal_node_setup.cpp.

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.

Definition at line 90 of file traversal_node_setup.cpp.

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.

Definition at line 109 of file traversal_node_setup.cpp.

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.

Definition at line 100 of file traversal_node_setup.cpp.

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 
)

Initialize traversal node for distance between two geometric shapes.

Definition at line 678 of file traversal_node_setup.h.

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

Definition at line 699 of file traversal_node_setup.h.

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.

Definition at line 153 of file traversal_node_setup.cpp.

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.

Definition at line 163 of file traversal_node_setup.cpp.

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.

Definition at line 172 of file traversal_node_setup.cpp.

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 
)

Initialize traversal node for distance computation between one mesh and one shape, given the current transforms.

Definition at line 784 of file traversal_node_setup.h.

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 
)

Initialize traversal node for distance computation between one shape and one mesh, given the current transforms.

Definition at line 831 of file traversal_node_setup.h.

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.

Definition at line 912 of file traversal_node_setup.h.

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.

Definition at line 924 of file traversal_node_setup.h.

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.

Definition at line 936 of file traversal_node_setup.h.

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.

Definition at line 983 of file traversal_node_setup.h.

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.

Definition at line 995 of file traversal_node_setup.h.

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.

Definition at line 1007 of file traversal_node_setup.h.

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

Definition at line 1021 of file traversal_node_setup.h.

template<typename BV >
bool fcl::initialize ( MeshConservativeAdvancementTraversalNode< BV > &  node,
BVHModel< BV > &  model1,
BVHModel< BV > &  model2,
const Matrix3f &  R1,
const Vec3f &  T1,
const Matrix3f &  R2,
const Vec3f &  T2,
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.

Definition at line 1050 of file traversal_node_setup.h.

bool fcl::initialize ( MeshConservativeAdvancementTraversalNodeRSS &  node,
const BVHModel< RSS > &  model1,
const BVHModel< RSS > &  model2,
const Matrix3f &  R1,
const Vec3f &  T1,
const Matrix3f &  R2,
const Vec3f &  T2,
FCL_REAL  w = 1 
) [inline]

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

Definition at line 1100 of file traversal_node_setup.h.

Quaternion3f fcl::inverse ( const Quaternion3f &  q)

inverse of quaternion

Definition at line 324 of file transform.cpp.

Transform3f fcl::inverse ( const Transform3f &  tf)

inverse the transform

Definition at line 386 of file transform.cpp.

template<typename T >
Matrix3fX<T> fcl::inverse ( const Matrix3fX< T > &  R)

Definition at line 434 of file matrix_3f.h.

bool fcl::inVoronoi ( FCL_REAL  a,
FCL_REAL  b,
FCL_REAL  Anorm_dot_B,
FCL_REAL  Anorm_dot_T,
FCL_REAL  A_dot_B,
FCL_REAL  A_dot_T,
FCL_REAL  B_dot_T 
)

Returns whether the nearest point on rectangle edge Pb + B*u, 0 <= u <= b, to the rectangle edge, Pa + A*t, 0 <= t <= a, is within the half space determined by the point Pa and the direction Anorm. A,B, and Anorm are unit vectors. T is the vector between Pa and Pb.

Definition at line 89 of file RSS.cpp.

void fcl::loadOBJFile ( const char *  filename,
std::vector< Vec3f > &  points,
std::vector< Triangle > &  triangles 
)

Load an obj mesh file.

Definition at line 100 of file test_fcl_utility.cpp.

template<typename T >
static Vec3fX<T> fcl::max ( const Vec3fX< T > &  x,
const Vec3fX< T > &  y 
) [inline, static]

Definition at line 183 of file vec_3f.h.

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.

Definition at line 681 of file BVH_utility.cpp.

static FCL_REAL fcl::maximumDistance_mesh ( Vec3f *  ps,
Vec3f *  ps2,
Triangle *  ts,
unsigned int *  indices,
int  n,
const Vec3f &  query 
) [inline, static]

Definition at line 620 of file BVH_utility.cpp.

static FCL_REAL fcl::maximumDistance_pointcloud ( Vec3f *  ps,
Vec3f *  ps2,
unsigned int *  indices,
int  n,
const Vec3f &  query 
) [inline, static]

Definition at line 656 of file BVH_utility.cpp.

OBB fcl::merge_largedist ( const OBB &  b1,
const OBB &  b2 
) [inline]

OBB merge method when the centers of two smaller OBB are far away.

Definition at line 69 of file OBB.cpp.

OBB fcl::merge_smalldist ( const OBB &  b1,
const OBB &  b2 
) [inline]

OBB merge method when the centers of two smaller OBB are close.

Definition at line 117 of file OBB.cpp.

template<typename T >
static Vec3fX<T> fcl::min ( const Vec3fX< T > &  x,
const Vec3fX< T > &  y 
) [inline, static]

Definition at line 177 of file vec_3f.h.

void fcl::minmax ( FCL_REAL  a,
FCL_REAL  b,
FCL_REAL &  minv,
FCL_REAL &  maxv 
) [inline]

Find the smaller and larger one of two values.

Definition at line 45 of file kDOP.cpp.

void fcl::minmax ( FCL_REAL  p,
FCL_REAL &  minv,
FCL_REAL &  maxv 
) [inline]

Merge the interval [minv, maxv] and value p/.

Definition at line 59 of file kDOP.cpp.

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.

Definition at line 87 of file hierarchy_tree.h.

template<typename T >
static Vec3fX<T> fcl::normalize ( const Vec3fX< T > &  v) [inline, static]

Definition at line 154 of file vec_3f.h.

bool fcl::obbDisjoint ( const Matrix3f &  B,
const Vec3f &  T,
const Vec3f &  a,
const Vec3f &  b 
)

Check collision between two boxes: the first box is in configuration (R, T) and its half dimension is set by a; the second box is in identity configuration and its half dimension is set by b.

Definition at line 175 of file OBB.cpp.

template<typename T >
std::ostream& fcl::operator<< ( std::ostream &  out,
const Vec3fX< T > &  x 
)

Definition at line 170 of file vec_3f.h.

static std::ostream& fcl::operator<< ( std::ostream &  o,
const Vec3f &  v 
) [inline, static]

Definition at line 227 of file vec_3f.h.

static std::ostream& fcl::operator<< ( std::ostream &  o,
const Matrix3f &  m 
) [inline, static]

Definition at line 452 of file matrix_3f.h.

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.

Definition at line 371 of file OBB.cpp.

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.

Definition at line 852 of file RSS.cpp.

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.

Definition at line 42 of file OBBRSS.cpp.

bool fcl::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.

Todo:
Not efficient

Definition at line 170 of file kIOS.cpp.

bool fcl::overlap ( double  a1,
double  a2,
double  b1,
double  b2 
)

returns 1 if the intervals overlap, and 0 otherwise

Definition at line 505 of file interval_tree.cpp.

void fcl::propagateBVHFrontListCollisionRecurse ( CollisionTraversalNodeBase *  node,
BVHFrontList *  front_list 
)

Recurse function for front list propagation.

Definition at line 391 of file traversal_recurse.cpp.

template<typename T >
T::meta_type fcl::quadraticForm ( const Matrix3fX< T > &  R,
const Vec3fX< typename T::vector_type > &  v 
)

Definition at line 440 of file matrix_3f.h.

FCL_REAL fcl::rand_interval ( FCL_REAL  rmin,
FCL_REAL  rmax 
)

Definition at line 94 of file test_fcl_utility.cpp.

FCL_REAL fcl::rectDistance ( const Matrix3f &  Rab,
Vec3f const &  Tab,
const FCL_REAL  a[2],
const FCL_REAL  b[2],
Vec3f *  P = NULL,
Vec3f *  Q = NULL 
)

Distance between two oriented rectangles; P and Q (optional return values) are the closest points in the rectangles, both are in the local frame of the first rectangle.

Definition at line 116 of file RSS.cpp.

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 
)

Definition at line 324 of file matrix_3f.h.

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

compute the relative transform between two transforms: tf2 = tf * tf1

Definition at line 392 of file transform.cpp.

TMatrix3 fcl::rotationConstrain ( const TMatrix3 &  m)

Definition at line 289 of file taylor_matrix.cpp.

IMatrix3 fcl::rotationConstrain ( const IMatrix3 &  m)

Definition at line 245 of file interval_matrix.cpp.

void fcl::segCoords ( FCL_REAL &  t,
FCL_REAL &  u,
FCL_REAL  a,
FCL_REAL  b,
FCL_REAL  A_dot_B,
FCL_REAL  A_dot_T,
FCL_REAL  B_dot_T 
)

Finds the parameters t & u corresponding to the two closest points on a pair of line segments. The first segment is defined as Pa + A*t, 0 <= t <= a, where "Pa" is one endpoint of the segment, "A" is a unit vector pointing to the other endpoint, and t is a scalar that produces all the points between the two endpoints. Since "A" is a unit vector, "a" is the segment's length. The second segment is defined as Pb + B*u, 0 <= u <= b. Many of the terms needed by the algorithm are already computed for other purposes,so we just pass these terms into the function instead of complete specifications of each segment. "T" in the dot products is the vector betweeen Pa and Pb. Reference: "On fast computation of distance between line segments." Vladimir J. Lumelsky, in Information Processing Letters, no. 21, pages 55-61, 1985.

Definition at line 58 of file RSS.cpp.

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

Definition at line 95 of file hierarchy_tree.h.

template<>
size_t fcl::select ( const NodeBase< AABB > &  node,
const NodeBase< AABB > &  node1,
const NodeBase< AABB > &  node2 
)

Definition at line 43 of file hierarchy_tree.cpp.

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

Definition at line 105 of file hierarchy_tree.h.

template<>
size_t fcl::select ( const AABB &  query,
const NodeBase< AABB > &  node1,
const NodeBase< AABB > &  node2 
)

Definition at line 57 of file hierarchy_tree.cpp.

void fcl::selfCollide ( CollisionTraversalNodeBase *  node,
BVHFrontList *  front_list = NULL 
)

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

Definition at line 90 of file collision_node.cpp.

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.

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

Definition at line 177 of file traversal_recurse.cpp.

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 
)

Definition at line 196 of file collision_func_matrix.cpp.

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 
)

Definition at line 130 of file distance_func_matrix.cpp.

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 
) [inline, static]

Definition at line 124 of file simd_intersect.h.

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 
) [inline, static]

Definition at line 83 of file simd_intersect.h.

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 
) [inline, static]

Definition at line 50 of file simd_intersect.h.

Halfspace fcl::transform ( const Halfspace &  a,
const Transform3f &  tf 
)

suppose the initial halfspace is n * x <= d after transform (R, T), x --> x' = R x + T and the new half space becomes n' * x' <= d' where n' = R * n and d' = d + n' * T

suppose the initial halfspace is n * x <= d after transform (R, T), x --> x' = R x + T and the new half space becomes n' * x' <= d' where n' = R * n and d' = d + n' * T

Definition at line 218 of file geometric_shapes_utility.cpp.

Plane fcl::transform ( const Plane &  a,
const Transform3f &  tf 
)

suppose the initial halfspace is n * x <= d after transform (R, T), x --> x' = R x + T and the new half space becomes n' * x' <= d' where n' = R * n and d' = d + n' * T

suppose the initial halfspace is n * x <= d after transform (R, T), x --> x' = R x + T and the new half space becomes n' * x' <= d' where n' = R * n and d' = d + n' * T

Definition at line 233 of file geometric_shapes_utility.cpp.

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

Translate the OBB bv.

Definition at line 387 of file OBB.cpp.

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

Translate the RSS bv.

Definition at line 1139 of file RSS.cpp.

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

Translate the OBBRSS bv.

Definition at line 52 of file OBBRSS.cpp.

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

Translate the kIOS BV.

Definition at line 199 of file kIOS.cpp.

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

translate the KDOP BV

Definition at line 230 of file kDOP.cpp.

static AABB fcl::translate ( const AABB &  aabb,
const Vec3f &  t 
) [inline, static]

translate the center of AABB by t

Definition at line 225 of file AABB.h.

template KDOP<16> fcl::translate< 16 > ( const KDOP< 16 > &  ,
const Vec3f &   
)
template KDOP<18> fcl::translate< 18 > ( const KDOP< 18 > &  ,
const Vec3f &   
)
template KDOP<24> fcl::translate< 24 > ( const KDOP< 24 > &  ,
const Vec3f &   
)
template<typename T >
Matrix3fX<T> fcl::transpose ( const Matrix3fX< T > &  R)

Definition at line 428 of file matrix_3f.h.

template<typename T >
static T::meta_type fcl::triple ( const Vec3fX< T > &  x,
const Vec3fX< T > &  y,
const Vec3fX< T > &  z 
) [inline, static]

Definition at line 164 of file vec_3f.h.

void fcl::updateFrontList ( BVHFrontList *  front_list,
int  b1,
int  b2 
) [inline]

Add new front node into the front list.

Definition at line 69 of file BVH_front.h.


Variable Documentation

const double fcl::cosA = sqrt(3.0) / 2.0 [static]

Definition at line 49 of file BV_fitter.cpp.

Definition at line 43 of file interpolation_linear.cpp.

const double fcl::invCosA = 2.0 / sqrt(3.0) [static]

Definition at line 47 of file BV_fitter.cpp.

const double fcl::invSinA = 2 [static]

Definition at line 46 of file BV_fitter.cpp.

const double fcl::kIOS_RATIO = 1.5 [static]

Definition at line 45 of file BV_fitter.cpp.

const double fcl::sinA = 0.5 [static]

Definition at line 48 of file BV_fitter.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


fcl
Author(s): Jia Pan
autogenerated on Tue Jan 15 2013 16:05:31