Classes | Typedefs | Enumerator | Functions | Variables
Construction of BVHModel

Classes which are used to build a BVHModel (Bounding Volume Hierarchy) More...

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 CollisionGeometryhpp::fcl::CollisionGeometry::clone () const =0
 Clone *this into a new CollisionGeometry. More...
 
 hpp::fcl::CollisionGeometry::CollisionGeometry ()
 
const shared_ptr< CollisionGeometry > & hpp::fcl::CollisionObject::collisionGeometry ()
 get shared pointer to collision geometry of the object instance More...
 
const shared_ptr< const CollisionGeometryhpp::fcl::CollisionObject::collisionGeometry () const
 get shared pointer to collision geometry of the object instance More...
 
 hpp::fcl::CollisionGeometry::CollisionGeometry (const CollisionGeometry &other)=default
 Copy constructor. More...
 
CollisionGeometryhpp::fcl::CollisionObject::collisionGeometryPtr ()
 get raw pointer to collision geometry of the object instance More...
 
const CollisionGeometryhpp::fcl::CollisionObject::collisionGeometryPtr () const
 get raw pointer to collision geometry of 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 Matrix3f &R, const Vec3f &T, bool compute_local_aabb=true)
 
 hpp::fcl::CollisionObject::CollisionObject (const shared_ptr< CollisionGeometry > &cgeom_, const Transform3f &tf, 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...
 
AABBhpp::fcl::CollisionObject::getAABB ()
 get the AABB in world space More...
 
const AABBhpp::fcl::CollisionObject::getAABB () const
 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 Matrix3fhpp::fcl::BVNode< BV >::getOrientation () const
 Access to the orientation of the BV. More...
 
const Matrix3fhpp::fcl::CollisionObject::getRotation () const
 get matrix rotation of the object More...
 
const Transform3fhpp::fcl::CollisionObject::getTransform () const
 get object's transform More...
 
const Vec3fhpp::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::BVNode< BV >::operator!= (const BVNode &other) const
 Difference operator. More...
 
bool hpp::fcl::BVNodeBase::operator!= (const BVNodeBase &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::BVNode< BV >::operator== (const BVNode &other) const
 Equality operator. More...
 
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::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< CollisionGeometryhpp::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...
 

Detailed Description

Classes which are used to build a BVHModel (Bounding Volume Hierarchy)

Typedef Documentation

◆ Base

template<typename BV >
typedef BVNodeBase hpp::fcl::BVNode< BV >::Base

Definition at line 110 of file BV/BV_node.h.

Function Documentation

◆ BVNodeBase()

hpp::fcl::BVNodeBase::BVNodeBase ( )
inline

Default constructor.

Definition at line 70 of file BV/BV_node.h.

◆ clone()

virtual CollisionGeometry* hpp::fcl::CollisionGeometry::clone ( ) const
pure virtual

◆ CollisionGeometry() [1/2]

hpp::fcl::CollisionGeometry::CollisionGeometry ( )
inline

Definition at line 97 of file collision_object.h.

◆ collisionGeometry() [1/2]

const shared_ptr<CollisionGeometry>& hpp::fcl::CollisionObject::collisionGeometry ( )
inline

get shared pointer to collision geometry of the object instance

Definition at line 309 of file collision_object.h.

◆ collisionGeometry() [2/2]

const shared_ptr<const CollisionGeometry> hpp::fcl::CollisionObject::collisionGeometry ( ) const
inline

get shared pointer to collision geometry of the object instance

Definition at line 304 of file collision_object.h.

◆ CollisionGeometry() [2/2]

hpp::fcl::CollisionGeometry::CollisionGeometry ( const CollisionGeometry other)
default

Copy constructor.

◆ collisionGeometryPtr() [1/2]

CollisionGeometry* hpp::fcl::CollisionObject::collisionGeometryPtr ( )
inline

get raw pointer to collision geometry of the object instance

Definition at line 315 of file collision_object.h.

◆ collisionGeometryPtr() [2/2]

const CollisionGeometry* hpp::fcl::CollisionObject::collisionGeometryPtr ( ) const
inline

get raw pointer to collision geometry of the object instance

Definition at line 312 of file collision_object.h.

◆ CollisionObject() [1/3]

hpp::fcl::CollisionObject::CollisionObject ( const shared_ptr< CollisionGeometry > &  cgeom_,
bool  compute_local_aabb = true 
)
inline

Definition at line 217 of file collision_object.h.

◆ CollisionObject() [2/3]

hpp::fcl::CollisionObject::CollisionObject ( const shared_ptr< CollisionGeometry > &  cgeom_,
const Matrix3f R,
const Vec3f T,
bool  compute_local_aabb = true 
)
inline

Definition at line 229 of file collision_object.h.

◆ CollisionObject() [3/3]

hpp::fcl::CollisionObject::CollisionObject ( const shared_ptr< CollisionGeometry > &  cgeom_,
const Transform3f tf,
bool  compute_local_aabb = true 
)
inline

Definition at line 223 of file collision_object.h.

◆ computeAABB()

void hpp::fcl::CollisionObject::computeAABB ( )
inline

compute the AABB in world space

Definition at line 259 of file collision_object.h.

◆ computeCOM()

virtual Vec3f hpp::fcl::CollisionGeometry::computeCOM ( ) const
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.

◆ computeLocalAABB()

virtual void hpp::fcl::CollisionGeometry::computeLocalAABB ( )
pure virtual

◆ computeMomentofInertia()

virtual Matrix3f hpp::fcl::CollisionGeometry::computeMomentofInertia ( ) const
inlinevirtual

◆ computeMomentofInertiaRelatedToCOM()

virtual Matrix3f hpp::fcl::CollisionGeometry::computeMomentofInertiaRelatedToCOM ( ) const
inlinevirtual

compute the inertia matrix, related to the com

Definition at line 185 of file collision_object.h.

◆ computeVolume()

virtual FCL_REAL hpp::fcl::CollisionGeometry::computeVolume ( ) const
inlinevirtual

◆ distance()

template<typename BV >
FCL_REAL hpp::fcl::BVNode< BV >::distance ( const BVNode< BV > &  other,
Vec3f P1 = NULL,
Vec3f P2 = NULL 
) const
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.

◆ getAABB() [1/2]

AABB& hpp::fcl::CollisionObject::getAABB ( )
inline

get the AABB in world space

Definition at line 256 of file collision_object.h.

◆ getAABB() [2/2]

const AABB& hpp::fcl::CollisionObject::getAABB ( ) const
inline

get the AABB in world space

Definition at line 253 of file collision_object.h.

◆ getCenter()

template<typename BV >
Vec3f hpp::fcl::BVNode< BV >::getCenter ( ) const
inline

Access to the center of the BV.

Definition at line 139 of file BV/BV_node.h.

◆ getNodeType() [1/2]

virtual NODE_TYPE hpp::fcl::CollisionGeometry::getNodeType ( ) const
inlinevirtual

◆ getNodeType() [2/2]

NODE_TYPE hpp::fcl::CollisionObject::getNodeType ( ) const
inline

get the node type

Definition at line 250 of file collision_object.h.

◆ getObjectType() [1/2]

virtual OBJECT_TYPE hpp::fcl::CollisionGeometry::getObjectType ( ) const
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.

◆ getObjectType() [2/2]

OBJECT_TYPE hpp::fcl::CollisionObject::getObjectType ( ) const
inline

get the type of the object

Definition at line 247 of file collision_object.h.

◆ getOrientation()

template<typename BV >
const Matrix3f& hpp::fcl::BVNode< BV >::getOrientation ( ) const
inline

Access to the orientation of the BV.

Definition at line 142 of file BV/BV_node.h.

◆ getRotation()

const Matrix3f& hpp::fcl::CollisionObject::getRotation ( ) const
inline

get matrix rotation of the object

Definition at line 280 of file collision_object.h.

◆ getTransform()

const Transform3f& hpp::fcl::CollisionObject::getTransform ( ) const
inline

get object's transform

Definition at line 283 of file collision_object.h.

◆ getTranslation()

const Vec3f& hpp::fcl::CollisionObject::getTranslation ( ) const
inline

get translation of the object

Definition at line 277 of file collision_object.h.

◆ getUserData() [1/2]

void* hpp::fcl::CollisionGeometry::getUserData ( ) const
inline

get user data in geometry

Definition at line 137 of file collision_object.h.

◆ getUserData() [2/2]

void* hpp::fcl::CollisionObject::getUserData ( ) const
inline

get user data in object

Definition at line 271 of file collision_object.h.

◆ init()

void hpp::fcl::CollisionObject::init ( bool  compute_local_aabb = true)
inlineprotected

Definition at line 333 of file collision_object.h.

◆ isEqual()

virtual bool hpp::fcl::CollisionGeometry::isEqual ( const CollisionGeometry other) const
privatepure virtual

◆ isFree()

bool hpp::fcl::CollisionGeometry::isFree ( ) const
inline

whether the object is completely free

Definition at line 146 of file collision_object.h.

◆ isIdentityTransform()

bool hpp::fcl::CollisionObject::isIdentityTransform ( ) const
inline

whether the object is in local coordinate

Definition at line 298 of file collision_object.h.

◆ isLeaf()

bool hpp::fcl::BVNodeBase::isLeaf ( ) const
inline

Whether current node is a leaf node (i.e. contains a primitive index.

Definition at line 90 of file BV/BV_node.h.

◆ isNotEqual()

virtual bool hpp::fcl::CollisionGeometry::isNotEqual ( const CollisionGeometry other) const
inlineprivatevirtual

not equal operator with another object of derived type.

Definition at line 205 of file collision_object.h.

◆ isOccupied()

bool hpp::fcl::CollisionGeometry::isOccupied ( ) const
inline

whether the object is completely occupied

Definition at line 143 of file collision_object.h.

◆ isUncertain()

bool hpp::fcl::CollisionGeometry::isUncertain ( ) const

whether the object has some uncertainty

Definition at line 42 of file collision_object.cpp.

◆ leftChild()

int hpp::fcl::BVNodeBase::leftChild ( ) const
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.

◆ operator!=() [1/4]

template<typename BV >
bool hpp::fcl::BVNode< BV >::operator!= ( const BVNode< BV > &  other) const
inline

Difference operator.

Definition at line 121 of file BV/BV_node.h.

◆ operator!=() [2/4]

bool hpp::fcl::BVNodeBase::operator!= ( const BVNodeBase other) const
inline

Difference operator.

Definition at line 86 of file BV/BV_node.h.

◆ operator!=() [3/4]

bool hpp::fcl::CollisionGeometry::operator!= ( const CollisionGeometry other) const
inline

Difference operator.

Definition at line 123 of file collision_object.h.

◆ operator!=() [4/4]

bool hpp::fcl::CollisionObject::operator!= ( const CollisionObject other) const
inline

Definition at line 240 of file collision_object.h.

◆ operator==() [1/4]

template<typename BV >
bool hpp::fcl::BVNode< BV >::operator== ( const BVNode< BV > &  other) const
inline

Equality operator.

Definition at line 116 of file BV/BV_node.h.

◆ operator==() [2/4]

bool hpp::fcl::BVNodeBase::operator== ( const BVNodeBase other) const
inline

Equality operator.

Definition at line 79 of file BV/BV_node.h.

◆ operator==() [3/4]

bool hpp::fcl::CollisionGeometry::operator== ( const CollisionGeometry other) const
inline

Equality operator.

Definition at line 113 of file collision_object.h.

◆ operator==() [4/4]

bool hpp::fcl::CollisionObject::operator== ( const CollisionObject other) const
inline

Definition at line 236 of file collision_object.h.

◆ overlap() [1/2]

template<typename BV >
bool hpp::fcl::BVNode< BV >::overlap ( const BVNode< BV > &  other) const
inline

Check whether two BVNode collide.

Definition at line 124 of file BV/BV_node.h.

◆ overlap() [2/2]

template<typename BV >
bool hpp::fcl::BVNode< BV >::overlap ( const BVNode< BV > &  other,
const CollisionRequest request,
FCL_REAL sqrDistLowerBound 
) const
inline

Check whether two BVNode collide.

Definition at line 126 of file BV/BV_node.h.

◆ primitiveId()

int hpp::fcl::BVNodeBase::primitiveId ( ) const
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.

◆ rightChild()

int hpp::fcl::BVNodeBase::rightChild ( ) const
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.

◆ setCollisionGeometry()

void hpp::fcl::CollisionObject::setCollisionGeometry ( const shared_ptr< CollisionGeometry > &  collision_geometry,
bool  compute_local_aabb = true 
)
inline

Associate a new CollisionGeometry.

Parameters
[in]collision_geometryThe new CollisionGeometry
[in]compute_local_aabbWhether the local aabb of the input new has to be computed.

Definition at line 323 of file collision_object.h.

◆ setIdentityTransform()

void hpp::fcl::CollisionObject::setIdentityTransform ( )
inline

set the object in local coordinate

Definition at line 301 of file collision_object.h.

◆ setRotation()

void hpp::fcl::CollisionObject::setRotation ( const Matrix3f R)
inline

set object's rotation matrix

Definition at line 286 of file collision_object.h.

◆ setTransform() [1/2]

void hpp::fcl::CollisionObject::setTransform ( const Matrix3f R,
const Vec3f T 
)
inline

set object's transform

Definition at line 292 of file collision_object.h.

◆ setTransform() [2/2]

void hpp::fcl::CollisionObject::setTransform ( const Transform3f tf)
inline

set object's transform

Definition at line 295 of file collision_object.h.

◆ setTranslation()

void hpp::fcl::CollisionObject::setTranslation ( const Vec3f T)
inline

set object's translation

Definition at line 289 of file collision_object.h.

◆ setUserData() [1/2]

void hpp::fcl::CollisionGeometry::setUserData ( void *  data)
inline

set user data in geometry

Definition at line 140 of file collision_object.h.

◆ setUserData() [2/2]

void hpp::fcl::CollisionObject::setUserData ( void *  data)
inline

set user data in object

Definition at line 274 of file collision_object.h.

◆ ~CollisionGeometry()

virtual hpp::fcl::CollisionGeometry::~CollisionGeometry ( )
inlinevirtual

Definition at line 107 of file collision_object.h.

◆ ~CollisionObject()

hpp::fcl::CollisionObject::~CollisionObject ( )
inline

Definition at line 244 of file collision_object.h.

Variable Documentation

◆ aabb

AABB hpp::fcl::CollisionObject::aabb
mutableprotected

AABB in global coordinate.

Definition at line 345 of file collision_object.h.

◆ aabb_center

Vec3f hpp::fcl::CollisionGeometry::aabb_center

AABB center in local coordinate.

Definition at line 152 of file collision_object.h.

◆ aabb_local

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.

◆ aabb_radius

FCL_REAL hpp::fcl::CollisionGeometry::aabb_radius

AABB radius.

Definition at line 155 of file collision_object.h.

◆ bv

template<typename BV >
BV hpp::fcl::BVNode< BV >::bv

bounding volume storing the geometry

Definition at line 113 of file BV/BV_node.h.

◆ cgeom

shared_ptr<CollisionGeometry> hpp::fcl::CollisionObject::cgeom
protected

Definition at line 340 of file collision_object.h.

◆ cost_density

FCL_REAL hpp::fcl::CollisionGeometry::cost_density

collision cost for unit volume

Definition at line 165 of file collision_object.h.

◆ first_child

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.

◆ first_primitive

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.

◆ num_primitives

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.

◆ t

Transform3f hpp::fcl::CollisionObject::t
protected

Definition at line 342 of file collision_object.h.

◆ threshold_free

FCL_REAL hpp::fcl::CollisionGeometry::threshold_free

threshold for free (<= is free)

Definition at line 171 of file collision_object.h.

◆ threshold_occupied

FCL_REAL hpp::fcl::CollisionGeometry::threshold_occupied

threshold for occupied ( >= is occupied)

Definition at line 168 of file collision_object.h.

◆ user_data [1/2]

void* hpp::fcl::CollisionGeometry::user_data

pointer to user defined data specific to this object

Definition at line 162 of file collision_object.h.

◆ user_data [2/2]

void* hpp::fcl::CollisionObject::user_data
protected

pointer to user defined data specific to this object

Definition at line 348 of file collision_object.h.



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