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

Namespaces

 details
 
 internal
 
 time
 Namespace containing time datatypes and time operations.
 
 tools
 

Classes

class  AABB
 A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points. More...
 
class  Box
 Center at zero point, axis aligned box. More...
 
class  BVFitter
 The class for the default algorithm fitting a bounding volume to a set of points. More...
 
class  BVFitter< AABB >
 Specification of BVFitter for AABB bounding volume. 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  BVFitterTpl
 The class for the default algorithm fitting a bounding volume to a set of points. 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...
 
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...
 
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  CachedMeshLoader
 
class  Capsule
 Capsule It is $ { x \in \mathcal{R}^3, d(x, AB) < 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...
 
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  Cone
 Cone The base of the cone is at $ z = - halfLength $ and the top is at $ z = halfLength $. More...
 
struct  Contact
 Contact information returned by collision. More...
 
class  Convex
 Convex polytope. More...
 
class  ConvexBase
 Base for convex polytope. More...
 
class  Cylinder
 Cylinder along Z axis. The cylinder is defined at its centroid. More...
 
struct  DistanceFunctionMatrix
 distance matrix stores the functions for distance between different types of objects and provides a uniform call interface More...
 
struct  DistanceRequest
 request to the distance computation More...
 
struct  DistanceResult
 distance result More...
 
struct  GJKSolver
 collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the GJK in bullet) 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  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  MeshLoader
 
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  Plane
 Infinite plane. More...
 
class  RSS
 A class for rectangle sphere-swept bounding volume. More...
 
class  ShapeBase
 Base class for all basic geometric shapes. More...
 
class  Sphere
 Center at zero point sphere. More...
 
class  Transform3f
 Simple transform class used locally by InterpMotion. More...
 
struct  TraversalTraitsCollision
 
struct  TraversalTraitsDistance
 
class  Triangle
 Triangle with 3 indices for points. More...
 
class  TriangleP
 Triangle stores the points instead of only indices of points. More...
 

Typedefs

typedef std::list< BVHFrontNodeBVHFrontList
 BVH front list is a list of front nodes. More...
 
typedef double FCL_REAL
 
typedef boost::uint64_t FCL_INT64
 
typedef boost::int64_t FCL_UINT64
 
typedef boost::uint32_t FCL_UINT32
 
typedef boost::int32_t FCL_INT32
 
typedef Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
 
typedef Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
 
typedef boost::shared_ptr< CollisionObjectCollisionObjectPtr_t
 
typedef boost::shared_ptr< const CollisionObjectCollisionObjectConstPtr_t
 
typedef boost::shared_ptr< CollisionGeometryCollisionGeometryPtr_t
 
typedef boost::shared_ptr< const CollisionGeometryCollisionGeometryConstPtr_t
 
typedef boost::shared_ptr< BVHModelBaseBVHModelPtr_t
 
typedef Eigen::Quaternion< FCL_REALQuaternion3f
 

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 = -1, BVH_ERR_BUILD_OUT_OF_SEQUENCE = -2, BVH_ERR_BUILD_EMPTY_MODEL = -3,
  BVH_ERR_BUILD_EMPTY_PREVIOUS_FRAME = -4, BVH_ERR_UNSUPPORTED_FUNCTION = -5, BVH_ERR_UNUPDATED_MODEL = -6, BVH_ERR_INCORRECT_DATA = -7,
  BVH_ERR_UNKNOWN = -8
}
 Error code for BVH. More...
 
enum  BVHModelType { BVH_MODEL_UNKNOWN, BVH_MODEL_TRIANGLES, BVH_MODEL_POINTCLOUD }
 BVH model type. More...
 
enum  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_COUNT
}
 object type: BVH (mesh, points), basic geometry, octree More...
 
