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

Namespaces

 detail
 
 details
 
 internal
 
 kIOS_fit_functions
 
 OBB_fit_functions
 
 OBBRSS_fit_functions
 
 python
 
 RSS_fit_functions
 

Classes

class  AABB
 A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points. More...
 
class  BenchTimer
 
class  Box
 Center at zero point, axis aligned box. More...
 
class  BroadPhaseCollisionManager
 Base class for broad phase collision. It helps to accelerate the collision/distance between N objects. Also support self collision, self distance and collision/distance with another M objects. More...
 
struct  BroadPhaseCollisionManagerWrapper
 
class  BroadPhaseContinuousCollisionManager
 Base class for broad phase continuous collision. It helps to accelerate the continuous collision/distance between N objects. Also support self collision, self distance and collision/distance with another M objects. More...
 
class  BVFitter
 The class for the default algorithm fitting a bounding volume to a set of points. More...
 
class  BVFitter< 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  BVHShapeCollider
 
struct  BVHShapeDistancer
 
struct  BVHShapeDistancer< kIOS, T_SH >
 
struct  BVHShapeDistancer< OBBRSS, T_SH >
 
struct  BVHShapeDistancer< RSS, T_SH >
 
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...
 
struct  BVT
 Bounding volume test structure. More...
 
struct  BVT_Comparer
 Comparer between two BVT. More...
 
struct  BVTQ
 
class  CachedMeshLoader
 
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...
 
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  CollisionCallBackBaseWrapper
 
struct  CollisionCallBackCollect
 Collision callback to collect collision pairs potentially in contacts. More...
 
struct  CollisionCallBackDefault
 Default collision callback to check collision between collision objects. More...
 
struct  CollisionData
 Collision data stores the collision request and the result given by collision algorithm. More...
 
struct  CollisionFunctionMatrix
 collision matrix stores the functions for collision between different types of objects and provides a uniform call interface More...
 
class  CollisionGeometry
 The geometry for the object for collision or distance computation. More...
 
class  CollisionObject
 the object for collision or distance computation, contains the geometry and the transform information More...
 
struct  CollisionRequest
 request to the collision algorithm More...
 
struct  CollisionResult
 collision result More...
 
class  ComputeCollision
 This class reduces the cost of identifying the geometry pair. This is mostly useful for repeated shape-shape queries. More...
 
class  ComputeDistance
 
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...
 
struct  CPUTimes
 
class  Cylinder
 Cylinder along Z axis. The cylinder is defined at its centroid. 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...
 
struct  DistanceCallBackBaseWrapper
 
struct  DistanceCallBackDefault
 Default distance callback to check collision between collision objects. More...
 
struct  DistanceData
 Distance data stores the distance request and the result given by distance algorithm. More...
 
struct  DistanceFunctionMatrix
 distance matrix stores the functions for distance between different types of objects and provides a uniform call interface More...
 
struct  DistanceRequest
 request to the distance computation More...
 
struct  DistanceRes
 
struct  DistanceResult
 distance result More...
 
class  DummyCollisionObject
 Dummy collision object with a point AABB. More...
 
class  DynamicAABBTreeArrayCollisionManager
 
class  DynamicAABBTreeCollisionManager
 
class  Ellipsoid
 Ellipsoid centered at point zero. 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  HeightField
 Data structure depicting a height field given by the base grid dimensions and the elevation along the grid. More...
 
struct  HeightFieldShapeCollider
 Collider functor for HeightField data structure. More...
 
struct  HeightFieldShapeDistancer
 
struct  HFNode
 
struct  HFNodeBase
 
class  IntervalTreeCollisionManager
 Collision manager based on interval tree. 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  NaiveCollisionManager
 Brute force N-body collision manager. More...
 
struct  OBB
 Oriented bounding box class. More...
 
struct  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...
 
struct  Quadrilateral
 Quadrilateral with 4 indices for points. More...
 
struct  QueryRequest
 base class for all query requests More...
 
struct  QueryResult
 base class for all query results More...
 
struct  RSS
 A class for rectangle sphere-swept bounding volume. More...
 
class  SaPCollisionManager
 Rigorous SAP collision manager. More...
 
struct  shape_traits
 
struct  shape_traits< Box >
 
struct  shape_traits< Capsule >
 
struct  shape_traits< Cone >
 
struct  shape_traits< ConvexBase >
 
struct  shape_traits< Cylinder >
 
struct  shape_traits< Ellipsoid >
 
struct  shape_traits< Halfspace >
 
struct  shape_traits< Sphere >
 
struct  shape_traits< TriangleP >
 
struct  shape_traits_base
 
class  ShapeBase
 Base class for all basic geometric shapes. More...
 
struct  SortByXLow
 Functor sorting objects according to the AABB lower x bound. More...
 
struct  SortByYLow
 Functor sorting objects according to the AABB lower y bound. More...
 
struct  SortByZLow
 Functor sorting objects according to the AABB lower z bound. More...
 
class  SpatialHashingCollisionManager
 spatial hashing collision mananger More...
 
class  Sphere
 Center at zero point sphere. More...
 
class  SSaPCollisionManager
 Simple SAP collision manager. More...
 
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...
 
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...
 
struct  TStruct
 

Typedefs

typedef Eigen::AngleAxis< FCL_REALAngleAxis
 
using BroadPhaseContinuousCollisionManagerd = BroadPhaseContinuousCollisionManager< FCL_REAL >
 
using BroadPhaseContinuousCollisionManagerf = BroadPhaseContinuousCollisionManager< float >
 
typedef std::list< BVHFrontNodeBVHFrontList
 BVH front list is a list of front nodes. More...
 
typedef shared_ptr< BVHModelBaseBVHModelPtr_t
 
typedef shared_ptr< const CollisionGeometryCollisionGeometryConstPtr_t
 
typedef shared_ptr< CollisionGeometryCollisionGeometryPtr_t
 
typedef shared_ptr< const CollisionObjectCollisionObjectConstPtr_t
 
typedef shared_ptr< CollisionObjectCollisionObjectPtr_t
 
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...
 
typedef double FCL_REAL
 
typedef Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
 
typedef Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 3 > Matrixx3f
 
typedef Eigen::Matrix< Eigen::DenseIndex, Eigen::Dynamic, 3 > Matrixx3i
 
typedef Eigen::Matrix< FCL_REAL, Eigen::Dynamic, Eigen::Dynamic > MatrixXf
 
typedef shared_ptr< const OcTreeOcTreeConstPtr_t
 
typedef shared_ptr< OcTreeOcTreePtr_t
 
typedef Eigen::Quaternion< FCL_REALQuaternion3f
 
typedef Eigen::Vector2i support_func_guess_t
 
typedef Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
 
typedef Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 1 > VecXf
 

Enumerations

enum  BVHBuildState {
  BVH_BUILD_STATE_EMPTY, BVH_BUILD_STATE_BEGUN, BVH_BUILD_STATE_PROCESSED, BVH_BUILD_STATE_UPDATE_BEGUN,
  BVH_BUILD_STATE_UPDATED, BVH_BUILD_STATE_REPLACE_BEGUN
}
 States for BVH construction empty->begun->processed ->replace_begun->processed -> ...... | |-> update_begun -> updated -> ..... More...
 
enum  BVHModelType { BVH_MODEL_UNKNOWN, BVH_MODEL_TRIANGLES, BVH_MODEL_POINTCLOUD }
 BVH model type. More...
 
enum  BVHReturnCode {
  BVH_OK = 0, BVH_ERR_MODEL_OUT_OF_MEMORY, 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  CollisionRequestFlag { CONTACT = 0x00001, DISTANCE_LOWER_BOUND = 0x00002, NO_REQUEST = 0x01000 }
 flag declaration for specifying required params in CollisionResult More...
 
enum  GJKConvergenceCriterion { VDB, 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  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, NesterovAcceleration }
 Variant to use for the GJK algorithm. 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  OBJECT_TYPE {
  OT_UNKNOWN, OT_BVH, OT_GEOM, OT_OCTREE,
  OT_HFIELD, OT_COUNT
}
 object type: BVH (mesh, points), basic geometry, octree More...
 
enum  SplitMethodType { SPLIT_METHOD_MEAN, SPLIT_METHOD_MEDIAN, SPLIT_METHOD_BV_CENTER }
 Three types of split algorithms are provided in FCL as default. More...
 

Functions

template<typename BV >
BVHModelPtr_t _load (const std::string &filename, const Vec3f &scale)
 
static void axisFromEigen (Vec3f eigenV[3], Matrix3f::Scalar eigenS[3], Matrix3f &axes)
 
template<typename T_BVH >
std::size_t BVHCollide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 
template<typename T_BVH >
std::size_t BVHCollide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const CollisionRequest &request, CollisionResult &result)
 
