Classes | |
class | hpp::fcl::BVFitter< BV > |
The class for the default algorithm fitting a bounding volume to a set of points. More... | |
class | hpp::fcl::BVHModel< BV > |
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 | hpp::fcl::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 | hpp::fcl::BVNode< BV > |
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 | hpp::fcl::BVNodeBase |
BVNodeBase encodes the tree structure for BVH. More... | |
class | hpp::fcl::BVSplitter< BV > |
A class describing the split rule that splits each BV node. More... | |
class | hpp::fcl::CollisionGeometry |
The geometry for the object for collision or distance computation. More... | |
class | hpp::fcl::CollisionObject |
the object for collision or distance computation, contains the geometry and the transform information More... | |
Typedefs | |
typedef BVNodeBase | hpp::fcl::BVNode< BV >::Base |
Functions | |
hpp::fcl::BVNodeBase::BVNodeBase () | |
Default constructor. More... | |
virtual CollisionGeometry * | hpp::fcl::CollisionGeometry::clone () const =0 |
Clone *this into a new CollisionGeometry. More... | |
hpp::fcl::CollisionGeometry::CollisionGeometry () | |
hpp::fcl::CollisionGeometry::CollisionGeometry (const CollisionGeometry &other)=default | |
Copy constructor. More... | |
const shared_ptr< const CollisionGeometry > | hpp::fcl::CollisionObject::collisionGeometry () const |
get geometry from the object instance More... | |
const shared_ptr< CollisionGeometry > & | hpp::fcl::CollisionObject::collisionGeometry () |
get geometry from the object instance More... | |
hpp::fcl::CollisionObject::CollisionObject (const shared_ptr< CollisionGeometry > &cgeom_, bool compute_local_aabb=true) | |
hpp::fcl::CollisionObject::CollisionObject (const shared_ptr< CollisionGeometry > &cgeom_, const Transform3f &tf, bool compute_local_aabb=true) | |
hpp::fcl::CollisionObject::CollisionObject (const shared_ptr< CollisionGeometry > &cgeom_, const Matrix3f &R, const Vec3f &T, bool compute_local_aabb=true) | |
void | hpp::fcl::CollisionObject::computeAABB () |
compute the AABB in world space More... | |
virtual Vec3f | hpp::fcl::CollisionGeometry::computeCOM () const |
compute center of mass More... | |
virtual void | hpp::fcl::CollisionGeometry::computeLocalAABB ()=0 |
compute the AABB for object in local coordinate More... | |
virtual Matrix3f | hpp::fcl::CollisionGeometry::computeMomentofInertia () const |
compute the inertia matrix, related to the origin More... | |
virtual Matrix3f | hpp::fcl::CollisionGeometry::computeMomentofInertiaRelatedToCOM () const |
compute the inertia matrix, related to the com More... | |
virtual FCL_REAL | hpp::fcl::CollisionGeometry::computeVolume () const |
compute the volume More... | |
FCL_REAL | hpp::fcl::BVNode< BV >::distance (const BVNode &other, Vec3f *P1=NULL, Vec3f *P2=NULL) const |
Compute the distance between two BVNode. P1 and P2, if not NULL and the underlying BV supports distance, return the nearest points. More... | |
const AABB & | hpp::fcl::CollisionObject::getAABB () const |
get the AABB in world space More... | |
AABB & | hpp::fcl::CollisionObject::getAABB () |
get the AABB in world space More... | |
Vec3f | hpp::fcl::BVNode< BV >::getCenter () const |
Access to the center of the BV. More... | |
virtual NODE_TYPE | hpp::fcl::CollisionGeometry::getNodeType () const |
get the node type More... | |
NODE_TYPE | hpp::fcl::CollisionObject::getNodeType () const |
get the node type More... | |
virtual OBJECT_TYPE | hpp::fcl::CollisionGeometry::getObjectType () const |
get the type of the object More... | |
OBJECT_TYPE | hpp::fcl::CollisionObject::getObjectType () const |
get the type of the object More... | |
const Matrix3f & | hpp::fcl::BVNode< BV >::getOrientation () const |
Access to the orientation of the BV. More... | |
const Matrix3f & | hpp::fcl::CollisionObject::getRotation () const |
get matrix rotation of the object More... | |
const Transform3f & | hpp::fcl::CollisionObject::getTransform () const |
get object's transform More... | |
const Vec3f & | hpp::fcl::CollisionObject::getTranslation () const |
get translation of the object More... | |
void * | hpp::fcl::CollisionGeometry::getUserData () const |
get user data in geometry More... | |
void * | hpp::fcl::CollisionObject::getUserData () const |
get user data in object More... | |
void | hpp::fcl::CollisionObject::init (bool compute_local_aabb=true) |
virtual bool | hpp::fcl::CollisionGeometry::isEqual (const CollisionGeometry &other) const =0 |
equal operator with another object of derived type. More... | |
bool | hpp::fcl::CollisionGeometry::isFree () const |
whether the object is completely free More... | |
bool | hpp::fcl::CollisionObject::isIdentityTransform () const |
whether the object is in local coordinate More... | |
bool | hpp::fcl::BVNodeBase::isLeaf () const |
Whether current node is a leaf node (i.e. contains a primitive index. More... | |
virtual bool | hpp::fcl::CollisionGeometry::isNotEqual (const CollisionGeometry &other) const |
not equal operator with another object of derived type. More... | |
bool | hpp::fcl::CollisionGeometry::isOccupied () const |
whether the object is completely occupied More... | |
bool | hpp::fcl::CollisionGeometry::isUncertain () const |
whether the object has some uncertainty More... | |
int | hpp::fcl::BVNodeBase::leftChild () const |
Return the index of the first child. The index is referred to the bounding volume array (i.e. bvs) in BVHModel. More... | |
bool | hpp::fcl::BVNodeBase::operator!= (const BVNodeBase &other) const |
Difference operator. More... | |
bool | hpp::fcl::BVNode< BV >::operator!= (const BVNode &other) const |
Difference operator. More... | |
bool | hpp::fcl::CollisionGeometry::operator!= (const CollisionGeometry &other) const |
Difference operator. More... | |
bool | hpp::fcl::CollisionObject::operator!= (const CollisionObject &other) const |
bool | hpp::fcl::BVNodeBase::operator== (const BVNodeBase &other) const |
Equality operator. More... | |
bool | hpp::fcl::CollisionGeometry::operator== (const CollisionGeometry &other) const |
Equality operator. More... | |
bool | hpp::fcl::BVNode< BV >::operator== (const BVNode &other) const |
Equality operator. More... | |
bool | hpp::fcl::CollisionObject::operator== (const CollisionObject &other) const |
bool | hpp::fcl::BVNode< BV >::overlap (const BVNode &other) const |
Check whether two BVNode collide. More... | |
bool | hpp::fcl::BVNode< BV >::overlap (const BVNode &other, const CollisionRequest &request, FCL_REAL &sqrDistLowerBound) const |
Check whether two BVNode collide. More... | |
int | hpp::fcl::BVNodeBase::primitiveId () const |
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices) in BVHModel. More... | |
int | hpp::fcl::BVNodeBase::rightChild () const |
Return the index of the second child. The index is referred to the bounding volume array (i.e. bvs) in BVHModel. More... | |
void | hpp::fcl::CollisionObject::setCollisionGeometry (const shared_ptr< CollisionGeometry > &collision_geometry, bool compute_local_aabb=true) |
Associate a new CollisionGeometry. More... | |
void | hpp::fcl::CollisionObject::setIdentityTransform () |
set the object in local coordinate More... | |
void | hpp::fcl::CollisionObject::setRotation (const Matrix3f &R) |
set object's rotation matrix More... | |
void | hpp::fcl::CollisionObject::setTransform (const Matrix3f &R, const Vec3f &T) |
set object's transform More... | |
void | hpp::fcl::CollisionObject::setTransform (const Transform3f &tf) |
set object's transform More... | |
void | hpp::fcl::CollisionObject::setTranslation (const Vec3f &T) |
set object's translation More... | |
void | hpp::fcl::CollisionGeometry::setUserData (void *data) |
set user data in geometry More... | |
void | hpp::fcl::CollisionObject::setUserData (void *data) |
set user data in object More... | |
virtual | hpp::fcl::CollisionGeometry::~CollisionGeometry () |
hpp::fcl::CollisionObject::~CollisionObject () | |
Variables | |
AABB | hpp::fcl::CollisionObject::aabb |
AABB in global coordinate. More... | |
Vec3f | hpp::fcl::CollisionGeometry::aabb_center |
AABB center in local coordinate. More... | |
AABB | hpp::fcl::CollisionGeometry::aabb_local |
AABB in local coordinate, used for tight AABB when only translation transform. More... | |
FCL_REAL | hpp::fcl::CollisionGeometry::aabb_radius |
AABB radius. More... | |
BV | hpp::fcl::BVNode< BV >::bv |
bounding volume storing the geometry More... | |
shared_ptr< CollisionGeometry > | hpp::fcl::CollisionObject::cgeom |
FCL_REAL | hpp::fcl::CollisionGeometry::cost_density |
collision cost for unit volume More... | |
int | hpp::fcl::BVNodeBase::first_child |
An index for first child node or primitive If the value is positive, it is the index of the first child bv node If the value is negative, it is -(primitive index + 1) Zero is not used. More... | |
unsigned int | hpp::fcl::BVNodeBase::first_primitive |
The start id the primitive belonging to the current node. The index is referred to the primitive_indices in BVHModel and from that we can obtain the primitive's index in original data indirectly. More... | |
unsigned int | hpp::fcl::BVNodeBase::num_primitives |
The number of primitives belonging to the current node. More... | |
Transform3f | hpp::fcl::CollisionObject::t |
FCL_REAL | hpp::fcl::CollisionGeometry::threshold_free |
threshold for free (<= is free) More... | |
FCL_REAL | hpp::fcl::CollisionGeometry::threshold_occupied |
threshold for occupied ( >= is occupied) More... | |
void * | hpp::fcl::CollisionGeometry::user_data |
pointer to user defined data specific to this object More... | |
void * | hpp::fcl::CollisionObject::user_data |
pointer to user defined data specific to this object More... | |
Classes which are used to build a BVHModel (Bounding Volume Hierarchy)
typedef BVNodeBase hpp::fcl::BVNode< BV >::Base |
Definition at line 110 of file BV/BV_node.h.
|
inline |
Default constructor.
Definition at line 70 of file BV/BV_node.h.
|
pure virtual |
Clone *this into a new CollisionGeometry.
Implemented in hpp::fcl::Plane, hpp::fcl::Halfspace, hpp::fcl::ConvexBase, hpp::fcl::Cylinder, hpp::fcl::Cone, hpp::fcl::Capsule, hpp::fcl::BVHModel< BV >, hpp::fcl::Ellipsoid, hpp::fcl::HeightField< BV >, hpp::fcl::Sphere, hpp::fcl::Box, hpp::fcl::Convex< PolygonT >, hpp::fcl::OcTree, and hpp::fcl::TriangleP.
|
inline |
Definition at line 97 of file collision_object.h.
|
default |
Copy constructor.
|
inline |
get geometry from the object instance
Definition at line 304 of file collision_object.h.
|
inline |
get geometry from the object instance
Definition at line 309 of file collision_object.h.
|
inline |
Definition at line 217 of file collision_object.h.
|
inline |
Definition at line 223 of file collision_object.h.
|
inline |
Definition at line 229 of file collision_object.h.
|
inline |
compute the AABB in world space
Definition at line 259 of file collision_object.h.
|
inlinevirtual |
compute center of mass
Reimplemented in hpp::fcl::Cone, hpp::fcl::HeightField< BV >, hpp::fcl::BVHModelBase, and hpp::fcl::Convex< PolygonT >.
Definition at line 174 of file collision_object.h.
|
pure virtual |
compute the AABB for object in local coordinate
Implemented in hpp::fcl::Plane, hpp::fcl::Halfspace, hpp::fcl::ConvexBase, hpp::fcl::Cylinder, hpp::fcl::Cone, hpp::fcl::Capsule, hpp::fcl::Ellipsoid, hpp::fcl::HeightField< BV >, hpp::fcl::Sphere, hpp::fcl::Box, hpp::fcl::BVHModelBase, hpp::fcl::OcTree, and hpp::fcl::TriangleP.
|
inlinevirtual |
compute the inertia matrix, related to the origin
Reimplemented in hpp::fcl::Cylinder, hpp::fcl::Cone, hpp::fcl::Capsule, hpp::fcl::HeightField< BV >, hpp::fcl::Ellipsoid, hpp::fcl::BVHModelBase, hpp::fcl::Sphere, hpp::fcl::Box, and hpp::fcl::Convex< PolygonT >.
Definition at line 177 of file collision_object.h.
|
inlinevirtual |
compute the inertia matrix, related to the com
Definition at line 185 of file collision_object.h.
|
inlinevirtual |
compute the volume
Reimplemented in hpp::fcl::Cylinder, hpp::fcl::Cone, hpp::fcl::Capsule, hpp::fcl::HeightField< BV >, hpp::fcl::Ellipsoid, hpp::fcl::Sphere, hpp::fcl::BVHModelBase, hpp::fcl::Box, and hpp::fcl::Convex< PolygonT >.
Definition at line 182 of file collision_object.h.
|
inline |
Compute the distance between two BVNode. P1 and P2, if not NULL and the underlying BV supports distance, return the nearest points.
Definition at line 133 of file BV/BV_node.h.
|
inline |
get the AABB in world space
Definition at line 253 of file collision_object.h.
|
inline |
get the AABB in world space
Definition at line 256 of file collision_object.h.
|
inline |
Access to the center of the BV.
Definition at line 139 of file BV/BV_node.h.
|
inlinevirtual |
get the node type
Reimplemented in hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::Plane, hpp::fcl::Halfspace, hpp::fcl::ConvexBase, hpp::fcl::Cylinder, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::BVHModel< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::Cone, hpp::fcl::Capsule, hpp::fcl::BVHModel< BV >, hpp::fcl::Ellipsoid, hpp::fcl::OcTree, hpp::fcl::Sphere, hpp::fcl::Box, hpp::fcl::TriangleP, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, hpp::fcl::HeightField< BV >, and hpp::fcl::HeightField< BV >.
Definition at line 131 of file collision_object.h.
|
inline |
get the node type
Definition at line 250 of file collision_object.h.
|
inlinevirtual |
get the type of the object
Reimplemented in hpp::fcl::HeightField< BV >, hpp::fcl::OcTree, hpp::fcl::BVHModelBase, and hpp::fcl::ShapeBase.
Definition at line 128 of file collision_object.h.
|
inline |
get the type of the object
Definition at line 247 of file collision_object.h.
|
inline |
Access to the orientation of the BV.
Definition at line 142 of file BV/BV_node.h.
|
inline |
get matrix rotation of the object
Definition at line 280 of file collision_object.h.
|
inline |
get object's transform
Definition at line 283 of file collision_object.h.
|
inline |
get translation of the object
Definition at line 277 of file collision_object.h.
|
inline |
get user data in geometry
Definition at line 137 of file collision_object.h.
|
inline |
get user data in object
Definition at line 271 of file collision_object.h.
|
inlineprotected |
Definition at line 327 of file collision_object.h.
|
privatepure virtual |
equal operator with another object of derived type.
Implemented in hpp::fcl::Plane, hpp::fcl::Halfspace, hpp::fcl::ConvexBase, hpp::fcl::Cylinder, hpp::fcl::Cone, hpp::fcl::HeightField< BV >, hpp::fcl::Capsule, hpp::fcl::BVHModel< BV >, hpp::fcl::Ellipsoid, hpp::fcl::BVHModelBase, hpp::fcl::Sphere, hpp::fcl::OcTree, hpp::fcl::Box, and hpp::fcl::TriangleP.
|
inline |
whether the object is completely free
Definition at line 146 of file collision_object.h.
|
inline |
whether the object is in local coordinate
Definition at line 298 of file collision_object.h.
|
inline |
Whether current node is a leaf node (i.e. contains a primitive index.
Definition at line 90 of file BV/BV_node.h.
|
inlineprivatevirtual |
not equal operator with another object of derived type.
Definition at line 205 of file collision_object.h.
|
inline |
whether the object is completely occupied
Definition at line 143 of file collision_object.h.
bool hpp::fcl::CollisionGeometry::isUncertain | ( | ) | const |
whether the object has some uncertainty
Definition at line 42 of file collision_object.cpp.
|
inline |
Return the index of the first child. The index is referred to the bounding volume array (i.e. bvs) in BVHModel.
Definition at line 98 of file BV/BV_node.h.
|
inline |
Difference operator.
Definition at line 86 of file BV/BV_node.h.
|
inline |
Difference operator.
Definition at line 121 of file BV/BV_node.h.
|
inline |
Difference operator.
Definition at line 123 of file collision_object.h.
|
inline |
Definition at line 240 of file collision_object.h.
|
inline |
Equality operator.
Definition at line 79 of file BV/BV_node.h.
|
inline |
Equality operator.
Definition at line 113 of file collision_object.h.
|
inline |
Equality operator.
Definition at line 116 of file BV/BV_node.h.
|
inline |
Definition at line 236 of file collision_object.h.
|
inline |
Check whether two BVNode collide.
Definition at line 124 of file BV/BV_node.h.
|
inline |
Check whether two BVNode collide.
Definition at line 126 of file BV/BV_node.h.
|
inline |
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices) in BVHModel.
Definition at line 94 of file BV/BV_node.h.
|
inline |
Return the index of the second child. The index is referred to the bounding volume array (i.e. bvs) in BVHModel.
Definition at line 102 of file BV/BV_node.h.
|
inline |
Associate a new CollisionGeometry.
[in] | collision_geometry | The new CollisionGeometry |
[in] | compute_local_aabb | Whether the local aabb of the input new has to be computed. |
Definition at line 317 of file collision_object.h.
|
inline |
set the object in local coordinate
Definition at line 301 of file collision_object.h.
|
inline |
set object's rotation matrix
Definition at line 286 of file collision_object.h.
set object's transform
Definition at line 292 of file collision_object.h.
|
inline |
set object's transform
Definition at line 295 of file collision_object.h.
|
inline |
set object's translation
Definition at line 289 of file collision_object.h.
|
inline |
set user data in geometry
Definition at line 140 of file collision_object.h.
|
inline |
set user data in object
Definition at line 274 of file collision_object.h.
|
inlinevirtual |
Definition at line 107 of file collision_object.h.
|
inline |
Definition at line 244 of file collision_object.h.
|
mutableprotected |
AABB in global coordinate.
Definition at line 339 of file collision_object.h.
Vec3f hpp::fcl::CollisionGeometry::aabb_center |
AABB center in local coordinate.
Definition at line 152 of file collision_object.h.
AABB hpp::fcl::CollisionGeometry::aabb_local |
AABB in local coordinate, used for tight AABB when only translation transform.
Definition at line 159 of file collision_object.h.
FCL_REAL hpp::fcl::CollisionGeometry::aabb_radius |
AABB radius.
Definition at line 155 of file collision_object.h.
BV hpp::fcl::BVNode< BV >::bv |
bounding volume storing the geometry
Definition at line 113 of file BV/BV_node.h.
|
protected |
Definition at line 334 of file collision_object.h.
FCL_REAL hpp::fcl::CollisionGeometry::cost_density |
collision cost for unit volume
Definition at line 165 of file collision_object.h.
int hpp::fcl::BVNodeBase::first_child |
An index for first child node or primitive If the value is positive, it is the index of the first child bv node If the value is negative, it is -(primitive index + 1) Zero is not used.
Definition at line 59 of file BV/BV_node.h.
unsigned int hpp::fcl::BVNodeBase::first_primitive |
The start id the primitive belonging to the current node. The index is referred to the primitive_indices in BVHModel and from that we can obtain the primitive's index in original data indirectly.
Definition at line 64 of file BV/BV_node.h.
unsigned int hpp::fcl::BVNodeBase::num_primitives |
The number of primitives belonging to the current node.
Definition at line 67 of file BV/BV_node.h.
|
protected |
Definition at line 336 of file collision_object.h.
FCL_REAL hpp::fcl::CollisionGeometry::threshold_free |
threshold for free (<= is free)
Definition at line 171 of file collision_object.h.
FCL_REAL hpp::fcl::CollisionGeometry::threshold_occupied |
threshold for occupied ( >= is occupied)
Definition at line 168 of file collision_object.h.
void* hpp::fcl::CollisionGeometry::user_data |
pointer to user defined data specific to this object
Definition at line 162 of file collision_object.h.
|
protected |
pointer to user defined data specific to this object
Definition at line 342 of file collision_object.h.