enum  NODE_TYPE {
  BV_UNKNOWN, BV_AABB, BV_OBB, BV_RSS,
  BV_kIOS, BV_OBBRSS, BV_KDOP16, BV_KDOP18,
  BV_KDOP24, GEOM_BOX, GEOM_SPHERE, GEOM_CAPSULE,
  GEOM_CONE, GEOM_CYLINDER, GEOM_CONVEX, GEOM_PLANE,
  GEOM_HALFSPACE, GEOM_TRIANGLE, GEOM_OCTREE, NODE_COUNT
}
 traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, capsule, cone, cylinder, convex, plane, triangle), and octree More...
 
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 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, int b1, 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...
 
void getCovariance (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, Matrix3f &M)
 Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to points directly; otherwise refer to triangles. More...
 
void getRadiusAndOriginAndRectangleSize (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, 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, 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, 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)
 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...
 
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)
 
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)
 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...
 
template<typename BV >
void fit (Vec3f *ps, int n, BV &bv)
 Compute a bounding volume that fits a set of n points. More...
 
template<>
void fit< OBB > (Vec3f *ps, int n, OBB &bv)
 
template<>
void fit< RSS > (Vec3f *ps, int n, RSS &bv)
 
template<>
void fit< kIOS > (Vec3f *ps, int n, kIOS &bv)
 
template<>
void fit< OBBRSS > (Vec3f *ps, int n, OBBRSS &bv)
 
template<>
void fit< AABB > (Vec3f *ps, int n, AABB &bv)
 
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 >
Quaternion3f fromAxisAngle (const Eigen::MatrixBase< Derived > &axis, FCL_REAL angle)
 
template<class BoundingVolume >
void loadPolyhedronFromResource (const std::string &resource_path, const fcl::Vec3f &scale, const boost::shared_ptr< BVHModel< BoundingVolume > > &polyhedron)
 Read a mesh file and convert it to a polyhedral mesh. 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, 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)
 
bool obbDisjointAndLowerBoundDistance (const Matrix3f &B, const Vec3f &T, const Vec3f &a, const Vec3f &b, const CollisionRequest &request, FCL_REAL &squaredLowerBoundDistance)
 
Shape intersection specializations
 HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF (Sphere,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Sphere, Capsule,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Sphere, Halfspace,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Sphere, Plane,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Box, Halfspace,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Box, Plane,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Capsule, Halfspace,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Capsule, Plane,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Cylinder, Halfspace,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Cylinder, Plane,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Cone, Halfspace,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Cone, Plane,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF (Halfspace,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF (Plane,)
 
 HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR (Plane, Halfspace,)
 
Shape triangle interaction specializations
 HPP_FCL_DECLARE_SHAPE_TRIANGLE (Sphere,)
 
 HPP_FCL_DECLARE_SHAPE_TRIANGLE (Halfspace,)
 
 HPP_FCL_DECLARE_SHAPE_TRIANGLE (Plane,)
 
Shape distance specializations
 HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR (Sphere, Box,)
 
 HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR (Sphere, Capsule,)
 
 HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR (Sphere, Cylinder,)
 
 HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF (Sphere,)
 
 HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF (Capsule,)
 
 HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF (TriangleP,)
 

Variables

const int GST_INDEP HPP_FCL_DEPRECATED = 0
 

Typedef Documentation

◆ BVHFrontList

BVH front list is a list of front nodes.

◆ BVHModelPtr_t

typedef boost::shared_ptr<BVHModelBase> hpp::fcl::BVHModelPtr_t

◆ CollisionGeometryConstPtr_t

typedef boost::shared_ptr<const CollisionGeometry> hpp::fcl::CollisionGeometryConstPtr_t

◆ CollisionGeometryPtr_t

◆ CollisionObjectConstPtr_t

typedef boost::shared_ptr< const CollisionObject> hpp::fcl::CollisionObjectConstPtr_t

◆ CollisionObjectPtr_t

typedef boost::shared_ptr<CollisionObject> hpp::fcl::CollisionObjectPtr_t

◆ FCL_INT32

typedef boost::int32_t hpp::fcl::FCL_INT32

◆ FCL_INT64

typedef boost::uint64_t hpp::fcl::FCL_INT64

◆ FCL_REAL

typedef double hpp::fcl::FCL_REAL

◆ FCL_UINT32

typedef boost::uint32_t hpp::fcl::FCL_UINT32

◆ FCL_UINT64

typedef boost::int64_t hpp::fcl::FCL_UINT64

◆ Matrix3f

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

◆ Quaternion3f

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

◆ Vec3f

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

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 

◆ NODE_TYPE

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

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

◆ OBJECT_TYPE

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

Enumerator
OT_UNKNOWN 
OT_BVH 
OT_GEOM 
OT_OCTREE 
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()

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.

◆ 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 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.

◆ collide() [2/2]

std::size_t hpp::fcl::collide ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
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 
)

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

◆ 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 OBB bv,
Box box,
Transform3f tf 
)