template<>
std::size_t BVHCollide< kIOS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 
template<>
std::size_t BVHCollide< OBB > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 
template<>
std::size_t BVHCollide< OBBRSS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 
template<typename T_BVH >
FCL_REAL BVHDistance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 
template<typename T_BVH >
FCL_REAL BVHDistance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &request, DistanceResult &result)
 
template<>
FCL_REAL BVHDistance< kIOS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 
template<>
FCL_REAL BVHDistance< OBBRSS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 
template<>
FCL_REAL BVHDistance< RSS > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 
template<>
HPP_FCL_DLLAPI BVHModel< AABB > * BVHExtract (const BVHModel< AABB > &model, const Transform3f &pose, const AABB &aabb)
 
template<typename BV >
HPP_FCL_DLLAPI 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<>
HPP_FCL_DLLAPI BVHModel< KDOP< 16 > > * BVHExtract (const BVHModel< KDOP< 16 > > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
HPP_FCL_DLLAPI BVHModel< KDOP< 18 > > * BVHExtract (const BVHModel< KDOP< 18 > > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
HPP_FCL_DLLAPI BVHModel< KDOP< 24 > > * BVHExtract (const BVHModel< KDOP< 24 > > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
HPP_FCL_DLLAPI BVHModel< kIOS > * BVHExtract (const BVHModel< kIOS > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
HPP_FCL_DLLAPI BVHModel< OBB > * BVHExtract (const BVHModel< OBB > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
HPP_FCL_DLLAPI BVHModel< OBBRSS > * BVHExtract (const BVHModel< OBBRSS > &model, const Transform3f &pose, const AABB &aabb)
 
template<>
HPP_FCL_DLLAPI BVHModel< RSS > * BVHExtract (const BVHModel< RSS > &model, const Transform3f &pose, const AABB &aabb)
 
HPP_FCL_DLLAPI 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 clamp (const FCL_REAL &num, const FCL_REAL &denom)
 Clamp num / denom in [0, 1]. More...
 
void clamped_linear (Vec3f &a_sd, const Vec3f &a, const FCL_REAL &s_n, const FCL_REAL &s_d, const Vec3f &d)
 Clamp s=s_n/s_d in [0, 1] and stores a + s * d in a_sd. More...
 
void clipToRange (FCL_REAL &val, FCL_REAL a, FCL_REAL b)
 Clip value between a and b. More...
 
void collide (CollisionTraversalNodeBase *node, const CollisionRequest &request, CollisionResult &result, BVHFrontList *front_list, bool recursive)
 
std::size_t collide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, CollisionRequest &request, CollisionResult &result)
 
HPP_FCL_DLLAPI std::size_t collide (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const CollisionRequest &request, CollisionResult &result)
 
std::size_t collide (const CollisionObject *o1, const CollisionObject *o2, CollisionRequest &request, CollisionResult &result)
 
HPP_FCL_DLLAPI 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...
 
void collisionNonRecurse (CollisionTraversalNodeBase *node, BVHFrontList *front_list, FCL_REAL &sqrDistLowerBound)
 
void collisionRecurse (CollisionTraversalNodeBase *node, unsigned int b1, unsigned int b2, BVHFrontList *front_list, FCL_REAL &sqrDistLowerBound)
 
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<>
HPP_FCL_DLLAPI void computeBV< AABB, Box > (const Box &s, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< AABB, Capsule > (const Capsule &s, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< AABB, Cone > (const Cone &s, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< AABB, ConvexBase > (const ConvexBase &s, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< AABB, Cylinder > (const Cylinder &s, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< AABB, Ellipsoid > (const Ellipsoid &e, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< AABB, Halfspace > (const Halfspace &s, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< AABB, Plane > (const Plane &s, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< AABB, Sphere > (const Sphere &s, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< AABB, TriangleP > (const TriangleP &s, const Transform3f &tf, AABB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< KDOP< 16 >, Halfspace > (const Halfspace &s, const Transform3f &tf, KDOP< 16 > &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< KDOP< 16 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 16 > &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< KDOP< 18 >, Halfspace > (const Halfspace &s, const Transform3f &tf, KDOP< 18 > &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< KDOP< 18 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 18 > &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< KDOP< 24 >, Halfspace > (const Halfspace &s, const Transform3f &tf, KDOP< 24 > &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< KDOP< 24 >, Plane > (const Plane &s, const Transform3f &tf, KDOP< 24 > &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< kIOS, Halfspace > (const Halfspace &s, const Transform3f &tf, kIOS &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< kIOS, Plane > (const Plane &s, const Transform3f &tf, kIOS &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBB, Box > (const Box &s, const Transform3f &tf, OBB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBB, Capsule > (const Capsule &s, const Transform3f &tf, OBB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBB, Cone > (const Cone &s, const Transform3f &tf, OBB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBB, ConvexBase > (const ConvexBase &s, const Transform3f &tf, OBB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBB, Cylinder > (const Cylinder &s, const Transform3f &tf, OBB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBB, Halfspace > (const Halfspace &s, const Transform3f &tf, OBB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBB, Plane > (const Plane &s, const Transform3f &tf, OBB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBB, Sphere > (const Sphere &s, const Transform3f &tf, OBB &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBBRSS, Halfspace > (const Halfspace &s, const Transform3f &tf, OBBRSS &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< OBBRSS, Plane > (const Plane &s, const Transform3f &tf, OBBRSS &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< RSS, Halfspace > (const Halfspace &s, const Transform3f &tf, RSS &bv)
 
template<>
HPP_FCL_DLLAPI void computeBV< RSS, Plane > (const Plane &s, const Transform3f &tf, RSS &bv)
 
static void computeChildBV (const AABB &root_bv, unsigned int i, AABB &child_bv)
 compute the bounding volume of an octree node's i-th child 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 computeSplitValue_bvcenter (const BV &bv, FCL_REAL &split_value)
 
template<typename BV >
void computeSplitValue_mean (const BV &, Vec3f *vertices, Triangle *triangles, unsigned int *primitive_indices, unsigned int num_primitives, BVHModelType type, const Vec3f &split_vector, FCL_REAL &split_value)
 
template<typename BV >
void computeSplitValue_median (const BV &, Vec3f *vertices, Triangle *triangles, unsigned int *primitive_indices, unsigned int num_primitives, BVHModelType type, const Vec3f &split_vector, FCL_REAL &split_value)
 
template<typename BV >
void computeSplitVector (const BV &bv, Vec3f &split_vector)
 
template<>
void computeSplitVector< kIOS > (const kIOS &bv, Vec3f &split_vector)
 
template<>
void computeSplitVector< OBBRSS > (const OBBRSS &bv, Vec3f &split_vector)
 
void computeVertices (const OBB &b, Vec3f vertices[8])
 Compute the 8 vertices of a OBB. More...
 
HPP_FCL_DLLAPI void constructBox (const AABB &bv, Box &box, Transform3f &tf)
 construct a box shape (with a configuration) from a given bounding volume More...
 
HPP_FCL_DLLAPI void constructBox (const AABB &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const KDOP< 16 > &bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const KDOP< 16 > &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const KDOP< 18 > &bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const KDOP< 18 > &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const KDOP< 24 > &bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const KDOP< 24 > &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const kIOS &bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const kIOS &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const OBB &bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const OBB &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const OBBRSS &bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const OBBRSS &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const RSS &bv, Box &box, Transform3f &tf)
 
HPP_FCL_DLLAPI void constructBox (const RSS &bv, const Transform3f &tf_bv, Box &box, Transform3f &tf)
 
Convex< TriangleconstructPolytopeFromEllipsoid (const Ellipsoid &ellipsoid)
 We give an ellipsoid as input. The output is a 20 faces polytope which vertices belong to the original ellipsoid surface. The procedure is simple: we construct a icosahedron, see https://sinestesia.co/blog/tutorials/python-icospheres/ . We then apply an ellipsoid tranformation to each vertex of the icosahedron. More...
 
template<typename BV1 , typename BV2 >
static void convertBV (const BV1 &bv1, BV2 &bv2)
 Convert a bounding volume of type BV1 to bounding volume of type BV2 in identity configuration. More...
 
template<typename BV1 , typename BV2 >
static void convertBV (const BV1 &bv1, const Transform3f &tf1, BV2 &bv2)
 Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity configuration. More...
 
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...
 
HPP_FCL_DLLAPI FCL_REAL distance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result)
 
FCL_REAL distance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, DistanceRequest &request, DistanceResult &result)
 
HPP_FCL_DLLAPI 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 CollisionObject *o1, const CollisionObject *o2, DistanceRequest &request, DistanceResult &result)
 
HPP_FCL_DLLAPI 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...
 
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...
 
HPP_FCL_DLLAPI 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...
 
void distance (DistanceTraversalNodeBase *node, BVHFrontList *front_list, unsigned int qsize)
 
void distanceQueueRecurse (DistanceTraversalNodeBase *node, unsigned int b1, unsigned int b2, BVHFrontList *front_list, unsigned int qsize)
 
void distanceRecurse (DistanceTraversalNodeBase *node, unsigned int b1, unsigned int b2, BVHFrontList *front_list)
 
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...
 
void eulerToMatrix (FCL_REAL a, FCL_REAL b, FCL_REAL c, Matrix3f &R)
 
HPP_FCL_DLLAPI CollisionGeometryextract (const CollisionGeometry *model, const Transform3f &pose, const AABB &aabb)
 
template<>
void fit (Vec3f *ps, unsigned int n, AABB &bv)
 
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 (Vec3f *ps, unsigned int n, kIOS &bv)
 
template<>
void fit (Vec3f *ps, unsigned int n, OBB &bv)
 
template<>
void fit (Vec3f *ps, unsigned int n, OBBRSS &bv)
 
template<>
void fit (Vec3f *ps, unsigned int n, RSS &bv)
 
template<>
void fit< AABB > (Vec3f *ps, unsigned int n, AABB &bv)
 
template<>
void fit< kIOS > (Vec3f *ps, unsigned int n, kIOS &bv)
 
template<>
void fit< OBB > (Vec3f *ps, unsigned int n, OBB &bv)
 
template<>
void fit< OBBRSS > (Vec3f *ps, unsigned int n, OBBRSS &bv)
 
template<>
void fit< RSS > (Vec3f *ps, unsigned int n, RSS &bv)
 
template<typename Derived >
Quaternion3f fromAxisAngle (const Eigen::MatrixBase< Derived > &axis, FCL_REAL angle)
 
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 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 >
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 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 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 Derived1 , typename Derived2 , typename Derived3 >
void generateCoordinateSystem (const Eigen::MatrixBase< Derived1 > &_w, const Eigen::MatrixBase< Derived2 > &_u, const Eigen::MatrixBase< Derived3 > &_v)
 
void generateEnvironments (std::vector< CollisionObject * > &env, FCL_REAL env_scale, std::size_t n)
 
void generateEnvironmentsMesh (std::vector< CollisionObject * > &env, FCL_REAL env_scale, std::size_t n)
 
void generateRandomTransform (FCL_REAL extents[6], Transform3f &transform)
 Generate one random transform whose translation is constrained by extents and rotation without constraints. The translation is (x, y, z), and extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <= z <= extents[5]. More...
 
void generateRandomTransforms (FCL_REAL extents[6], FCL_REAL delta_trans[3], FCL_REAL delta_rot, std::vector< Transform3f > &transforms, std::vector< Transform3f > &transforms2, std::size_t n)
 Generate n random transforms whose translations are constrained by extents. Also generate another transforms2 which have additional random translation & rotation to the transforms generated. More...
 
void generateRandomTransforms (FCL_REAL extents[6], std::vector< Transform3f > &transforms, std::size_t n)
 Generate n random transforms whose translations are constrained by extents. More...
 
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...
 
CollisionFunctionMatrixgetCollisionFunctionLookTable ()
 
HPP_FCL_DLLAPI 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...
 
DistanceFunctionMatrixgetDistanceFunctionLookTable ()
 
template<short N>
void getDistances (const Vec3f &, FCL_REAL *)
 Compute the distances to planes with normals from KDOP vectors except those of AABB face planes. More...
 
template<>
void getDistances< 5 > (const Vec3f &p, FCL_REAL *d)
 Specification of getDistances. More...
 
template<>
void getDistances< 6 > (const Vec3f &p, FCL_REAL *d)
 
template<>
void getDistances< 9 > (const Vec3f &p, FCL_REAL *d)
 
HPP_FCL_DLLAPI 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...
 
static void getExtentAndCenter_mesh (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. The bounding volume axes are known. More...
 
static void getExtentAndCenter_pointcloud (Vec3f *ps, Vec3f *ps2, 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. The bounding volume axes are known. More...
 
std::size_t getNbRun (const int &argc, char const *const *argv, std::size_t defaultValue)
 Get the argument –nb-run from argv. More...
 
std::string getNodeTypeName (NODE_TYPE node_type)
 
HPP_FCL_DLLAPI 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...
 
bool inVoronoi (FCL_REAL a, FCL_REAL b, FCL_REAL Anorm_dot_B, FCL_REAL Anorm_dot_T, FCL_REAL A_dot_B, FCL_REAL A_dot_T, FCL_REAL B_dot_T)
 Returns whether the nearest point on rectangle edge Pb + B*u, 0 <= u <= b, to the rectangle edge, Pa + A*t, 0 <= t <= a, is within the half space determined by the point Pa and the direction Anorm. A,B, and Anorm are unit vectors. T is the vector between Pa and Pb. 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)
 
void loadOBJFile (const char *filename, std::vector< Vec3f > &points, std::vector< Triangle > &triangles)
 Load an obj mesh file. 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...
 
HPP_FCL_DLLAPI 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...
 
Quaternion3f makeQuat (FCL_REAL w, FCL_REAL x, FCL_REAL y, FCL_REAL z)
 
HPP_FCL_DLLAPI 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...
 
static FCL_REAL maximumDistance_mesh (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Vec3f &query)
 
static FCL_REAL maximumDistance_pointcloud (Vec3f *ps, Vec3f *ps2, unsigned int *indices, unsigned int n, const Vec3f &query)
 
OBB merge_largedist (const OBB &b1, const OBB &b2)
 OBB merge method when the centers of two smaller OBB are far away. More...
 
OBB merge_smalldist (const OBB &b1, const OBB &b2)
 OBB merge method when the centers of two smaller OBB are close. More...
 
void minmax (FCL_REAL a, FCL_REAL b, FCL_REAL &minv, FCL_REAL &maxv)
 Find the smaller and larger one of two values. More...
 
void minmax (FCL_REAL p, FCL_REAL &minv, FCL_REAL &maxv)
 Merge the interval [minv, maxv] and value p/. More...
 
HPP_FCL_DLLAPI bool obbDisjoint (const Matrix3f &B, const Vec3f &T, const Vec3f &a, const Vec3f &b)
 
bool obbDisjointAndLowerBoundDistance (const Matrix3f &B, const Vec3f &T, const Vec3f &a_, const Vec3f &b_, const CollisionRequest &request, FCL_REAL &squaredLowerBoundDistance)
 
CollisionRequestFlag operator& (CollisionRequestFlag a, CollisionRequestFlag b)
 
CollisionRequestFlagoperator&= (CollisionRequestFlag &a, CollisionRequestFlag b)
 
static std::ostream & operator<< (std::ostream &o, const Quaternion3f &q)
 
std::ostream & operator<< (std::ostream &os, const Box &b)
 
std::ostream & operator<< (std::ostream &os, const ShapeBase &)
 
std::ostream & operator<< (std::ostream &os, const Transform3f &tf)
 
CollisionRequestFlag operator^ (CollisionRequestFlag a, CollisionRequestFlag b)
 
CollisionRequestFlagoperator^= (CollisionRequestFlag &a, CollisionRequestFlag b)
 
CollisionRequestFlag operator| (CollisionRequestFlag a, CollisionRequestFlag b)
 
CollisionRequestFlagoperator|= (CollisionRequestFlag &a, CollisionRequestFlag b)
 
CollisionRequestFlag operator~ (CollisionRequestFlag a)
 
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 &)
 
HPP_FCL_DLLAPI 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...
 
HPP_FCL_DLLAPI 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...
 
HPP_FCL_DLLAPI 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...
 
HPP_FCL_DLLAPI 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...
 
HPP_FCL_DLLAPI 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...
 
HPP_FCL_DLLAPI 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 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)
 
HPP_FCL_DLLAPI 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...
 
HPP_FCL_DLLAPI 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 propagateBVHFrontListCollisionRecurse (CollisionTraversalNodeBase *node, const CollisionRequest &, CollisionResult &result, BVHFrontList *front_list)
 
FCL_REAL rand_interval (FCL_REAL rmin, FCL_REAL rmax)
 
FCL_REAL rectDistance (const Matrix3f &Rab, Vec3f const &Tab, const FCL_REAL a[2], const FCL_REAL b[2], Vec3f *P=NULL, Vec3f *Q=NULL)
 Distance between two oriented rectangles; P and Q (optional return values) are the closest points in the rectangles, both are in the local frame of the first rectangle. More...
 
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)
 
void relativeTransform (const Transform3f &tf1, const Transform3f &tf2, Transform3f &tf)
 
void relativeTransform2 (const Transform3f &tf1, const Transform3f &tf2, Transform3f &tf)
 
void reorderTriangle (const Convex< Triangle > *convex_tri, Triangle &tri)
 
static AABB rotate (const AABB &aabb, const Matrix3f &R)
 
void saveOBJFile (const char *filename, std::vector< Vec3f > &points, std::vector< Triangle > &triangles)
 
void segCoords (FCL_REAL &t, FCL_REAL &u, FCL_REAL a, FCL_REAL b, FCL_REAL A_dot_B, FCL_REAL A_dot_T, FCL_REAL B_dot_T)
 Finds the parameters t & u corresponding to the two closest points on a pair of line segments. The first segment is defined as Pa + A*t, 0 <= t <= a, where "Pa" is one endpoint of the segment, "A" is a unit vector pointing to the other endpoint, and t is a scalar that produces all the points between the two endpoints. Since "A" is a unit vector, "a" is the segment's length. The second segment is defined as Pb + B*u, 0 <= u <= b. Many of the terms needed by the algorithm are already computed for other purposes,so we just pass these terms into the function instead of complete specifications of each segment. "T" in the dot products is the vector betweeen Pa and Pb. Reference: "On fast computation of distance between line segments." Vladimir J. Lumelsky, in Information Processing Letters, no. 21, pages 55-61, 1985. More...
 
 SHAPE_DISTANCE_SPECIALIZATION (Sphere, Box)
 
 SHAPE_DISTANCE_SPECIALIZATION (Sphere, Capsule)
 
 SHAPE_DISTANCE_SPECIALIZATION (Sphere, Cylinder)
 
 SHAPE_DISTANCE_SPECIALIZATION_BASE (Capsule, Capsule)
 
 SHAPE_DISTANCE_SPECIALIZATION_BASE (Sphere, Sphere)
 
 SHAPE_DISTANCE_SPECIALIZATION_BASE (TriangleP, TriangleP)
 
 SHAPE_INTERSECT_SPECIALIZATION (Halfspace, Box)
 
 SHAPE_INTERSECT_SPECIALIZATION (Halfspace, Capsule)
 
 SHAPE_INTERSECT_SPECIALIZATION (Halfspace, Cone)
 
 SHAPE_INTERSECT_SPECIALIZATION (Halfspace, Cylinder)
 
 SHAPE_INTERSECT_SPECIALIZATION (Halfspace, Plane)
 
 SHAPE_INTERSECT_SPECIALIZATION (Plane, Box)
 
 SHAPE_INTERSECT_SPECIALIZATION (Plane, Capsule)
 
 SHAPE_INTERSECT_SPECIALIZATION (Plane, Cone)
 
 SHAPE_INTERSECT_SPECIALIZATION (Plane, Cylinder)
 
 SHAPE_INTERSECT_SPECIALIZATION (Sphere, Box)
 
 SHAPE_INTERSECT_SPECIALIZATION (Sphere, Capsule)
 
 SHAPE_INTERSECT_SPECIALIZATION (Sphere, Halfspace)
 
 SHAPE_INTERSECT_SPECIALIZATION (Sphere, Plane)
 
 SHAPE_INTERSECT_SPECIALIZATION_BASE (Sphere, Sphere)
 
template<typename T_SH1 , typename T_SH2 >
FCL_REAL ShapeShapeDistance (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Box, Halfspace > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Box, Plane > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Box, Sphere > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Capsule, Capsule > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &request, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Capsule, Halfspace > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Capsule, Plane > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Cone, Halfspace > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Cone, Plane > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< ConvexBase, Halfspace > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Cylinder, Halfspace > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Cylinder, Plane > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Cylinder, Sphere > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Halfspace, Box > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Halfspace, Capsule > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Halfspace, Cone > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Halfspace, ConvexBase > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Halfspace, Cylinder > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Halfspace, Sphere > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Halfspace, TriangleP > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Plane, Box > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Plane, Capsule > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Plane, Cone > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Plane, Cylinder > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Plane, Sphere > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Sphere, Box > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Sphere, Cylinder > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Sphere, Halfspace > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Sphere, Plane > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< Sphere, Sphere > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
template<>
FCL_REAL ShapeShapeDistance< TriangleP, Halfspace > (const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *, const DistanceRequest &, DistanceResult &result)
 
void toEllipsoid (Vec3f &point, const Ellipsoid &ellipsoid)
 
void toSphere (Vec3f &point)
 Takes a point and projects it onto the surface of the unit sphere. More...
 
HPP_FCL_DLLAPI Halfspace transform (const Halfspace &a, const Transform3f &tf)
 
HPP_FCL_DLLAPI Plane transform (const Plane &a, const Transform3f &tf)
 
static AABB translate (const AABB &aabb, const Vec3f &t)
 translate the center of AABB by t More...
 
template<short N>
HPP_FCL_DLLAPI KDOP< N > translate (const KDOP< N > &bv, const Vec3f &t)
 translate the KDOP BV More...
 
template<short N>
KDOP< N > translate (const KDOP< N > &bv, const Vec3f &t)
 translate the KDOP BV More...
 
HPP_FCL_DLLAPI kIOS translate (const kIOS &bv, const Vec3f &t)
 Translate the kIOS BV. More...
 
HPP_FCL_DLLAPI OBB translate (const OBB &bv, const Vec3f &t)
 Translate the OBB bv. More...
 
OBBRSS translate (const OBBRSS &bv, const Vec3f &t)
 
RSS translate (const RSS &bv, const Vec3f &t)
 
template KDOP< 16 > translate< 16 > (const KDOP< 16 > &, const Vec3f &)
 
template KDOP< 18 > translate< 18 > (const KDOP< 18 > &, const Vec3f &)
 
template KDOP< 24 > translate< 24 > (const KDOP< 24 > &, const Vec3f &)
 
template<typename Derived >
static Derived::Scalar triple (const Eigen::MatrixBase< Derived > &x, const Eigen::MatrixBase< Derived > &y, const Eigen::MatrixBase< Derived > &z)
 
void updateFrontList (BVHFrontList *front_list, unsigned int b1, unsigned int b2)
 Add new front node into the front list. More...
 

Variables

static const double cosA = sqrt(3.0) / 2.0
 
static const double invSinA = 2
 
static const double kIOS_RATIO = 1.5
 
const Eigen::IOFormat pyfmt
 
const Vec3f UnitX = Vec3f(1, 0, 0)
 
const Vec3f UnitY = Vec3f(0, 1, 0)
 
const Vec3f UnitZ = Vec3f(0, 0, 1)
 
const Eigen::IOFormat vfmt
 

Typedef Documentation

◆ AngleAxis

typedef Eigen::AngleAxis<FCL_REAL> hpp::fcl::AngleAxis

Definition at line 123 of file utility.h.

◆ BroadPhaseContinuousCollisionManagerd

Definition at line 138 of file broadphase_continuous_collision_manager.h.

◆ BroadPhaseContinuousCollisionManagerf

Definition at line 136 of file broadphase_continuous_collision_manager.h.

◆ BVHFrontList

BVH front list is a list of front nodes.

Definition at line 67 of file BVH_front.h.

◆ BVHModelPtr_t

Definition at line 103 of file include/hpp/fcl/fwd.hh.

◆ CollisionGeometryConstPtr_t

Definition at line 98 of file include/hpp/fcl/fwd.hh.

◆ CollisionGeometryPtr_t

Definition at line 96 of file include/hpp/fcl/fwd.hh.

◆ CollisionObjectConstPtr_t

Definition at line 95 of file include/hpp/fcl/fwd.hh.

◆ CollisionObjectPtr_t

Definition at line 93 of file include/hpp/fcl/fwd.hh.

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

Definition at line 53 of file broadphase_continuous_collision_manager.h.

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

Definition at line 60 of file broadphase_continuous_collision_manager.h.

◆ FCL_REAL

typedef double hpp::fcl::FCL_REAL

Definition at line 65 of file data_types.h.

◆ Matrix3f

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

Definition at line 68 of file data_types.h.

◆ Matrixx3f

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

Definition at line 69 of file data_types.h.

◆ Matrixx3i

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

Definition at line 70 of file data_types.h.

◆ MatrixXf

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

Definition at line 71 of file data_types.h.

◆ OcTreeConstPtr_t

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

Definition at line 108 of file include/hpp/fcl/fwd.hh.

◆ OcTreePtr_t

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

Definition at line 106 of file include/hpp/fcl/fwd.hh.

◆ Quaternion3f

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

Definition at line 46 of file transform.h.

◆ support_func_guess_t

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

Definition at line 72 of file data_types.h.

◆ Vec3f

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

Definition at line 66 of file data_types.h.

◆ VecXf

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

Definition at line 67 of file data_types.h.

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

Definition at line 50 of file BVH_internal.h.

◆ BVHModelType

BVH model type.

Enumerator
BVH_MODEL_UNKNOWN 
BVH_MODEL_TRIANGLES 

unknown model type

BVH_MODEL_POINTCLOUD 

triangle model

point cloud model

Definition at line 80 of file BVH_internal.h.

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

Definition at line 64 of file BVH_internal.h.

◆ CollisionRequestFlag

flag declaration for specifying required params in CollisionResult

Enumerator
CONTACT 
DISTANCE_LOWER_BOUND 
NO_REQUEST 

Definition at line 228 of file collision_data.h.

◆ 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
VDB 
DualityGap 
Hybrid 

Definition at line 89 of file data_types.h.

◆ GJKConvergenceCriterionType

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

Enumerator
Relative 
Absolute 

Definition at line 93 of file data_types.h.

◆ 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 

Definition at line 80 of file data_types.h.

◆ GJKVariant

Variant to use for the GJK algorithm.

Enumerator
DefaultGJK 
NesterovAcceleration 

Definition at line 83 of file data_types.h.

◆ 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 

Definition at line 65 of file collision_object.h.

◆ OBJECT_TYPE

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

Enumerator
OT_UNKNOWN 
OT_BVH 
OT_GEOM 
OT_OCTREE 
OT_HFIELD 
OT_COUNT 

Definition at line 53 of file collision_object.h.

◆ SplitMethodType

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

Enumerator
SPLIT_METHOD_MEAN 
SPLIT_METHOD_MEDIAN 
SPLIT_METHOD_BV_CENTER 

Definition at line 51 of file internal/BV_splitter.h.

Function Documentation

◆ _load()

template<typename BV >
BVHModelPtr_t hpp::fcl::_load ( const std::string &  filename,
const Vec3f scale 
)

Definition at line 62 of file loader.cpp.

◆ axisFromEigen()

static void hpp::fcl::axisFromEigen ( Vec3f  eigenV[3],
Matrix3f::Scalar  eigenS[3],
Matrix3f axes 
)
inlinestatic

Definition at line 50 of file BV_fitter.cpp.

◆ BVHCollide() [1/2]

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

Definition at line 214 of file collision_func_matrix.cpp.

◆ BVHCollide() [2/2]

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

Definition at line 269 of file collision_func_matrix.cpp.

◆ BVHCollide< kIOS >()

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

Definition at line 258 of file collision_func_matrix.cpp.

◆ BVHCollide< OBB >()

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

Definition at line 238 of file collision_func_matrix.cpp.

◆ BVHCollide< OBBRSS >()

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

Definition at line 247 of file collision_func_matrix.cpp.

◆ BVHDistance() [1/2]

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

Definition at line 202 of file distance_func_matrix.cpp.

◆ BVHDistance() [2/2]

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

Definition at line 273 of file distance_func_matrix.cpp.

◆ BVHDistance< kIOS >()

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

Definition at line 253 of file distance_func_matrix.cpp.

◆ BVHDistance< OBBRSS >()

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

Definition at line 262 of file distance_func_matrix.cpp.

◆ BVHDistance< RSS >()

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

Definition at line 244 of file distance_func_matrix.cpp.

◆ BVHExtract() [1/9]

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

Definition at line 133 of file BVH_utility.cpp.

◆ BVHExtract() [2/9]

template<typename BV >
HPP_FCL_DLLAPI 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.

Definition at line 47 of file BVH_utility.cpp.

◆ BVHExtract() [3/9]

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

Definition at line 153 of file BVH_utility.cpp.

◆ BVHExtract() [4/9]

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

Definition at line 158 of file BVH_utility.cpp.

◆ BVHExtract() [5/9]

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

Definition at line 163 of file BVH_utility.cpp.

◆ BVHExtract() [6/9]

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

Definition at line 143 of file BVH_utility.cpp.

◆ BVHExtract() [7/9]

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

Definition at line 128 of file BVH_utility.cpp.

◆ BVHExtract() [8/9]

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

Definition at line 148 of file BVH_utility.cpp.

◆ BVHExtract() [9/9]

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

Definition at line 138 of file BVH_utility.cpp.

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

Definition at line 571 of file BVH_utility.cpp.

◆ clamp()

FCL_REAL hpp::fcl::clamp ( const FCL_REAL num,
const FCL_REAL denom 
)

Clamp num / denom in [0, 1].

Definition at line 53 of file src/distance/capsule_capsule.cpp.

◆ clamped_linear()

void hpp::fcl::clamped_linear ( Vec3f a_sd,
const Vec3f a,
const FCL_REAL s_n,
const FCL_REAL s_d,
const Vec3f d 
)

Clamp s=s_n/s_d in [0, 1] and stores a + s * d in a_sd.

Definition at line 64 of file src/distance/capsule_capsule.cpp.

◆ clipToRange()

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

Clip value between a and b.

Definition at line 49 of file RSS.cpp.

◆ collide() [1/5]

void hpp::fcl::collide ( CollisionTraversalNodeBase *  node,
const CollisionRequest request,
CollisionResult result,
BVHFrontList front_list,
bool  recursive 
)

Definition at line 44 of file collision_node.cpp.

◆ collide() [2/5]

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

Note
this function update the initial guess of request if requested. See QueryRequest::updateGuess

Definition at line 87 of file collision.h.

◆ collide() [3/5]

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

Definition at line 70 of file src/collision.cpp.

◆ collide() [4/5]

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

Note
this function update the initial guess of request if requested. See QueryRequest::updateGuess

Definition at line 76 of file collision.h.

◆ collide() [5/5]

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.

Definition at line 63 of file src/collision.cpp.

◆ collisionNonRecurse()

void hpp::fcl::collisionNonRecurse ( CollisionTraversalNodeBase *  node,
BVHFrontList front_list,
FCL_REAL sqrDistLowerBound 
)

Definition at line 87 of file traversal_recurse.cpp.

◆ collisionRecurse()

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

Definition at line 44 of file traversal_recurse.cpp.

◆ 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

Definition at line 74 of file geometric_shapes_utility.h.

◆ computeBV< AABB, Box >()

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

Definition at line 275 of file geometric_shapes_utility.cpp.

◆ computeBV< AABB, Capsule >()

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

Definition at line 305 of file geometric_shapes_utility.cpp.

◆ computeBV< AABB, Cone >()

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

Definition at line 316 of file geometric_shapes_utility.cpp.

◆ computeBV< AABB, ConvexBase >()

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

Definition at line 351 of file geometric_shapes_utility.cpp.

◆ computeBV< AABB, Cylinder >()

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

Definition at line 333 of file geometric_shapes_utility.cpp.

◆ computeBV< AABB, Ellipsoid >()

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

Definition at line 294 of file geometric_shapes_utility.cpp.

◆ computeBV< AABB, Halfspace >()

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

Definition at line 372 of file geometric_shapes_utility.cpp.

◆ computeBV< AABB, Plane >()

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

Definition at line 405 of file geometric_shapes_utility.cpp.

◆ computeBV< AABB, Sphere >()

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

Definition at line 285 of file geometric_shapes_utility.cpp.

◆ computeBV< AABB, TriangleP >()

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

Definition at line 366 of file geometric_shapes_utility.cpp.

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

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

Definition at line 536 of file geometric_shapes_utility.cpp.

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

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

Definition at line 776 of file geometric_shapes_utility.cpp.

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

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

Definition at line 592 of file geometric_shapes_utility.cpp.

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

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

Definition at line 818 of file geometric_shapes_utility.cpp.

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

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

Definition at line 654 of file geometric_shapes_utility.cpp.

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

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

Definition at line 862 of file geometric_shapes_utility.cpp.

◆ computeBV< kIOS, Halfspace >()

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

Definition at line 527 of file geometric_shapes_utility.cpp.

◆ computeBV< kIOS, Plane >()

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

Definition at line 768 of file geometric_shapes_utility.cpp.

◆ computeBV< OBB, Box >()

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

Definition at line 440 of file geometric_shapes_utility.cpp.

◆ computeBV< OBB, Capsule >()

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

Definition at line 459 of file geometric_shapes_utility.cpp.

◆ computeBV< OBB, Cone >()

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

Definition at line 469 of file geometric_shapes_utility.cpp.

◆ computeBV< OBB, ConvexBase >()

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

Definition at line 490 of file geometric_shapes_utility.cpp.

◆ computeBV< OBB, Cylinder >()

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

Definition at line 479 of file geometric_shapes_utility.cpp.

◆ computeBV< OBB, Halfspace >()

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

Half space can only have very rough OBB

Half space can only have very rough OBB

Definition at line 503 of file geometric_shapes_utility.cpp.

◆ computeBV< OBB, Plane >()

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

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

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

Definition at line 731 of file geometric_shapes_utility.cpp.

◆ computeBV< OBB, Sphere >()

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

Definition at line 450 of file geometric_shapes_utility.cpp.

◆ computeBV< OBBRSS, Halfspace >()

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

Definition at line 520 of file geometric_shapes_utility.cpp.

◆ computeBV< OBBRSS, Plane >()

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

Definition at line 761 of file geometric_shapes_utility.cpp.

◆ computeBV< RSS, Halfspace >()

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

Half space can only have very rough RSS

Half space can only have very rough RSS

Definition at line 511 of file geometric_shapes_utility.cpp.

◆ computeBV< RSS, Plane >()

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

Definition at line 745 of file geometric_shapes_utility.cpp.

◆ computeChildBV()

static void hpp::fcl::computeChildBV ( const AABB root_bv,
unsigned int  i,
AABB child_bv 
)
inlinestatic

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

Definition at line 239 of file octree.h.

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

Definition at line 25 of file memory.h.

◆ computeSplitValue_bvcenter()

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

Definition at line 87 of file BV_splitter.cpp.

◆ computeSplitValue_mean()

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

Definition at line 93 of file BV_splitter.cpp.

◆ computeSplitValue_median()

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

Definition at line 121 of file BV_splitter.cpp.

◆ computeSplitVector()

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

Definition at line 44 of file BV_splitter.cpp.

◆ computeSplitVector< kIOS >()

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

Definition at line 49 of file BV_splitter.cpp.

◆ computeSplitVector< OBBRSS >()

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

Definition at line 82 of file BV_splitter.cpp.

◆ computeVertices()

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

Compute the 8 vertices of a OBB.

Definition at line 51 of file OBB.cpp.

◆ 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

Definition at line 911 of file geometric_shapes_utility.cpp.

◆ constructBox() [2/16]

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

Definition at line 951 of file geometric_shapes_utility.cpp.

◆ constructBox() [3/16]

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

Definition at line 936 of file geometric_shapes_utility.cpp.

◆ constructBox() [4/16]

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

Definition at line 981 of file geometric_shapes_utility.cpp.

◆ constructBox() [5/16]

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

Definition at line 941 of file geometric_shapes_utility.cpp.

◆ constructBox() [6/16]

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

Definition at line 987 of file geometric_shapes_utility.cpp.

◆ constructBox() [7/16]

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

Definition at line 946 of file geometric_shapes_utility.cpp.

◆ constructBox() [8/16]

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

Definition at line 993 of file geometric_shapes_utility.cpp.

◆ constructBox() [9/16]

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

Definition at line 926 of file geometric_shapes_utility.cpp.

◆ constructBox() [10/16]

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

Definition at line 969 of file geometric_shapes_utility.cpp.

◆ constructBox() [11/16]

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

Definition at line 916 of file geometric_shapes_utility.cpp.

◆ constructBox() [12/16]

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

Definition at line 957 of file geometric_shapes_utility.cpp.

◆ constructBox() [13/16]

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

Definition at line 921 of file geometric_shapes_utility.cpp.

◆ constructBox() [14/16]

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

Definition at line 963 of file geometric_shapes_utility.cpp.

◆ constructBox() [15/16]

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

Definition at line 931 of file geometric_shapes_utility.cpp.

◆ constructBox() [16/16]

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

Definition at line 975 of file geometric_shapes_utility.cpp.

◆ constructPolytopeFromEllipsoid()

Convex< Triangle > hpp::fcl::constructPolytopeFromEllipsoid ( const Ellipsoid ellipsoid)

We give an ellipsoid as input. The output is a 20 faces polytope which vertices belong to the original ellipsoid surface. The procedure is simple: we construct a icosahedron, see https://sinestesia.co/blog/tutorials/python-icospheres/ . We then apply an ellipsoid tranformation to each vertex of the icosahedron.

Definition at line 477 of file utility.cpp.

◆ convertBV() [1/2]

template<typename BV1 , typename BV2 >
static void hpp::fcl::convertBV ( const BV1 &  bv1,
BV2 &  bv2 
)
inlinestatic

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

Definition at line 284 of file BV.h.

◆ convertBV() [2/2]

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

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

Definition at line 277 of file BV.h.

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

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

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.

Definition at line 43 of file default_broadphase_callbacks.cpp.

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

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

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.

Definition at line 67 of file default_broadphase_callbacks.cpp.

◆ distance() [1/5]

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

Definition at line 60 of file src/distance.cpp.

◆ distance() [2/5]

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

Note
this function update the initial guess of request if requested. See QueryRequest::updateGuess

Definition at line 82 of file distance.h.

◆ distance() [3/5]

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.

Definition at line 53 of file src/distance.cpp.

◆ distance() [4/5]

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

Note
this function update the initial guess of request if requested. See QueryRequest::updateGuess

Definition at line 71 of file distance.h.

◆ distance() [5/5]

void hpp::fcl::distance ( DistanceTraversalNodeBase *  node,
BVHFrontList front_list,
unsigned int  qsize 
)

Definition at line 68 of file collision_node.cpp.

◆ distanceQueueRecurse()

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

Definition at line 242 of file traversal_recurse.cpp.

◆ distanceRecurse()

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

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

Definition at line 153 of file traversal_recurse.cpp.

◆ 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

Definition at line 104 of file tools.h.

◆ eulerToMatrix()

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

Definition at line 196 of file utility.cpp.

◆ extract()

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

Definition at line 68 of file collision_utility.cpp.

◆ fit() [1/6]

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

Definition at line 472 of file BV_fitter.cpp.

◆ fit() [2/6]

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.

Definition at line 52 of file BV_fitter.h.

◆ fit() [3/6]

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

Definition at line 438 of file BV_fitter.cpp.

◆ fit() [4/6]

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

Definition at line 401 of file BV_fitter.cpp.

◆ fit() [5/6]

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

Definition at line 455 of file BV_fitter.cpp.

◆ fit() [6/6]

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

Definition at line 421 of file BV_fitter.cpp.

◆ 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 >
Quaternion3f hpp::fcl::fromAxisAngle ( const Eigen::MatrixBase< Derived > &  axis,
FCL_REAL  angle 
)
inline

Definition at line 209 of file transform.h.

◆ generateBVHModel() [1/7]

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

Generate BVH model from box.

Definition at line 50 of file geometric_shape_to_BVH_model.h.

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

Definition at line 265 of file geometric_shape_to_BVH_model.h.

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

Definition at line 338 of file geometric_shape_to_BVH_model.h.

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

Definition at line 173 of file geometric_shape_to_BVH_model.h.

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

Definition at line 246 of file geometric_shape_to_BVH_model.h.

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

Definition at line 158 of file geometric_shape_to_BVH_model.h.

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

Definition at line 92 of file geometric_shape_to_BVH_model.h.

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

Definition at line 60 of file tools.h.

◆ generateEnvironments()

void hpp::fcl::generateEnvironments ( std::vector< CollisionObject * > &  env,
FCL_REAL  env_scale,
std::size_t  n 
)

Definition at line 390 of file utility.cpp.

◆ generateEnvironmentsMesh()

void hpp::fcl::generateEnvironmentsMesh ( std::vector< CollisionObject * > &  env,
FCL_REAL  env_scale,
std::size_t  n 
)

Definition at line 421 of file utility.cpp.

◆ generateRandomTransform()

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

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

Definition at line 208 of file utility.cpp.

◆ generateRandomTransforms() [1/2]

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

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

Definition at line 247 of file utility.cpp.

◆ generateRandomTransforms() [2/2]

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

Generate n random transforms whose translations are constrained by extents.

Definition at line 224 of file utility.cpp.

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

Definition at line 33 of file collision_utility.h.

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

Definition at line 48 of file collision_utility.h.

◆ getCollisionFunctionLookTable()

CollisionFunctionMatrix& hpp::fcl::getCollisionFunctionLookTable ( )

Definition at line 48 of file src/collision.cpp.

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

Definition at line 168 of file BVH_utility.cpp.

◆ getDistanceFunctionLookTable()

DistanceFunctionMatrix& hpp::fcl::getDistanceFunctionLookTable ( )

Definition at line 48 of file src/distance.cpp.

◆ getDistances()

template<short N>
void hpp::fcl::getDistances ( const Vec3f ,
FCL_REAL  
)

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

Definition at line 66 of file kDOP.cpp.

◆ getDistances< 5 >()

template<>
void hpp::fcl::getDistances< 5 > ( const Vec3f p,
FCL_REAL d 
)
inline

Specification of getDistances.

Definition at line 70 of file kDOP.cpp.

◆ getDistances< 6 >()

template<>
void hpp::fcl::getDistances< 6 > ( const Vec3f p,
FCL_REAL d 
)
inline

Definition at line 79 of file kDOP.cpp.

◆ getDistances< 9 >()

template<>
void hpp::fcl::getDistances< 9 > ( const Vec3f p,
FCL_REAL d 
)
inline

Definition at line 89 of file kDOP.cpp.

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

Definition at line 562 of file BVH_utility.cpp.

◆ getExtentAndCenter_mesh()

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

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

Definition at line 514 of file BVH_utility.cpp.

◆ getExtentAndCenter_pointcloud()

static void hpp::fcl::getExtentAndCenter_pointcloud ( Vec3f ps,
Vec3f ps2,
unsigned int *  indices,
unsigned int  n,
Matrix3f axes,
Vec3f center,
Vec3f extent 
)
inlinestatic

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

Definition at line 472 of file BVH_utility.cpp.

◆ getNbRun()

std::size_t hpp::fcl::getNbRun ( const int &  argc,
char const *const *  argv,
std::size_t  defaultValue 
)

Get the argument –nb-run from argv.

Definition at line 382 of file utility.cpp.

◆ getNodeTypeName()

std::string hpp::fcl::getNodeTypeName ( NODE_TYPE  node_type)

Definition at line 325 of file utility.cpp.

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

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

Definition at line 249 of file BVH_utility.cpp.

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

◆ HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF() [2/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_DISTANCE_SELF ( Sphere  )

◆ 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 ( Box  ,
Halfspace   
)

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [2/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [3/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [4/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [5/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [6/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [7/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [8/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [9/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [10/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [11/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_PAIR() [12/12]

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

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF() [1/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF ( Halfspace  )

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF() [2/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF ( Plane  )

◆ HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF() [3/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_INTERSECT_SELF ( Sphere  )

◆ HPP_FCL_DECLARE_SHAPE_TRIANGLE() [1/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_TRIANGLE ( Halfspace  )

◆ HPP_FCL_DECLARE_SHAPE_TRIANGLE() [2/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_TRIANGLE ( Plane  )

◆ HPP_FCL_DECLARE_SHAPE_TRIANGLE() [3/3]

hpp::fcl::HPP_FCL_DECLARE_SHAPE_TRIANGLE ( Sphere  )

◆ inVoronoi()

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

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

Definition at line 95 of file RSS.cpp.

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

Definition at line 209 of file tools.h.

◆ loadOBJFile()

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

Load an obj mesh file.

Definition at line 96 of file utility.cpp.

◆ 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

Definition at line 118 of file assimp.h.

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

Definition at line 185 of file src/octree.cpp.

◆ makeQuat()

Quaternion3f hpp::fcl::makeQuat ( FCL_REAL  w,
FCL_REAL  x,
FCL_REAL  y,
FCL_REAL  z 
)

Definition at line 368 of file utility.cpp.

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

Definition at line 644 of file BVH_utility.cpp.

◆ maximumDistance_mesh()

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

Definition at line 585 of file BVH_utility.cpp.

◆ maximumDistance_pointcloud()

static FCL_REAL hpp::fcl::maximumDistance_pointcloud ( Vec3f ps,
Vec3f ps2,
unsigned int *  indices,
unsigned int  n,
const Vec3f query 
)
inlinestatic

Definition at line 619 of file BVH_utility.cpp.

◆ merge_largedist()

OBB hpp::fcl::merge_largedist ( const OBB b1,
const OBB b2 
)
inline

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

Definition at line 64 of file OBB.cpp.

◆ merge_smalldist()

OBB hpp::fcl::merge_smalldist ( const OBB b1,
const OBB b2 
)
inline

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

Definition at line 116 of file OBB.cpp.

◆ minmax() [1/2]

void hpp::fcl::minmax ( FCL_REAL  a,
FCL_REAL  b,
FCL_REAL minv,
FCL_REAL maxv 
)
inline

Find the smaller and larger one of two values.

Definition at line 48 of file kDOP.cpp.

◆ minmax() [2/2]

void hpp::fcl::minmax ( FCL_REAL  p,
FCL_REAL minv,
FCL_REAL maxv 
)
inline

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

Definition at line 58 of file kDOP.cpp.

◆ obbDisjointAndLowerBoundDistance()

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

Definition at line 345 of file OBB.cpp.

◆ operator&()

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

Definition at line 569 of file collision_data.h.

◆ operator&=()

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

Definition at line 586 of file collision_data.h.

◆ operator<<() [1/4]

static std::ostream& hpp::fcl::operator<< ( std::ostream &  o,
const Quaternion3f q 
)
inlinestatic

Definition at line 48 of file transform.h.

◆ operator<<() [2/4]

std::ostream& hpp::fcl::operator<< ( std::ostream &  os,
const Box b 
)

Definition at line 73 of file test/geometric_shapes.cpp.

◆ operator<<() [3/4]

std::ostream& hpp::fcl::operator<< ( std::ostream &  os,
const ShapeBase  
)

Definition at line 69 of file test/geometric_shapes.cpp.

◆ operator<<() [4/4]

std::ostream & hpp::fcl::operator<< ( std::ostream &  os,
const Transform3f tf 
)

Definition at line 377 of file utility.cpp.

◆ operator^()

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

Definition at line 575 of file collision_data.h.

◆ operator^=()

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

Definition at line 591 of file collision_data.h.

◆ operator|()

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

Definition at line 563 of file collision_data.h.

◆ operator|=()

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

Definition at line 581 of file collision_data.h.

◆ operator~()

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

Definition at line 559 of file collision_data.h.

◆ propagateBVHFrontListCollisionRecurse()

void hpp::fcl::propagateBVHFrontListCollisionRecurse ( CollisionTraversalNodeBase *  node,
const CollisionRequest ,
CollisionResult result,
BVHFrontList front_list 
)

Definition at line 308 of file traversal_recurse.cpp.

◆ rand_interval()

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

Definition at line 91 of file utility.cpp.

◆ rectDistance()

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

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

Definition at line 121 of file RSS.cpp.

◆ relativeTransform() [1/2]

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 
)

Definition at line 91 of file tools.h.

◆ relativeTransform() [2/2]

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

Definition at line 43 of file transform.cpp.

◆ relativeTransform2()

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

Definition at line 48 of file transform.cpp.

◆ reorderTriangle()

void hpp::fcl::reorderTriangle ( const Convex< Triangle > *  convex_tri,
Triangle tri 
)

Definition at line 26 of file src/shape/convex.cpp.

◆ saveOBJFile()

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

Definition at line 162 of file utility.cpp.

◆ segCoords()

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

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

Definition at line 67 of file RSS.cpp.

◆ SHAPE_DISTANCE_SPECIALIZATION() [1/3]

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

◆ SHAPE_DISTANCE_SPECIALIZATION() [2/3]

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

◆ SHAPE_DISTANCE_SPECIALIZATION() [3/3]

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

◆ SHAPE_DISTANCE_SPECIALIZATION_BASE() [1/3]

hpp::fcl::SHAPE_DISTANCE_SPECIALIZATION_BASE ( Capsule  ,
Capsule   
)

◆ SHAPE_DISTANCE_SPECIALIZATION_BASE() [2/3]

hpp::fcl::SHAPE_DISTANCE_SPECIALIZATION_BASE ( Sphere  ,
Sphere   
)

◆ SHAPE_DISTANCE_SPECIALIZATION_BASE() [3/3]

hpp::fcl::SHAPE_DISTANCE_SPECIALIZATION_BASE ( TriangleP  ,
TriangleP   
)

◆ SHAPE_INTERSECT_SPECIALIZATION() [1/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [2/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [3/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [4/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [5/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [6/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [7/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [8/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [9/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [10/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [11/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [12/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION() [13/13]

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

◆ SHAPE_INTERSECT_SPECIALIZATION_BASE()

hpp::fcl::SHAPE_INTERSECT_SPECIALIZATION_BASE ( Sphere  ,
Sphere   
)

◆ ShapeShapeDistance()

template<typename T_SH1 , typename T_SH2 >
FCL_REAL hpp::fcl::ShapeShapeDistance ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver nsolver,
const DistanceRequest request,
DistanceResult result 
)

Definition at line 70 of file distance_func_matrix.cpp.

◆ ShapeShapeDistance< Box, Halfspace >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Box, Halfspace > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file box_halfspace.cpp.

◆ ShapeShapeDistance< Box, Plane >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Box, Plane > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file box_plane.cpp.

◆ ShapeShapeDistance< Box, Sphere >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Box, Sphere > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file box_sphere.cpp.

◆ ShapeShapeDistance< Capsule, Capsule >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Capsule, Capsule > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest request,
DistanceResult result 
)

Definition at line 80 of file src/distance/capsule_capsule.cpp.

◆ ShapeShapeDistance< Capsule, Halfspace >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Capsule, Halfspace > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file capsule_halfspace.cpp.

◆ ShapeShapeDistance< Capsule, Plane >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Capsule, Plane > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file capsule_plane.cpp.

◆ ShapeShapeDistance< Cone, Halfspace >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Cone, Halfspace > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file cone_halfspace.cpp.

◆ ShapeShapeDistance< Cone, Plane >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Cone, Plane > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file cone_plane.cpp.

◆ ShapeShapeDistance< ConvexBase, Halfspace >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< ConvexBase, Halfspace > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 46 of file convex_halfspace.cpp.

◆ ShapeShapeDistance< Cylinder, Halfspace >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Cylinder, Halfspace > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file cylinder_halfspace.cpp.

◆ ShapeShapeDistance< Cylinder, Plane >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Cylinder, Plane > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file cylinder_plane.cpp.

◆ ShapeShapeDistance< Cylinder, Sphere >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Cylinder, Sphere > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file sphere_cylinder.cpp.

◆ ShapeShapeDistance< Halfspace, Box >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Halfspace, Box > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file box_halfspace.cpp.

◆ ShapeShapeDistance< Halfspace, Capsule >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Halfspace, Capsule > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file capsule_halfspace.cpp.

◆ ShapeShapeDistance< Halfspace, Cone >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Halfspace, Cone > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file cone_halfspace.cpp.

◆ ShapeShapeDistance< Halfspace, ConvexBase >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Halfspace, ConvexBase > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 64 of file convex_halfspace.cpp.

◆ ShapeShapeDistance< Halfspace, Cylinder >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Halfspace, Cylinder > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file cylinder_halfspace.cpp.

◆ ShapeShapeDistance< Halfspace, Sphere >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Halfspace, Sphere > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file sphere_halfspace.cpp.

◆ ShapeShapeDistance< Halfspace, TriangleP >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Halfspace, TriangleP > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 64 of file triangle_halfspace.cpp.

◆ ShapeShapeDistance< Plane, Box >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Plane, Box > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file box_plane.cpp.

◆ ShapeShapeDistance< Plane, Capsule >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Plane, Capsule > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file capsule_plane.cpp.

◆ ShapeShapeDistance< Plane, Cone >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Plane, Cone > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file cone_plane.cpp.

◆ ShapeShapeDistance< Plane, Cylinder >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Plane, Cylinder > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file cylinder_plane.cpp.

◆ ShapeShapeDistance< Plane, Sphere >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Plane, Sphere > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file sphere_plane.cpp.

◆ ShapeShapeDistance< Sphere, Box >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Sphere, Box > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 69 of file box_sphere.cpp.

◆ ShapeShapeDistance< Sphere, Cylinder >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Sphere, Cylinder > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file sphere_cylinder.cpp.

◆ ShapeShapeDistance< Sphere, Halfspace >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Sphere, Halfspace > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file sphere_halfspace.cpp.

◆ ShapeShapeDistance< Sphere, Plane >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Sphere, Plane > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 52 of file sphere_plane.cpp.

◆ ShapeShapeDistance< Sphere, Sphere >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< Sphere, Sphere > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 56 of file sphere_sphere.cpp.

◆ ShapeShapeDistance< TriangleP, Halfspace >()

template<>
FCL_REAL hpp::fcl::ShapeShapeDistance< TriangleP, Halfspace > ( const CollisionGeometry o1,
const Transform3f tf1,
const CollisionGeometry o2,
const Transform3f tf2,
const GJKSolver ,
const DistanceRequest ,
DistanceResult result 
)

Definition at line 46 of file triangle_halfspace.cpp.

◆ toEllipsoid()

void hpp::fcl::toEllipsoid ( Vec3f point,
const Ellipsoid ellipsoid 
)

Takes a point, projects it on the unit sphere and applies an ellipsoid transformation to it. A point x belongs to the surface of an ellipsoid if x^T * A * x = 1, where A = diag(1/r**2) with r being the radii of the ellipsoid. Thus, the point y = A^(1/2) * x belongs to the unit sphere if y * y = 1. Therefore, the tranformation which brings y to x is A^(-1/2) = diag(r).

Definition at line 470 of file utility.cpp.

◆ toSphere()

void hpp::fcl::toSphere ( Vec3f point)

Takes a point and projects it onto the surface of the unit sphere.

Definition at line 459 of file utility.cpp.

◆ transform() [1/2]

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

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

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

Definition at line 248 of file geometric_shapes_utility.cpp.

◆ transform() [2/2]

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

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

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

Definition at line 261 of file geometric_shapes_utility.cpp.

◆ translate() [1/2]

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

Definition at line 43 of file OBBRSS.cpp.

◆ translate() [2/2]

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

Definition at line 1007 of file RSS.cpp.

◆ translate< 16 >()

template KDOP<16> hpp::fcl::translate< 16 > ( const KDOP< 16 > &  ,
const Vec3f  
)

◆ translate< 18 >()

template KDOP<18> hpp::fcl::translate< 18 > ( const KDOP< 18 > &  ,
const Vec3f  
)

◆ translate< 24 >()

template KDOP<24> hpp::fcl::translate< 24 > ( const KDOP< 24 > &  ,
const Vec3f  
)

◆ triple()

template<typename Derived >
static Derived::Scalar hpp::fcl::triple ( const Eigen::MatrixBase< Derived > &  x,
const Eigen::MatrixBase< Derived > &  y,
const Eigen::MatrixBase< Derived > &  z 
)
inlinestatic

Definition at line 53 of file tools.h.

◆ updateFrontList()

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

Add new front node into the front list.

Definition at line 70 of file BVH_front.h.

Variable Documentation

◆ cosA

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

Definition at line 48 of file BV_fitter.cpp.

◆ invSinA

const double hpp::fcl::invSinA = 2
static

Definition at line 47 of file BV_fitter.cpp.

◆ kIOS_RATIO

const double hpp::fcl::kIOS_RATIO = 1.5
static

Definition at line 46 of file BV_fitter.cpp.

◆ pyfmt

const Eigen::IOFormat hpp::fcl::pyfmt
Initial value:
= Eigen::IOFormat(
Eigen::StreamPrecision, Eigen::DontAlignCols, ", ", ", ", "", "", "[", "]")

Definition at line 84 of file utility.cpp.

◆ UnitX

const Vec3f hpp::fcl::UnitX = Vec3f(1, 0, 0)

Definition at line 87 of file utility.cpp.

◆ UnitY

const Vec3f hpp::fcl::UnitY = Vec3f(0, 1, 0)

Definition at line 88 of file utility.cpp.

◆ UnitZ

const Vec3f hpp::fcl::UnitZ = Vec3f(0, 0, 1)

Definition at line 89 of file utility.cpp.

◆ vfmt

const Eigen::IOFormat hpp::fcl::vfmt
Initial value:
= Eigen::IOFormat(
Eigen::StreamPrecision, Eigen::DontAlignCols, ", ", ", ", "", "", "", "")

Definition at line 82 of file utility.cpp.



hpp-fcl
Author(s):
autogenerated on Fri Mar 8 2024 03:46:34