hpp-fcl  3.0.0
HPP fork of FCL -- The Flexible Collision Library
hpp::fcl Namespace Reference

Namespaces

 detail
 
 details
 
 internal
 
 serialization
 

Classes

class  NaiveCollisionManager
 Brute force N-body collision manager. More...
 
struct  CollisionCallBackBase
 Base callback class for collision queries. This class can be supersed by child classes to provide desired behaviors according to the application (e.g, only listing the potential CollisionObjects in collision). More...
 
struct  DistanceCallBackBase
 Base callback class for distance queries. This class can be supersed by child classes to provide desired behaviors according to the application (e.g, only listing the potential CollisionObjects in collision). More...
 
class  BroadPhaseCollisionManager
 Base class for broad phase collision. It helps to accelerate the collision/distance between N objects. Also support self collision, self distance and collision/distance with another M objects. More...
 
class  BroadPhaseContinuousCollisionManager
 Base class for broad phase continuous collision. It helps to accelerate the continuous collision/distance between N objects. Also support self collision, self distance and collision/distance with another M objects. More...
 
class  DynamicAABBTreeCollisionManager
 
class  DynamicAABBTreeArrayCollisionManager
 
class  IntervalTreeCollisionManager
 Collision manager based on interval tree. More...
 
class  SaPCollisionManager
 Rigorous SAP collision manager. More...
 
class  SpatialHashingCollisionManager
 spatial hashing collision mananger More...
 
class  SSaPCollisionManager
 Simple SAP collision manager. More...
 
struct  CollisionData
 Collision data stores the collision request and the result given by collision algorithm. More...
 
struct  DistanceData
 Distance data stores the distance request and the result given by distance algorithm. More...
 
struct  CollisionCallBackDefault
 Default collision callback to check collision between collision objects. More...
 
struct  DistanceCallBackDefault
 Default distance callback to check collision between collision objects. More...
 
struct  CollisionCallBackCollect
 Collision callback to collect collision pairs potentially in contacts. More...
 
class  AABB
 A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points. More...
 
struct  BVNodeBase
 BVNodeBase encodes the tree structure for BVH. 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...
 
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...
 
struct  OBB
 Oriented bounding box class. More...
 
struct  OBBRSS
 Class merging the OBB and RSS, can handle collision and distance simultaneously. More...
 
struct  RSS
 A class for rectangle sphere-swept bounding volume. 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  BVFitter
 The class for the default algorithm fitting a bounding volume to a set of points. More...
 
class  BVSplitter
 A class describing the split rule that splits each BV node. More...
 
class  BVHModelBase
 A base class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh) More...
 
class  BVHModel
 A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh) More...
 
class  ComputeCollision
 This class reduces the cost of identifying the geometry pair. This is mostly useful for repeated shape-shape queries. More...
 
struct  Contact
 Contact information returned by collision. More...
 
struct  QueryRequest
 base class for all query requests More...
 
struct  QueryResult
 base class for all query results More...
 
struct  CollisionRequest
 request to the collision algorithm More...
 
struct  CollisionResult
 collision result More...
 
struct  ContactPatch
 This structure allows to encode contact patches. A contact patch is defined by a set of points belonging to a subset of a plane passing by p and supported by n, where n = Contact::normal and p = Contact::pos. If we denote by P this plane and by S1 and S2 the first and second shape of a collision pair, a contact patch is represented as a polytope which vertices all belong to P & S1 & S2, where & denotes the set-intersection. Since a contact patch is a subset of a plane supported by n, it has a preferred direction. In HPP-FCL, the Contact::normal points from S1 to S2. In the same way, a contact patch points by default from S1 to S2. More...
 
struct  ContactPatchRequest
 Request for a contact patch computation. More...
 
struct  ContactPatchResult
 Result for a contact patch computation. More...
 
struct  DistanceRequest
 request to the distance computation More...
 
struct  DistanceResult
 distance result 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  ContactPatchSolver
 Solver to compute contact patches, i.e. the intersection between two contact surfaces projected onto the shapes' separating plane. Otherwise said, a contact patch is simply the intersection between two support sets: the support set of shape S1 in direction n and the support set of shape S2 in direction -n, where n is the contact normal (satisfying the optimality conditions of GJK/EPA). More...
 
class  ComputeContactPatch
 This class reduces the cost of identifying the geometry pair. This is usefull for repeated shape-shape queries. More...
 
struct  ContactPatchFunctionMatrix
 The contact patch matrix stores the functions for contact patches computation between different types of objects and provides a uniform call interface. More...
 
class  Triangle
 Triangle with 3 indices for points. More...
 
struct  Quadrilateral
 Quadrilateral with 4 indices for points. More...
 
class  ComputeDistance
 
struct  DistanceFunctionMatrix
 distance matrix stores the functions for distance between different types of objects and provides a uniform call interface More...
 
struct  HFNodeBase
 
struct  HFNode
 
class  HeightField
 Data structure depicting a height field given by the base grid dimensions and the elevation along the grid. More...
 
class  BVFitterTpl
 The class for the default algorithm fitting a bounding volume to a set of points. More...
 
class  BVFitter< OBB >
 Specification of BVFitter for OBB bounding volume. More...
 
class  BVFitter< RSS >
 Specification of BVFitter for RSS bounding volume. More...
 
class  BVFitter< kIOS >
 Specification of BVFitter for kIOS bounding volume. More...
 
class  BVFitter< OBBRSS >
 Specification of BVFitter for OBBRSS bounding volume. More...
 
class  BVFitter< AABB >
 Specification of BVFitter for AABB bounding volume. More...
 
struct  ComputeShapeShapeContactPatch
 Shape-shape contact patch computation. Assumes that csolver and the ContactPatchResult have already been set up by the ContactPatchRequest. More...
 
struct  ComputeShapeShapeContactPatch< OtherShapeType, Plane >
 
struct  ComputeShapeShapeContactPatch< Plane, OtherShapeType >
 
struct  ComputeShapeShapeContactPatch< OtherShapeType, Halfspace >
 
struct  ComputeShapeShapeContactPatch< Halfspace, OtherShapeType >
 
struct  ComputeShapeShapeContactPatch< Plane, Plane >
 
struct  ComputeShapeShapeContactPatch< Plane, Halfspace >
 
struct  ComputeShapeShapeContactPatch< Halfspace, Plane >
 
struct  ComputeShapeShapeContactPatch< Halfspace, Halfspace >
 
class  Transform3f
 Simple transform class used locally by InterpMotion. More...
 
class  MeshLoader
 
class  CachedMeshLoader
 
struct  GJKSolver
 collision and distance solver based on the GJK and EPA algorithms. Originally, GJK and EPA were implemented in fcl which itself took inspiration from the code of the GJK in bullet. Since then, both GJK and EPA have been largely modified to be faster and more robust to numerical accuracy and edge cases. More...
 