◆ constructBox() [3/16]

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

◆ constructBox() [4/16]

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

◆ constructBox() [5/16]

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

◆ constructBox() [6/16]

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

◆ constructBox() [7/16]

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

◆ constructBox() [8/16]

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

◆ constructBox() [9/16]

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

◆ constructBox() [10/16]

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

◆ constructBox() [11/16]

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

◆ constructBox() [12/16]

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

◆ constructBox() [13/16]

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

◆ constructBox() [14/16]

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

◆ constructBox() [15/16]

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

◆ constructBox() [16/16]

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

◆ distance() [1/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.

◆ distance() [2/2]

FCL_REAL hpp::fcl::distance ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
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,
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,
int  n,
AABB bv 
)

◆ fit< kIOS >()

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

◆ fit< OBB >()

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

◆ fit< OBBRSS >()

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

◆ fit< RSS >()

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

◆ fromAxisAngle()

template<typename Derived >
Quaternion3f 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 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.

◆ generateBVHModel() [3/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() [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 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() [7/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.

◆ 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 
)

◆ getCovariance()

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

◆ getExtentAndCenter()

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

◆ HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR() [1/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR ( Sphere  ,
Box   
)

◆ HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR() [2/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR ( Sphere  ,
Capsule   
)

◆ HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR() [3/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_DISTANCE_PAIR ( Sphere  ,
Cylinder   
)

◆ HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF() [1/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF ( Sphere  )

◆ HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF() [2/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF ( Capsule  )

◆ HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF() [3/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF ( TriangleP  )

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [1/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Sphere  ,
Capsule   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [2/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Sphere  ,
Halfspace   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [3/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Sphere  ,
Plane   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [4/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Box  ,
Halfspace   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [5/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Box  ,
Plane   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [6/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Capsule  ,
Halfspace   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [7/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Capsule  ,
Plane   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [8/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Cylinder  ,
Halfspace   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [9/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Cylinder  ,
Plane   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [10/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Cone  ,
Halfspace   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [11/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Cone  ,
Plane   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [12/12]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR ( Plane  ,
Halfspace   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF() [1/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF ( Sphere  )

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF() [2/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF ( Halfspace  )

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF() [3/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF ( Plane  )

◆ HPP_FCL_DECLARE_SHAPE_TRIANGLE() [1/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_TRIANGLE ( Sphere  )

◆ HPP_FCL_DECLARE_SHAPE_TRIANGLE() [2/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_TRIANGLE ( Halfspace  )

◆ HPP_FCL_DECLARE_SHAPE_TRIANGLE() [3/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_TRIANGLE ( Plane  )

◆ 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 boost::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

◆ maximumDistance()

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

◆ 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 
)

◆ 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 
)

◆ updateFrontList()

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

Add new front node into the front list.

Variable Documentation

◆ HPP_FCL_DEPRECATED

const int GST_INDEP hpp::fcl::HPP_FCL_DEPRECATED = 0