class  OcTree
 Octree is one type of collision geometry which can encode uncertainty information in the sensor data. More...
 
class  Convex
 Convex polytope. More...
 
class  ShapeBase
 Base class for all basic geometric shapes. More...
 
class  TriangleP
 Triangle stores the points instead of only indices of points. More...
 
class  Box
 Center at zero point, axis aligned box. More...
 
class  Sphere
 Center at zero point sphere. More...
 
class  Ellipsoid
 Ellipsoid centered at point zero. More...
 
class  Capsule
 Capsule It is \( { x~\in~\mathbb{R}^3, d(x, AB) \leq radius } \) where \( d(x, AB) \) is the distance between the point x and the capsule segment AB, with \( A = (0,0,-halfLength), B = (0,0,halfLength) \). More...
 
class  Cone
 Cone The base of the cone is at \( z = - halfLength \) and the top is at \( z = halfLength \). More...
 
class  Cylinder
 Cylinder along Z axis. The cylinder is defined at its centroid. More...
 
class  ConvexBase
 Base for convex polytope. More...
 
class  Halfspace
 Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the direction of the normal. 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. Note: prefer using a Halfspace instead of a Plane if possible, it has better behavior w.r.t. collision detection algorithms. More...
 
class  Plane
 Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction. Note: prefer using a Halfspace instead of a Plane if possible, it has better behavior w.r.t. collision detection algorithms. More...
 
struct  shape_traits_base
 
struct  shape_traits
 
struct  shape_traits< TriangleP >
 
struct  shape_traits< Box >
 
struct  shape_traits< Sphere >
 
struct  shape_traits< Ellipsoid >
 
struct  shape_traits< Capsule >
 
struct  shape_traits< Cone >
 
struct  shape_traits< Cylinder >
 
struct  shape_traits< ConvexBase >
 
struct  shape_traits< Halfspace >
 
struct  CPUTimes
 
struct  Timer
 This class mimics the way "boost/timer/timer.hpp" operates while using the modern std::chrono library. Importantly, this class will only have an effect for C++11 and more. More...
 
struct  TraversalTraitsCollision
 
struct  TraversalTraitsDistance
 

Typedefs

template<typename S >
using ContinuousCollisionCallBack = bool(*)(ContinuousCollisionObject *o1, ContinuousCollisionObject *o2, void *cdata)
 Callback for continuous collision between two objects. Return value is whether can stop now. More...
 
template<typename S >
using ContinuousDistanceCallBack = bool(*)(ContinuousCollisionObject *o1, ContinuousCollisionObject *o2, S &dist)
 Callback for continuous distance between two objects, Return value is whether can stop now, also return the minimum distance till now. More...
 
using BroadPhaseContinuousCollisionManagerf = BroadPhaseContinuousCollisionManager< float >
 
using BroadPhaseContinuousCollisionManagerd = BroadPhaseContinuousCollisionManager< FCL_REAL >
 
typedef std::list< BVHFrontNodeBVHFrontList
 BVH front list is a list of front nodes. More...
 
using SupportSet = ContactPatch
 Structure used for internal computations. A support set and a contact patch can be represented by the same structure. In fact, a contact patch is the intersection of two support sets, one with PatchDirection::DEFAULT and one with PatchDirection::INVERTED. More...
 
typedef double FCL_REAL
 
typedef Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
 
typedef Eigen::Matrix< FCL_REAL, 2, 1 > Vec2f
 
typedef Eigen::Matrix< FCL_REAL, 6, 1 > Vec6f
 
typedef Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 1 > VecXf
 
typedef Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
 
typedef Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 3, Eigen::RowMajor > Matrixx3f
 
typedef Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 2, Eigen::RowMajor > Matrixx2f
 
typedef Eigen::Matrix< Eigen::DenseIndex, Eigen::Dynamic, 3, Eigen::RowMajor > Matrixx3i
 
typedef Eigen::Matrix< FCL_REAL, Eigen::Dynamic, Eigen::Dynamic > MatrixXf
 
typedef Eigen::Vector2i support_func_guess_t
 
typedef shared_ptr< CollisionObjectCollisionObjectPtr_t
 
typedef shared_ptr< const CollisionObjectCollisionObjectConstPtr_t
 
typedef shared_ptr< CollisionGeometryCollisionGeometryPtr_t
 
typedef shared_ptr< const CollisionGeometryCollisionGeometryConstPtr_t
 
typedef shared_ptr< BVHModelBaseBVHModelPtr_t
 
typedef shared_ptr< OcTreeOcTreePtr_t
 
typedef shared_ptr< const OcTreeOcTreeConstPtr_t
 
typedef Eigen::Quaternion< FCL_REALQuaternion3f
 
typedef Eigen::Quaternion< FCL_REALQuatf
 

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  BVHReturnCode {
  BVH_OK = 0 , BVH_ERR_MODEL_OUT_OF_MEMORY , BVH_ERR_BUILD_OUT_OF_SEQUENCE , BVH_ERR_BUILD_EMPTY_MODEL = -3 ,
  BVH_ERR_BUILD_EMPTY_PREVIOUS_FRAME , BVH_ERR_UNSUPPORTED_FUNCTION = -5 , BVH_ERR_UNUPDATED_MODEL = -6 , BVH_ERR_INCORRECT_DATA = -7 ,
  BVH_ERR_UNKNOWN = -8
}
 Error code for BVH. More...
 
enum  BVHModelType { BVH_MODEL_UNKNOWN , BVH_MODEL_TRIANGLES , BVH_MODEL_POINTCLOUD }
 BVH model type. More...
 
enum  CollisionRequestFlag { CONTACT = 0x00001 , DISTANCE_LOWER_BOUND = 0x00002 , NO_REQUEST = 0x01000 }
 flag declaration for specifying required params in CollisionResult More...
 
enum  OBJECT_TYPE {
  OT_UNKNOWN , OT_BVH , OT_GEOM , OT_OCTREE ,
  OT_HFIELD , OT_COUNT
}
 object type: BVH (mesh, points), basic geometry, octree More...
 
enum  NODE_TYPE {
  BV_UNKNOWN , BV_AABB , BV_OBB , BV_RSS ,
  BV_kIOS , BV_OBBRSS , BV_KDOP16 , BV_KDOP18 ,
  BV_KDOP24 , GEOM_BOX , GEOM_SPHERE , GEOM_CAPSULE ,
  GEOM_CONE , GEOM_CYLINDER , GEOM_CONVEX , GEOM_PLANE ,
  GEOM_HALFSPACE , GEOM_TRIANGLE , GEOM_OCTREE , GEOM_ELLIPSOID ,
  HF_AABB , HF_OBBRSS , NODE_COUNT
}
 traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, triangle), and octree More...
 
enum  GJKInitialGuess { DefaultGuess , CachedGuess , BoundingVolumeGuess }
 Initial guess to use for the GJK algorithm DefaultGuess: Vec3f(1, 0, 0) CachedGuess: previous vector found by GJK or guess cached by the user BoundingVolumeGuess: guess using the centers of the shapes' AABB WARNING: to use BoundingVolumeGuess, computeLocalAABB must have been called on the two shapes. More...
 
enum  GJKVariant { DefaultGJK , PolyakAcceleration , NesterovAcceleration }
 Variant to use for the GJK algorithm. More...
 
enum  GJKConvergenceCriterion { Default , DualityGap , Hybrid }
 Which convergence criterion is used to stop the algorithm (when the shapes are not in collision). (default) VDB: Van den Bergen (A Fast and Robust GJK Implementation, 1999) DG: duality-gap, as used in the Frank-Wolfe and the vanilla 1988 GJK algorithms Hybrid: a mix between VDB and DG. More...
 
enum  GJKConvergenceCriterionType { Relative , Absolute }
 Wether the convergence criterion is scaled on the norm of the solution or not. 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

bool defaultCollisionFunction (CollisionObject *o1, CollisionObject *o2, void *data)
 Provides a simple callback for the collision query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of CollisionData. It simply invokes the collide() method on the culled pair of geometries and stores the results in the data's CollisionResult instance. More...
 
bool defaultDistanceFunction (CollisionObject *o1, CollisionObject *o2, void *data, FCL_REAL &dist)
 Collision data for use with the DefaultContinuousCollisionFunction. It stores the collision request and the result given by the collision algorithm (and stores the conclusion of whether further evaluation of the broadphase collision manager has been deemed unnecessary). More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const AABB &b1, const AABB &b2)
 Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const AABB &b1, const AABB &b2, const CollisionRequest &request, FCL_REAL &sqrDistLowerBound)
 Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
template<short N>
bool overlap (const Matrix3f &, const Vec3f &, const KDOP< N > &, const KDOP< N > &)
 
template<short N>
bool overlap (const Matrix3f &, const Vec3f &, const KDOP< N > &, const KDOP< N > &, const CollisionRequest &, FCL_REAL &)
 
template<short N>
KDOP< N > translate (const KDOP< N > &bv, const Vec3f &t)
 translate the KDOP BV More...
 
kIOS translate (const kIOS &bv, const Vec3f &t)
 Translate the kIOS BV. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2)
 Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, const CollisionRequest &request, FCL_REAL &sqrDistLowerBound)
 Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
FCL_REAL distance (const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
 Approximate distance between two kIOS bounding volumes. More...
 
OBB translate (const OBB &bv, const Vec3f &t)
 Translate the OBB bv. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const OBB &b1, const OBB &b2)
 Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const OBB &b1, const OBB &b2, const CollisionRequest &request, FCL_REAL &sqrDistLowerBound)
 Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
bool obbDisjoint (const Matrix3f &B, const Vec3f &T, const Vec3f &a, const Vec3f &b)
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const OBBRSS &b1, const OBBRSS &b2)
 Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const OBBRSS &b1, const OBBRSS &b2, const CollisionRequest &request, FCL_REAL &sqrDistLowerBound)
 
FCL_REAL distance (const Matrix3f &R0, const Vec3f &T0, const OBBRSS &b1, const OBBRSS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
 Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not NULL, returns the nearest points. More...
 
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) More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const RSS &b1, const RSS &b2)
 Check collision between two RSSs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
bool overlap (const Matrix3f &R0, const Vec3f &T0, const RSS &b1, const RSS &b2, const CollisionRequest &request, FCL_REAL &sqrDistLowerBound)
 Check collision between two RSSs, b1 is in configuration (R0, T0) and b2 is in identity. More...
 
void updateFrontList (BVHFrontList *front_list, unsigned int b1, unsigned int b2)
 Add new front node into the front list. More...
 
template<typename BV >
BVHModel< BV > * BVHExtract (const BVHModel< BV > &model, const Transform3f &pose, const AABB &aabb)
 Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is considered inside. More...
 
template<>
BVHModel< OBB > * BVHExtract (const BVHModel< OBB > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
BVHModel< AABB > * BVHExtract (const BVHModel< AABB > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
BVHModel< RSS > * BVHExtract (const BVHModel< RSS > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
BVHModel< kIOS > * BVHExtract (const BVHModel< kIOS > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
BVHModel< OBBRSS > * BVHExtract (const BVHModel< OBBRSS > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
BVHModel< KDOP< 16 > > * BVHExtract (const BVHModel< KDOP< 16 > > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
BVHModel< KDOP< 18 > > * BVHExtract (const BVHModel< KDOP< 18 > > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
BVHModel< KDOP< 24 > > * BVHExtract (const BVHModel< KDOP< 24 > > &model, const Transform3f &pose, const AABB &aabb)
 
void getCovariance (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3f &M)
 Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to points directly; otherwise refer to triangles. More...
 
void getRadiusAndOriginAndRectangleSize (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Matrix3f &axes, Vec3f &origin, FCL_REAL l[2], FCL_REAL &r)
 Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises. More...
 
void getExtentAndCenter (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3f &axes, Vec3f &center, Vec3f &extent)
 Compute the bounding volume extent and center for a set or subset of points, given the BV axises. More...
 
void circumCircleComputation (const Vec3f &a, const Vec3f &b, const Vec3f &c, Vec3f &center, FCL_REAL &radius)
 Compute the center and radius for a triangle's circumcircle. More...
 
FCL_REAL maximumDistance (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Vec3f &query)
 Compute the maximum distance from a given center point to a point cloud. More...
 
std::size_t collide (const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
 Main collision interface: given two collision objects, and the requirements for contacts, including num of max contacts, whether perform exhaustive collision (i.e., returning returning all the contact points), whether return detailed contact information (i.e., normal, contact point, depth; otherwise only contact primitive id is returned), this function performs the collision between them. Return value is the number of contacts generated between the two objects. More...
 
std::size_t collide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 
void constructContactPatchFrameFromContact (const Contact &contact, ContactPatch &contact_patch)
 Construct a frame from a Contact's position and normal. Because both Contact's position and normal are expressed in the world frame, this frame is also expressed w.r.t the world frame. The origin of the frame is contact.pos and the z-axis of the frame is contact.normal. More...
 
CollisionRequestFlag operator~ (CollisionRequestFlag a)
 
CollisionRequestFlag operator| (CollisionRequestFlag a, CollisionRequestFlag b)
 
CollisionRequestFlag operator& (CollisionRequestFlag a, CollisionRequestFlag b)
 
CollisionRequestFlag operator^ (CollisionRequestFlag a, CollisionRequestFlag b)
 
CollisionRequestFlagoperator|= (CollisionRequestFlag &a, CollisionRequestFlag b)
 
CollisionRequestFlagoperator&= (CollisionRequestFlag &a, CollisionRequestFlag b)
 
CollisionRequestFlagoperator^= (CollisionRequestFlag &a, CollisionRequestFlag b)
 
CollisionGeometryextract (const CollisionGeometry *model, const Transform3f &pose, const AABB &aabb)
 
const char * get_node_type_name (NODE_TYPE node_type)
 Returns the name associated to a NODE_TYPE. More...
 
const char * get_object_type_name (OBJECT_TYPE object_type)
 Returns the name associated to a OBJECT_TYPE. More...
 
void computeContactPatch (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionResult &collision_result, const ContactPatchRequest &request, ContactPatchResult &result)
 Main contact patch computation interface. More...
 
void computeContactPatch (const CollisionObject *o1, const CollisionObject *o2, const CollisionResult &collision_result, const ContactPatchRequest &request, ContactPatchResult &result)
 
FCL_REAL distance (const CollisionObject *o1, const CollisionObject *o2, const DistanceRequest &request, DistanceResult &result)
 Main distance interface: given two collision objects, and the requirements for contacts, including whether return the nearest points, this function performs the distance between them. Return value is the minimum distance generated between the two objects. More...
 
FCL_REAL distance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 
HFNodeBase::FaceOrientation operator& (HFNodeBase::FaceOrientation a, HFNodeBase::FaceOrientation b)
 
int operator& (int a, HFNodeBase::FaceOrientation b)
 
template<typename BV >
void fit (Vec3f *ps, unsigned int n, BV &bv)
 Compute a bounding volume that fits a set of n points. More...
 
template<>
void fit< OBB > (Vec3f *ps, unsigned int n, OBB &bv)
 
template<>
void fit< RSS > (Vec3f *ps, unsigned int n, RSS &bv)
 
template<>
void fit< kIOS > (Vec3f *ps, unsigned int n, kIOS &bv)
 
template<>
void fit< OBBRSS > (Vec3f *ps, unsigned int n, OBBRSS &bv)
 
template<>
void fit< AABB > (Vec3f *ps, unsigned int n, AABB &bv)
 
template<bool InvertShapes, typename OtherShapeType , typename PlaneOrHalfspace >
void computePatchPlaneOrHalfspace (const OtherShapeType &s1, const Transform3f &tf1, const PlaneOrHalfspace &s2, const Transform3f &tf2, const ContactPatchSolver *csolver, const Contact &contact, ContactPatch &contact_patch)
 Computes the contact patch between a Plane/Halfspace and another shape. More...
 
template<typename ShapeType1 , typename ShapeType2 >
void ShapeShapeContactPatch (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionResult &collision_result, const ContactPatchSolver *csolver, const ContactPatchRequest &request, ContactPatchResult &result)
 
template<typename Derived1 , typename Derived2 , typename Derived3 >
void generateCoordinateSystem (const Eigen::MatrixBase< Derived1 > &_w, const Eigen::MatrixBase< Derived2 > &_u, const Eigen::MatrixBase< Derived3 > &_v)
 
template<typename Derived , typename OtherDerived >
void relativeTransform (const Eigen::MatrixBase< Derived > &R1, const Eigen::MatrixBase< OtherDerived > &t1, const Eigen::MatrixBase< Derived > &R2, const Eigen::MatrixBase< OtherDerived > &t2, const Eigen::MatrixBase< Derived > &R, const Eigen::MatrixBase< OtherDerived > &t)
 
template<typename Derived , typename Vector >
void eigen (const Eigen::MatrixBase< Derived > &m, typename Derived::Scalar dout[3], Vector *vout)
 compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors More...
 
template<typename Derived , typename OtherDerived >
bool isEqual (const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const FCL_REAL tol=std::numeric_limits< FCL_REAL >::epsilon() *100)
 
template<typename Derived >
Quatf fromAxisAngle (const Eigen::MatrixBase< Derived > &axis, FCL_REAL angle)
 
Quatf uniformRandomQuaternion ()
 Uniformly random quaternion sphere. Code taken from Pinocchio (https://github.com/stack-of-tasks/pinocchio). More...
 
Matrix3f constructOrthonormalBasisFromVector (const Vec3f &vec)
 Construct othonormal basis from vector. The z-axis is the normalized input vector. More...
 
template<class BoundingVolume >
void loadPolyhedronFromResource (const std::string &resource_path, const fcl::Vec3f &scale, const shared_ptr< BVHModel< BoundingVolume > > &polyhedron)
 Read a mesh file and convert it to a polyhedral mesh. More...
 
OcTreePtr_t makeOctree (const Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 3 > &point_cloud, const FCL_REAL resolution)
 Build an OcTree from a point cloud and a given resolution. More...
 
template<typename T >
size_t computeMemoryFootprint (const T &object)
 Returns the memory footpring of the input object. For POD objects, this function returns the result of sizeof(T) More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Box &shape, const Transform3f &pose)
 Generate BVH model from box. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Sphere &shape, const Transform3f &pose, unsigned int seg, unsigned int ring)
 Generate BVH model from sphere, given the number of segments along longitude and number of rings along latitude. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Sphere &shape, const Transform3f &pose, unsigned int n_faces_for_unit_sphere)
 Generate BVH model from sphere The difference between generateBVHModel is that it gives the number of triangles faces N for a sphere with unit radius. 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. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Cylinder &shape, const Transform3f &pose, unsigned int tot, unsigned int h_num)
 Generate BVH model from cylinder, given the number of segments along circle and the number of segments along axis. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Cylinder &shape, const Transform3f &pose, unsigned int tot_for_unit_cylinder)
 Generate BVH model from cylinder Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius. For cylinder with larger radius, the number of circle split number is r * tot. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Cone &shape, const Transform3f &pose, unsigned int tot, unsigned int h_num)
 Generate BVH model from cone, given the number of segments along circle and the number of segments along axis. More...
 
template<typename BV >
void generateBVHModel (BVHModel< BV > &model, const Cone &shape, const Transform3f &pose, unsigned int tot_for_unit_cone)
 Generate BVH model from cone Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius. For cone with larger radius, the number of circle split number is r * tot. More...
 
template<typename BV , typename S >
void computeBV (const S &s, const Transform3f &tf, BV &bv)
 calculate a bounding volume for a shape in a specific configuration More...
 
template<>
void computeBV< AABB, Box > (const Box &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Sphere > (const Sphere &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Ellipsoid > (const Ellipsoid &e, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Capsule > (const Capsule &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Cone > (const Cone &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Cylinder > (const Cylinder &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, ConvexBase > (const ConvexBase &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, TriangleP > (const TriangleP &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Halfspace > (const Halfspace &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< AABB, Plane > (const Plane &s, const Transform3f &tf, AABB &bv)
 
template<>
void computeBV< OBB, Box > (const Box &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Sphere > (const Sphere &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Capsule > (const Capsule &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Cone > (const Cone &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Cylinder > (const Cylinder &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, ConvexBase > (const ConvexBase &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< OBB, Halfspace > (const Halfspace &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< RSS, Halfspace > (const Halfspace &s, const Transform3f &tf, RSS &bv)
 
template<>
void computeBV< OBBRSS, Halfspace > (const Halfspace &s, const Transform3f &tf, OBBRSS &bv)
 
template<>
void computeBV< kIOS, Halfspace > (const Halfspace &s, const Transform3f &tf, kIOS &bv)
 
template<>
void computeBV< KDOP< 16 >, Halfspace > (const Halfspace &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< 24 >, Halfspace > (const Halfspace &s, const Transform3f &tf, KDOP< 24 > &bv)
 
template<>
void computeBV< OBB, Plane > (const Plane &s, const Transform3f &tf, OBB &bv)
 
template<>
void computeBV< RSS, Plane > (const Plane &s, const Transform3f &tf, RSS &bv)
 
template<>
void computeBV< OBBRSS, Plane > (const Plane &s, const Transform3f &tf, OBBRSS &bv)
 
template<>
void computeBV< kIOS, Plane > (const Plane &s, const Transform3f &tf, kIOS &bv)
 
template<>
void computeBV< KDOP< 16 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 16 > &bv)
 
template<>
void computeBV< KDOP< 18 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 18 > &bv)
 
template<>
void computeBV< KDOP< 24 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 24 > &bv)
 
void constructBox (const AABB &bv, Box &box, Transform3f &tf)
 construct a box shape (with a configuration) from a given bounding volume More...
 
void constructBox (const OBB &bv, Box &box, Transform3f &tf)
 
void constructBox (const OBBRSS &bv, Box &box, Transform3f &tf)
 
void constructBox (const kIOS &bv, Box &box, Transform3f &tf)
 
void constructBox (const RSS &bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 16 > &bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 18 > &bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 24 > &bv, Box &box, Transform3f &tf)
 
void constructBox (const AABB &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const OBB &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const OBBRSS &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const kIOS &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const RSS &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 16 > &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 18 > &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
void constructBox (const KDOP< 24 > &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
Halfspace transform (const Halfspace &a, const Transform3f &tf)
 
Plane transform (const Plane &a, const Transform3f &tf)
 
std::array< Halfspace, 2 > transformToHalfspaces (const Plane &a, const Transform3f &tf)
 
bool obbDisjointAndLowerBoundDistance (const Matrix3f &B, const Vec3f &T, const Vec3f &a, const Vec3f &b, const CollisionRequest &request, FCL_REAL &squaredLowerBoundDistance)
 

Variables

constexpr size_t GJK_DEFAULT_MAX_ITERATIONS = 128
 GJK. More...
 
constexpr FCL_REAL GJK_DEFAULT_TOLERANCE = 1e-6
 
constexpr FCL_REAL GJK_MINIMUM_TOLERANCE = 1e-6
 
constexpr size_t EPA_DEFAULT_MAX_ITERATIONS = 64
 
constexpr FCL_REAL EPA_DEFAULT_TOLERANCE = 1e-6
 
constexpr FCL_REAL EPA_MINIMUM_TOLERANCE = 1e-6
 

Typedef Documentation

◆ BroadPhaseContinuousCollisionManagerd

◆ BroadPhaseContinuousCollisionManagerf

◆ BVHFrontList

BVH front list is a list of front nodes.

◆ BVHModelPtr_t

◆ CollisionGeometryConstPtr_t

◆ CollisionGeometryPtr_t

◆ CollisionObjectConstPtr_t

◆ CollisionObjectPtr_t

◆ ContinuousCollisionCallBack

template<typename S >
using hpp::fcl::ContinuousCollisionCallBack = typedef bool (*)(ContinuousCollisionObject* o1, ContinuousCollisionObject* o2, void* cdata)

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

◆ ContinuousDistanceCallBack

template<typename S >
using hpp::fcl::ContinuousDistanceCallBack = typedef bool (*)(ContinuousCollisionObject* o1, ContinuousCollisionObject* o2, S& dist)

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

◆ FCL_REAL

typedef double hpp::fcl::FCL_REAL

◆ Matrix3f

typedef Eigen::Matrix<FCL_REAL, 3, 3> hpp::fcl::Matrix3f

◆ Matrixx2f

typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 2, Eigen::RowMajor> hpp::fcl::Matrixx2f

◆ Matrixx3f

typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 3, Eigen::RowMajor> hpp::fcl::Matrixx3f

◆ Matrixx3i

typedef Eigen::Matrix<Eigen::DenseIndex, Eigen::Dynamic, 3, Eigen::RowMajor> hpp::fcl::Matrixx3i

◆ MatrixXf

typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, Eigen::Dynamic> hpp::fcl::MatrixXf

◆ OcTreeConstPtr_t

typedef shared_ptr<const OcTree> hpp::fcl::OcTreeConstPtr_t

◆ OcTreePtr_t

typedef shared_ptr<OcTree> hpp::fcl::OcTreePtr_t

◆ Quaternion3f

typedef Eigen::Quaternion<FCL_REAL> hpp::fcl::Quaternion3f

◆ Quatf

typedef Eigen::Quaternion<FCL_REAL> hpp::fcl::Quatf

◆ support_func_guess_t

typedef Eigen::Vector2i hpp::fcl::support_func_guess_t

◆ SupportSet

Structure used for internal computations. A support set and a contact patch can be represented by the same structure. In fact, a contact patch is the intersection of two support sets, one with PatchDirection::DEFAULT and one with PatchDirection::INVERTED.

Note
A support set with DEFAULT direction is the support set of a shape in the direction given by +n, where n is the z-axis of the frame's patch rotation. An INVERTED support set is the support set of a shape in the direction -n.

◆ Vec2f

typedef Eigen::Matrix<FCL_REAL, 2, 1> hpp::fcl::Vec2f

◆ Vec3f

typedef Eigen::Matrix<FCL_REAL, 3, 1> hpp::fcl::Vec3f

◆ Vec6f

typedef Eigen::Matrix<FCL_REAL, 6, 1> hpp::fcl::Vec6f

◆ VecXf

typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 1> hpp::fcl::VecXf

Enumeration Type Documentation

◆ BVHBuildState

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 after beginReplaceModel(), state for replacing geometry primitives

◆ BVHModelType

BVH model type.

Enumerator
BVH_MODEL_UNKNOWN 
BVH_MODEL_TRIANGLES 

unknown model type

BVH_MODEL_POINTCLOUD 

triangle model

point cloud model

◆ BVHReturnCode

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.

◆ CollisionRequestFlag

flag declaration for specifying required params in CollisionResult

Enumerator
CONTACT 
DISTANCE_LOWER_BOUND 
NO_REQUEST 

◆ GJKConvergenceCriterion

Which convergence criterion is used to stop the algorithm (when the shapes are not in collision). (default) VDB: Van den Bergen (A Fast and Robust GJK Implementation, 1999) DG: duality-gap, as used in the Frank-Wolfe and the vanilla 1988 GJK algorithms Hybrid: a mix between VDB and DG.

Enumerator
Default 
DualityGap 
Hybrid 

◆ GJKConvergenceCriterionType

Wether the convergence criterion is scaled on the norm of the solution or not.

Enumerator
Relative 
Absolute 

◆ GJKInitialGuess

Initial guess to use for the GJK algorithm DefaultGuess: Vec3f(1, 0, 0) CachedGuess: previous vector found by GJK or guess cached by the user BoundingVolumeGuess: guess using the centers of the shapes' AABB WARNING: to use BoundingVolumeGuess, computeLocalAABB must have been called on the two shapes.

Enumerator
DefaultGuess 
CachedGuess 
BoundingVolumeGuess 

◆ GJKVariant

Variant to use for the GJK algorithm.

Enumerator
DefaultGJK 
PolyakAcceleration 
NesterovAcceleration 

◆ NODE_TYPE

traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, 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 
GEOM_ELLIPSOID 
HF_AABB 
HF_OBBRSS 
NODE_COUNT 

◆ OBJECT_TYPE

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

Enumerator
OT_UNKNOWN 
OT_BVH 
OT_GEOM 
OT_OCTREE 
OT_HFIELD 
OT_COUNT 

◆ SplitMethodType

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

Enumerator
SPLIT_METHOD_MEAN 
SPLIT_METHOD_MEDIAN 
SPLIT_METHOD_BV_CENTER 

Function Documentation

◆ BVHExtract() [1/9]

template<>
BVHModel<AABB>* hpp::fcl::BVHExtract ( const BVHModel< AABB > &  model,
const Transform3f pose,
const AABB aabb 
)

◆ BVHExtract() [2/9]

template<typename BV >
BVHModel<BV>* hpp::fcl::BVHExtract ( const BVHModel< BV > &  model,
const Transform3f pose,
const AABB aabb 
)

Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is considered inside.

◆ BVHExtract() [3/9]

template<>
BVHModel<KDOP<16> >* hpp::fcl::BVHExtract ( const BVHModel< KDOP< 16 > > &  model,
const Transform3f pose,
const AABB aabb 
)

◆ BVHExtract() [4/9]

template<>
BVHModel<KDOP<18> >* hpp::fcl::BVHExtract ( const BVHModel< KDOP< 18 > > &  model,
const Transform3f pose,
const AABB aabb 
)

◆ BVHExtract() [5/9]

template<>
BVHModel<KDOP<24> >* hpp::fcl::BVHExtract ( const BVHModel< KDOP< 24 > > &  model,
const Transform3f pose,
const AABB aabb 
)

◆ BVHExtract() [6/9]

template<>
BVHModel<kIOS>* hpp::fcl::BVHExtract ( const BVHModel< kIOS > &  model,
const Transform3f pose,
const AABB aabb 
)

◆ BVHExtract() [7/9]

template<>
BVHModel<OBB>* hpp::fcl::BVHExtract ( const BVHModel< OBB > &  model,
const Transform3f pose,
const AABB aabb 
)

◆ BVHExtract() [8/9]

template<>
BVHModel<OBBRSS>* hpp::fcl::BVHExtract ( const BVHModel< OBBRSS > &  model,
const Transform3f pose,
const AABB aabb 
)

◆ BVHExtract() [9/9]

template<>
BVHModel<RSS>* hpp::fcl::BVHExtract ( const BVHModel< RSS > &  model,
const Transform3f pose,
const AABB aabb 
)

◆ circumCircleComputation()

void hpp::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.

◆ collide() [1/2]

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

◆ collide() [2/2]

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

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

◆ computeBV()

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

calculate a bounding volume for a shape in a specific configuration

◆ computeBV< AABB, Box >()

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

◆ computeBV< AABB, Capsule >()

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

◆ computeBV< AABB, Cone >()

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

◆ computeBV< AABB, ConvexBase >()

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

◆ computeBV< AABB, Cylinder >()

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

◆ computeBV< AABB, Ellipsoid >()

template<>
void hpp::fcl::computeBV< AABB, Ellipsoid > ( const Ellipsoid e,
const Transform3f tf,
AABB bv 
)

◆ computeBV< AABB, Halfspace >()

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

◆ computeBV< AABB, Plane >()

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

◆ computeBV< AABB, Sphere >()

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

◆ computeBV< AABB, TriangleP >()

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

◆ computeBV< KDOP< 16 >, Halfspace >()

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

◆ computeBV< KDOP< 16 >, Plane >()

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

◆ computeBV< KDOP< 18 >, Halfspace >()

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

◆ computeBV< KDOP< 18 >, Plane >()

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

◆ computeBV< KDOP< 24 >, Halfspace >()

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

◆ computeBV< KDOP< 24 >, Plane >()

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

◆ computeBV< kIOS, Halfspace >()

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

◆ computeBV< kIOS, Plane >()

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

◆ computeBV< OBB, Box >()

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

◆ computeBV< OBB, Capsule >()

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

◆ computeBV< OBB, Cone >()

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

◆ computeBV< OBB, ConvexBase >()

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

◆ computeBV< OBB, Cylinder >()

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

◆ computeBV< OBB, Halfspace >()

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

◆ computeBV< OBB, Plane >()

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

◆ computeBV< OBB, Sphere >()

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

◆ computeBV< OBBRSS, Halfspace >()

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

◆ computeBV< OBBRSS, Plane >()

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

◆ computeBV< RSS, Halfspace >()

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

◆ computeBV< RSS, Plane >()

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

◆ computeContactPatch() [1/2]

void hpp::fcl::computeContactPatch ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const CollisionResult collision_result,
const ContactPatchRequest request,
ContactPatchResult result 
)

Main contact patch computation interface.

Note
Please see ContactPatchRequest and ContactPatchResult for more info on the content of the input/output of this function. Also, please read ContactPatch if you want to fully understand what is meant by "contact patch".

◆ computeContactPatch() [2/2]

void hpp::fcl::computeContactPatch ( const CollisionObject o1,
const CollisionObject o2,
const CollisionResult collision_result,
const ContactPatchRequest request,
ContactPatchResult result 
)

◆ computeMemoryFootprint()

template<typename T >
size_t hpp::fcl::computeMemoryFootprint ( const T &  object)

Returns the memory footpring of the input object. For POD objects, this function returns the result of sizeof(T)

Parameters
[in]objectwhose memory footprint needs to be evaluated.
Returns
the memory footprint of the input object.

◆ computePatchPlaneOrHalfspace()

template<bool InvertShapes, typename OtherShapeType , typename PlaneOrHalfspace >
void hpp::fcl::computePatchPlaneOrHalfspace ( const OtherShapeType &  s1,
const Transform3f tf1,
const PlaneOrHalfspace &  s2,
const Transform3f tf2,
const ContactPatchSolver csolver,
const Contact contact,
ContactPatch contact_patch 
)

Computes the contact patch between a Plane/Halfspace and another shape.

Template Parameters
InvertShapesset to true if the first shape of the collision pair is s2 and not s1 (if you had to invert (s1, tf1) and (s2, tf2) when calling this function).

◆ constructBox() [1/16]

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

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

◆ constructBox() [2/16]

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

◆ constructBox() [3/16]

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

◆ constructBox() [4/16]

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

◆ constructBox() [5/16]

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

◆ constructBox() [6/16]

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

◆ constructBox() [7/16]

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

◆ constructBox() [8/16]

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

◆ constructBox() [9/16]

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

◆ constructBox() [10/16]

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

◆ constructBox() [11/16]

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

◆ constructBox() [12/16]

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

◆ constructBox() [13/16]

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

◆ constructBox() [14/16]

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

◆ constructBox() [15/16]

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

◆ constructBox() [16/16]

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

◆ constructContactPatchFrameFromContact()

void hpp::fcl::constructContactPatchFrameFromContact ( const Contact contact,
ContactPatch contact_patch 
)
inline

Construct a frame from a Contact's position and normal. Because both Contact's position and normal are expressed in the world frame, this frame is also expressed w.r.t the world frame. The origin of the frame is contact.pos and the z-axis of the frame is contact.normal.

◆ constructOrthonormalBasisFromVector()

Matrix3f hpp::fcl::constructOrthonormalBasisFromVector ( const Vec3f vec)
inline

Construct othonormal basis from vector. The z-axis is the normalized input vector.

◆ defaultCollisionFunction()

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

Provides a simple callback for the collision query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of CollisionData. It simply invokes the collide() method on the culled pair of geometries and stores the results in the data's CollisionResult instance.

This callback will cause the broadphase evaluation to stop if:

  • the collision requests disables cost and
  • the collide() reports a collision for the culled pair, and
  • we've reported the number of contacts requested in the CollisionRequest.

For a given instance of CollisionData, if broadphase evaluation has already terminated (i.e., defaultCollisionFunction() returned true), subsequent invocations with the same instance of CollisionData will return immediately, requesting termination of broadphase evaluation (i.e., return true).

Parameters
o1The first object in the culled pair.
o2The second object in the culled pair.
dataA non-null pointer to a CollisionData instance.
Returns
true if the broadphase evaluation should stop.
Template Parameters
SThe scalar type with which the computation will be performed.

◆ defaultDistanceFunction()

bool hpp::fcl::defaultDistanceFunction ( CollisionObject o1,
CollisionObject o2,
void *  data,
FCL_REAL dist 
)

Collision data for use with the DefaultContinuousCollisionFunction. It stores the collision request and the result given by the collision algorithm (and stores the conclusion of whether further evaluation of the broadphase collision manager has been deemed unnecessary).

Provides a simple callback for the continuous collision query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of DefaultContinuousCollisionData. It simply invokes the collide() method on the culled pair of geometries and stores the results in the data's ContinuousCollisionResult instance.

This callback will never cause the broadphase evaluation to terminate early. However, if the done member of the DefaultContinuousCollisionData is set to true, this method will simply return without doing any computation.

For a given instance of DefaultContinuousCollisionData, if broadphase evaluation has already terminated (i.e., DefaultContinuousCollisionFunction() returned true), subsequent invocations with the same instance of CollisionData will return immediately, requesting termination of broadphase evaluation (i.e., return true).

Parameters
o1The first object in the culled pair.
o2The second object in the culled pair.
dataA non-null pointer to a CollisionData instance.
Returns
True if the broadphase evaluation should stop.
Template Parameters
SThe scalar type with which the computation will be performed.

Provides a simple callback for the distance query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of DistanceData. It simply invokes the distance() method on the culled pair of geometries and stores the results in the data's DistanceResult instance.

This callback will cause the broadphase evaluation to stop if:

  • The distance is less than or equal to zero (i.e., the pair is in contact).

For a given instance of DistanceData, if broadphase evaluation has already terminated (i.e., defaultDistanceFunction() returned true), subsequent invocations with the same instance of DistanceData will simply report the previously reported minimum distance and request termination of broadphase evaluation (i.e., return true).

Parameters
o1The first object in the culled pair.
o2The second object in the culled pair.
dataA non-null pointer to a DistanceData instance.
distThe distance computed by distance().
Returns
true if the broadphase evaluation should stop.
Template Parameters
SThe scalar type with which the computation will be performed.

◆ distance() [1/2]

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

◆ distance() [2/2]

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

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

◆ eigen()

template<typename Derived , typename Vector >
void hpp::fcl::eigen ( const Eigen::MatrixBase< Derived > &  m,
typename Derived::Scalar  dout[3],
Vector *  vout 
)

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

◆ extract()

CollisionGeometry* hpp::fcl::extract ( const CollisionGeometry model,
const Transform3f pose,
const AABB aabb 
)

◆ fit()

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

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

◆ fit< AABB >()

template<>
void hpp::fcl::fit< AABB > ( Vec3f ps,
unsigned int  n,
AABB bv 
)

◆ fit< kIOS >()

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

◆ fit< OBB >()

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

◆ fit< OBBRSS >()

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

◆ fit< RSS >()

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

◆ fromAxisAngle()

template<typename Derived >
Quatf hpp::fcl::fromAxisAngle ( const Eigen::MatrixBase< Derived > &  axis,
FCL_REAL  angle 
)
inline

◆ generateBVHModel() [1/7]

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

Generate BVH model from box.

◆ generateBVHModel() [2/7]

template<typename BV >
void hpp::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.

◆ generateBVHModel() [3/7]

template<typename BV >
void hpp::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.

◆ generateBVHModel() [4/7]

template<typename BV >
void hpp::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.

◆ generateBVHModel() [5/7]

template<typename BV >
void hpp::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.

◆ generateBVHModel() [6/7]

template<typename BV >
void hpp::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.

◆ generateBVHModel() [7/7]

template<typename BV >
void hpp::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.

◆ generateCoordinateSystem()

template<typename Derived1 , typename Derived2 , typename Derived3 >
void hpp::fcl::generateCoordinateSystem ( const Eigen::MatrixBase< Derived1 > &  _w,
const Eigen::MatrixBase< Derived2 > &  _u,
const Eigen::MatrixBase< Derived3 > &  _v 
)

◆ get_node_type_name()

const char* hpp::fcl::get_node_type_name ( NODE_TYPE  node_type)
inline

Returns the name associated to a NODE_TYPE.

◆ get_object_type_name()

const char* hpp::fcl::get_object_type_name ( OBJECT_TYPE  object_type)
inline

Returns the name associated to a OBJECT_TYPE.

◆ getCovariance()

void hpp::fcl::getCovariance ( Vec3f ps,
Vec3f ps2,
Triangle ts,
unsigned int *  indices,
unsigned 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.

◆ getExtentAndCenter()

void hpp::fcl::getExtentAndCenter ( Vec3f ps,
Vec3f ps2,
Triangle ts,
unsigned int *  indices,
unsigned int  n,
Matrix3f axes,
Vec3f center,
Vec3f extent 
)

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

◆ getRadiusAndOriginAndRectangleSize()

void hpp::fcl::getRadiusAndOriginAndRectangleSize ( Vec3f ps,
Vec3f ps2,
Triangle ts,
unsigned int *  indices,
unsigned int  n,
const Matrix3f axes,
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.

◆ isEqual()

template<typename Derived , typename OtherDerived >
bool hpp::fcl::isEqual ( const Eigen::MatrixBase< Derived > &  lhs,
const Eigen::MatrixBase< OtherDerived > &  rhs,
const FCL_REAL  tol = std::numeric_limits<FCL_REAL>::epsilon() * 100 
)

◆ loadPolyhedronFromResource()

template<class BoundingVolume >
void hpp::fcl::loadPolyhedronFromResource ( const std::string &  resource_path,
const fcl::Vec3f scale,
const shared_ptr< BVHModel< BoundingVolume > > &  polyhedron 
)
inline

Read a mesh file and convert it to a polyhedral mesh.

Parameters
[in]resource_pathPath to the ressource mesh file to be read
[in]scaleScale to apply when reading the ressource
[out]polyhedronThe resulted polyhedron

◆ makeOctree()

OcTreePtr_t hpp::fcl::makeOctree ( const Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 3 > &  point_cloud,
const FCL_REAL  resolution 
)

Build an OcTree from a point cloud and a given resolution.

Parameters
[in]point_cloudThe input points to insert in the OcTree
[in]resolutionof the octree.
Returns
An OcTree that can be used for collision checking and more.

◆ maximumDistance()

FCL_REAL hpp::fcl::maximumDistance ( Vec3f ps,
Vec3f ps2,
Triangle ts,
unsigned int *  indices,
unsigned int  n,
const Vec3f query 
)

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

◆ obbDisjointAndLowerBoundDistance()

bool hpp::fcl::obbDisjointAndLowerBoundDistance ( const Matrix3f B,
const Vec3f T,
const Vec3f a,
const Vec3f b,
const CollisionRequest request,
FCL_REAL squaredLowerBoundDistance 
)

◆ operator&()

CollisionRequestFlag hpp::fcl::operator& ( CollisionRequestFlag  a,
CollisionRequestFlag  b 
)
inline

◆ operator&=()

CollisionRequestFlag& hpp::fcl::operator&= ( CollisionRequestFlag a,
CollisionRequestFlag  b 
)
inline

◆ operator^()

CollisionRequestFlag hpp::fcl::operator^ ( CollisionRequestFlag  a,
CollisionRequestFlag  b 
)
inline

◆ operator^=()

CollisionRequestFlag& hpp::fcl::operator^= ( CollisionRequestFlag a,
CollisionRequestFlag  b 
)
inline

◆ operator|()

CollisionRequestFlag hpp::fcl::operator| ( CollisionRequestFlag  a,
CollisionRequestFlag  b 
)
inline

◆ operator|=()

CollisionRequestFlag& hpp::fcl::operator|= ( CollisionRequestFlag a,
CollisionRequestFlag  b 
)
inline

◆ operator~()

CollisionRequestFlag hpp::fcl::operator~ ( CollisionRequestFlag  a)
inline

◆ relativeTransform()

template<typename Derived , typename OtherDerived >
void hpp::fcl::relativeTransform ( const Eigen::MatrixBase< Derived > &  R1,
const Eigen::MatrixBase< OtherDerived > &  t1,
const Eigen::MatrixBase< Derived > &  R2,
const Eigen::MatrixBase< OtherDerived > &  t2,
const Eigen::MatrixBase< Derived > &  R,
const Eigen::MatrixBase< OtherDerived > &  t 
)

◆ ShapeShapeContactPatch()

template<typename ShapeType1 , typename ShapeType2 >
void hpp::fcl::ShapeShapeContactPatch ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const CollisionResult collision_result,
const ContactPatchSolver csolver,
const ContactPatchRequest request,
ContactPatchResult result 
)

◆ transform() [1/2]

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

◆ transform() [2/2]

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

◆ transformToHalfspaces()

std::array<Halfspace, 2> hpp::fcl::transformToHalfspaces ( const Plane a,
const Transform3f tf 
)

◆ uniformRandomQuaternion()

Quatf hpp::fcl::uniformRandomQuaternion ( )
inline

Uniformly random quaternion sphere. Code taken from Pinocchio (https://github.com/stack-of-tasks/pinocchio).

◆ updateFrontList()

void hpp::fcl::updateFrontList ( BVHFrontList front_list,
unsigned int  b1,
unsigned int  b2 
)
inline

Add new front node into the front list.

Variable Documentation

◆ EPA_DEFAULT_MAX_ITERATIONS

constexpr size_t hpp::fcl::EPA_DEFAULT_MAX_ITERATIONS = 64
constexpr

EPA EPA build a polytope which maximum size is:

  • #iterations + 4 vertices
  • 2 x #iterations + 4 faces

◆ EPA_DEFAULT_TOLERANCE

constexpr FCL_REAL hpp::fcl::EPA_DEFAULT_TOLERANCE = 1e-6
constexpr

◆ EPA_MINIMUM_TOLERANCE

constexpr FCL_REAL hpp::fcl::EPA_MINIMUM_TOLERANCE = 1e-6
constexpr

◆ GJK_DEFAULT_MAX_ITERATIONS

constexpr size_t hpp::fcl::GJK_DEFAULT_MAX_ITERATIONS = 128
constexpr

GJK.

◆ GJK_DEFAULT_TOLERANCE

constexpr FCL_REAL hpp::fcl::GJK_DEFAULT_TOLERANCE = 1e-6
constexpr

◆ GJK_MINIMUM_TOLERANCE

constexpr FCL_REAL hpp::fcl::GJK_MINIMUM_TOLERANCE = 1e-6
constexpr

Note: if the considered shapes are on the order of the meter, and the convergence criterion of GJK is the default VDB criterion, setting a tolerance of 1e-6 on the GJK algorithm makes it precise up to the micro-meter. The same is true for EPA.