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

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

Classes

class  coal::BVFitter< BV >
 The class for the default algorithm fitting a bounding volume to a set of points. More...
 
class  coal::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  coal::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  coal::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  coal::BVNodeBase
 BVNodeBase encodes the tree structure for BVH. More...
 
class  coal::BVSplitter< BV >
 A class describing the split rule that splits each BV node. More...
 
class  coal::CollisionGeometry
 The geometry for the object for collision or distance computation. More...
 
class  coal::CollisionObject
 the object for collision or distance computation, contains the geometry and the transform information More...
 

Typedefs

typedef BVNodeBase coal::BVNode< BV >::Base
 

Functions

 coal::BVNodeBase::BVNodeBase ()
 Default constructor. More...
 
virtual CollisionGeometrycoal::CollisionGeometry::clone () const =0
 Clone *this into a new CollisionGeometry. More...
 
 coal::CollisionGeometry::CollisionGeometry ()
 
const shared_ptr< CollisionGeometry > & coal::CollisionObject::collisionGeometry ()
 get shared pointer to collision geometry of the object instance More...
 
const shared_ptr< const CollisionGeometrycoal::CollisionObject::collisionGeometry () const
 get shared pointer to collision geometry of the object instance More...
 
 coal::CollisionGeometry::CollisionGeometry (const CollisionGeometry &other)=default
 Copy constructor. More...
 
CollisionGeometrycoal::CollisionObject::collisionGeometryPtr ()
 get raw pointer to collision geometry of the object instance More...
 
const CollisionGeometrycoal::CollisionObject::collisionGeometryPtr () const
 get raw pointer to collision geometry of the object instance More...
 
 coal::CollisionObject::CollisionObject (const shared_ptr< CollisionGeometry > &cgeom_, bool compute_local_aabb=true)
 
 coal::CollisionObject::CollisionObject (const shared_ptr< CollisionGeometry > &cgeom_, const Matrix3s &R, const Vec3s &T, bool compute_local_aabb=true)
 
 coal::CollisionObject::CollisionObject (const shared_ptr< CollisionGeometry > &cgeom_, const Transform3s &tf, bool compute_local_aabb=true)
 
void coal::CollisionObject::computeAABB ()
 compute the AABB in world space More...
 
virtual Vec3s coal::CollisionGeometry::computeCOM () const
 compute center of mass More...
 
virtual void coal::CollisionGeometry::computeLocalAABB ()=0
 compute the AABB for object in local coordinate More...
 
virtual Matrix3s coal::CollisionGeometry::computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
virtual Matrix3s coal::CollisionGeometry::computeMomentofInertiaRelatedToCOM () const
 compute the inertia matrix, related to the com More...
 
virtual CoalScalar coal::CollisionGeometry::computeVolume () const
 compute the volume More...
 
CoalScalar coal::BVNode< BV >::distance (const BVNode &other, Vec3s *P1=NULL, Vec3s *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...
 
AABBcoal::CollisionObject::getAABB ()
 get the AABB in world space More...
 
const AABBcoal::CollisionObject::getAABB () const
 get the AABB in world space More...
 
Vec3s coal::BVNode< BV >::getCenter () const
 Access to the center of the BV. More...
 
virtual NODE_TYPE coal::CollisionGeometry::getNodeType () const
 get the node type More...
 
NODE_TYPE coal::CollisionObject::getNodeType () const
 get the node type More...
 
virtual OBJECT_TYPE coal::CollisionGeometry::getObjectType () const
 get the type of the object More...
 
OBJECT_TYPE coal::CollisionObject::getObjectType () const
 get the type of the object More...
 
const Matrix3scoal::BVNode< BV >::getOrientation () const
 Access to the orientation of the BV. More...
 
const Matrix3scoal::CollisionObject::getRotation () const
 get matrix rotation of the object More...
 
const Transform3scoal::CollisionObject::getTransform () const
 get object's transform More...
 
const Vec3scoal::CollisionObject::getTranslation () const
 get translation of the object More...
 
void * coal::CollisionGeometry::getUserData () const
 get user data in geometry More...
 
void * coal::CollisionObject::getUserData () const
 get user data in object More...
 
void coal::CollisionObject::init (bool compute_local_aabb=true)
 
virtual bool coal::CollisionGeometry::isEqual (const CollisionGeometry &other) const =0
 equal operator with another object of derived type. More...
 
bool coal::CollisionGeometry::isFree () const
 whether the object is completely free More...
 
bool coal::CollisionObject::isIdentityTransform () const
 whether the object is in local coordinate More...
 
bool coal::BVNodeBase::isLeaf () const
 Whether current node is a leaf node (i.e. contains a primitive index. More...
 
virtual bool coal::CollisionGeometry::isNotEqual (const CollisionGeometry &other) const
 not equal operator with another object of derived type. More...
 
bool coal::CollisionGeometry::isOccupied () const
 whether the object is completely occupied More...
 
bool coal::CollisionGeometry::isUncertain () const
 whether the object has some uncertainty More...
 
int coal::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 coal::BVNode< BV >::operator!= (const BVNode &other) const
 Difference operator. More...
 
bool coal::BVNodeBase::operator!= (const BVNodeBase &other) const
 Difference operator. More...
 
bool coal::CollisionGeometry::operator!= (const CollisionGeometry &other) const
 Difference operator. More...
 
bool coal::CollisionObject::operator!= (const CollisionObject &other) const
 
bool coal::BVNode< BV >::operator== (const BVNode &other) const
 Equality operator. More...
 
bool coal::BVNodeBase::operator== (const BVNodeBase &other) const
 Equality operator. More...
 
bool coal::CollisionGeometry::operator== (const CollisionGeometry &other) const
 Equality operator. More...
 
bool coal::CollisionObject::operator== (const CollisionObject &other) const
 
bool coal::BVNode< BV >::overlap (const BVNode &other) const
 Check whether two BVNode collide. More...
 
bool coal::BVNode< BV >::overlap (const BVNode &other, const CollisionRequest &request, CoalScalar &sqrDistLowerBound) const
 Check whether two BVNode collide. More...
 
int coal::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 coal::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 coal::CollisionObject::setCollisionGeometry (const shared_ptr< CollisionGeometry > &collision_geometry, bool compute_local_aabb=true)
 Associate a new CollisionGeometry. More...
 
void coal::CollisionObject::setIdentityTransform ()
 set the object in local coordinate More...
 
void coal::CollisionObject::setRotation (const Matrix3s &R)
 set object's rotation matrix More...
 
void coal::CollisionObject::setTransform (const Matrix3s &R, const Vec3s &T)
 set object's transform More...
 
void coal::CollisionObject::setTransform (const Transform3s &tf)
 set object's transform More...
 
void coal::CollisionObject::setTranslation (const Vec3s &T)
 set object's translation More...
 
void coal::CollisionGeometry::setUserData (void *data)
 set user data in geometry More...
 
void coal::CollisionObject::setUserData (void *data)
 set user data in object More...
 
virtual coal::CollisionGeometry::~CollisionGeometry ()
 
 coal::CollisionObject::~CollisionObject ()
 

Variables

AABB coal::CollisionObject::aabb
 AABB in global coordinate. More...
 
Vec3s coal::CollisionGeometry::aabb_center
 AABB center in local coordinate. More...
 
AABB coal::CollisionGeometry::aabb_local
 AABB in local coordinate, used for tight AABB when only translation transform. More...
 
CoalScalar coal::CollisionGeometry::aabb_radius
 AABB radius. More...
 
BV coal::BVNode< BV >::bv
 bounding volume storing the geometry More...
 
shared_ptr< CollisionGeometrycoal::CollisionObject::cgeom
 
CoalScalar coal::CollisionGeometry::cost_density
 collision cost for unit volume More...
 
int coal::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 coal::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 coal::BVNodeBase::num_primitives
 The number of primitives belonging to the current node. More...
 
Transform3s coal::CollisionObject::t
 
CoalScalar coal::CollisionGeometry::threshold_free
 threshold for free (<= is free) More...
 
CoalScalar coal::CollisionGeometry::threshold_occupied
 threshold for occupied ( >= is occupied) More...
 
void * coal::CollisionGeometry::user_data
 pointer to user defined data specific to this object More...
 
void * coal::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 coal::BVNode< BV >::Base

Definition at line 107 of file coal/BV/BV_node.h.

Function Documentation

◆ BVNodeBase()

coal::BVNodeBase::BVNodeBase ( )
inline

Default constructor.

Definition at line 67 of file coal/BV/BV_node.h.

◆ clone()

virtual CollisionGeometry* coal::CollisionGeometry::clone ( ) const
pure virtual

◆ CollisionGeometry() [1/2]

coal::CollisionGeometry::CollisionGeometry ( )
inline

Definition at line 96 of file coal/collision_object.h.

◆ collisionGeometry() [1/2]

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

get shared pointer to collision geometry of the object instance

Definition at line 316 of file coal/collision_object.h.

◆ collisionGeometry() [2/2]

const shared_ptr<const CollisionGeometry> coal::CollisionObject::collisionGeometry ( ) const
inline

get shared pointer to collision geometry of the object instance

Definition at line 311 of file coal/collision_object.h.

◆ CollisionGeometry() [2/2]

coal::CollisionGeometry::CollisionGeometry ( const CollisionGeometry other)
default

Copy constructor.

◆ collisionGeometryPtr() [1/2]

CollisionGeometry* coal::CollisionObject::collisionGeometryPtr ( )
inline

get raw pointer to collision geometry of the object instance

Definition at line 322 of file coal/collision_object.h.

◆ collisionGeometryPtr() [2/2]

const CollisionGeometry* coal::CollisionObject::collisionGeometryPtr ( ) const
inline

get raw pointer to collision geometry of the object instance

Definition at line 319 of file coal/collision_object.h.

◆ CollisionObject() [1/3]

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

Definition at line 216 of file coal/collision_object.h.

◆ CollisionObject() [2/3]

coal::CollisionObject::CollisionObject ( const shared_ptr< CollisionGeometry > &  cgeom_,
const Matrix3s R,
const Vec3s T,
bool  compute_local_aabb = true 
)
inline

Definition at line 228 of file coal/collision_object.h.

◆ CollisionObject() [3/3]

coal::CollisionObject::CollisionObject ( const shared_ptr< CollisionGeometry > &  cgeom_,
const Transform3s tf,
bool  compute_local_aabb = true 
)
inline

Definition at line 222 of file coal/collision_object.h.

◆ computeAABB()

void coal::CollisionObject::computeAABB ( )
inline

compute the AABB in world space

Definition at line 258 of file coal/collision_object.h.

◆ computeCOM()

virtual Vec3s coal::CollisionGeometry::computeCOM ( ) const
inlinevirtual

compute center of mass

Reimplemented in coal::Cone, coal::HeightField< BV >, and coal::BVHModelBase.

Definition at line 173 of file coal/collision_object.h.

◆ computeLocalAABB()

virtual void coal::CollisionGeometry::computeLocalAABB ( )
pure virtual

◆ computeMomentofInertia()

virtual Matrix3s coal::CollisionGeometry::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented in coal::Cylinder, coal::Cone, coal::Capsule, coal::HeightField< BV >, coal::Ellipsoid, coal::Sphere, coal::BVHModelBase, and coal::Box.

Definition at line 176 of file coal/collision_object.h.

◆ computeMomentofInertiaRelatedToCOM()

virtual Matrix3s coal::CollisionGeometry::computeMomentofInertiaRelatedToCOM ( ) const
inlinevirtual

compute the inertia matrix, related to the com

Definition at line 184 of file coal/collision_object.h.

◆ computeVolume()

virtual CoalScalar coal::CollisionGeometry::computeVolume ( ) const
inlinevirtual

◆ distance()

template<typename BV >
CoalScalar coal::BVNode< BV >::distance ( const BVNode< BV > &  other,
Vec3s P1 = NULL,
Vec3s 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 130 of file coal/BV/BV_node.h.

◆ getAABB() [1/2]

AABB& coal::CollisionObject::getAABB ( )
inline

get the AABB in world space

Definition at line 255 of file coal/collision_object.h.

◆ getAABB() [2/2]

const AABB& coal::CollisionObject::getAABB ( ) const
inline

get the AABB in world space

Definition at line 252 of file coal/collision_object.h.

◆ getCenter()

template<typename BV >
Vec3s coal::BVNode< BV >::getCenter ( ) const
inline

Access to the center of the BV.

Definition at line 136 of file coal/BV/BV_node.h.

◆ getNodeType() [1/2]

virtual NODE_TYPE coal::CollisionGeometry::getNodeType ( ) const
inlinevirtual

◆ getNodeType() [2/2]

NODE_TYPE coal::CollisionObject::getNodeType ( ) const
inline

get the node type

Definition at line 249 of file coal/collision_object.h.

◆ getObjectType() [1/2]

virtual OBJECT_TYPE coal::CollisionGeometry::getObjectType ( ) const
inlinevirtual

get the type of the object

Reimplemented in coal::HeightField< BV >, coal::OcTree, coal::BVHModelBase, and coal::ShapeBase.

Definition at line 127 of file coal/collision_object.h.

◆ getObjectType() [2/2]

OBJECT_TYPE coal::CollisionObject::getObjectType ( ) const
inline

get the type of the object

Definition at line 246 of file coal/collision_object.h.

◆ getOrientation()

template<typename BV >
const Matrix3s& coal::BVNode< BV >::getOrientation ( ) const
inline

Access to the orientation of the BV.

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

◆ getRotation()

const Matrix3s& coal::CollisionObject::getRotation ( ) const
inline

get matrix rotation of the object

Definition at line 287 of file coal/collision_object.h.

◆ getTransform()

const Transform3s& coal::CollisionObject::getTransform ( ) const
inline

get object's transform

Definition at line 290 of file coal/collision_object.h.

◆ getTranslation()

const Vec3s& coal::CollisionObject::getTranslation ( ) const
inline

get translation of the object

Definition at line 284 of file coal/collision_object.h.

◆ getUserData() [1/2]

void* coal::CollisionGeometry::getUserData ( ) const
inline

get user data in geometry

Definition at line 136 of file coal/collision_object.h.

◆ getUserData() [2/2]

void* coal::CollisionObject::getUserData ( ) const
inline

get user data in object

Definition at line 278 of file coal/collision_object.h.

◆ init()

void coal::CollisionObject::init ( bool  compute_local_aabb = true)
inlineprotected

Definition at line 340 of file coal/collision_object.h.

◆ isEqual()

virtual bool coal::CollisionGeometry::isEqual ( const CollisionGeometry other) const
privatepure virtual

◆ isFree()

bool coal::CollisionGeometry::isFree ( ) const
inline

whether the object is completely free

Definition at line 145 of file coal/collision_object.h.

◆ isIdentityTransform()

bool coal::CollisionObject::isIdentityTransform ( ) const
inline

whether the object is in local coordinate

Definition at line 305 of file coal/collision_object.h.

◆ isLeaf()

bool coal::BVNodeBase::isLeaf ( ) const
inline

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

Definition at line 87 of file coal/BV/BV_node.h.

◆ isNotEqual()

virtual bool coal::CollisionGeometry::isNotEqual ( const CollisionGeometry other) const
inlineprivatevirtual

not equal operator with another object of derived type.

Definition at line 204 of file coal/collision_object.h.

◆ isOccupied()

bool coal::CollisionGeometry::isOccupied ( ) const
inline

whether the object is completely occupied

Definition at line 142 of file coal/collision_object.h.

◆ isUncertain()

bool coal::CollisionGeometry::isUncertain ( ) const

whether the object has some uncertainty

Definition at line 41 of file collision_object.cpp.

◆ leftChild()

int coal::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 95 of file coal/BV/BV_node.h.

◆ operator!=() [1/4]

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

Difference operator.

Definition at line 118 of file coal/BV/BV_node.h.

◆ operator!=() [2/4]

bool coal::BVNodeBase::operator!= ( const BVNodeBase other) const
inline

Difference operator.

Definition at line 83 of file coal/BV/BV_node.h.

◆ operator!=() [3/4]

bool coal::CollisionGeometry::operator!= ( const CollisionGeometry other) const
inline

Difference operator.

Definition at line 122 of file coal/collision_object.h.

◆ operator!=() [4/4]

bool coal::CollisionObject::operator!= ( const CollisionObject other) const
inline

Definition at line 239 of file coal/collision_object.h.

◆ operator==() [1/4]

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

Equality operator.

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

◆ operator==() [2/4]

bool coal::BVNodeBase::operator== ( const BVNodeBase other) const
inline

Equality operator.

Definition at line 76 of file coal/BV/BV_node.h.

◆ operator==() [3/4]

bool coal::CollisionGeometry::operator== ( const CollisionGeometry other) const
inline

Equality operator.

Definition at line 112 of file coal/collision_object.h.

◆ operator==() [4/4]

bool coal::CollisionObject::operator== ( const CollisionObject other) const
inline

Definition at line 235 of file coal/collision_object.h.

◆ overlap() [1/2]

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

Check whether two BVNode collide.

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

◆ overlap() [2/2]

template<typename BV >
bool coal::BVNode< BV >::overlap ( const BVNode< BV > &  other,
const CollisionRequest request,
CoalScalar sqrDistLowerBound 
) const
inline

Check whether two BVNode collide.

Definition at line 123 of file coal/BV/BV_node.h.

◆ primitiveId()

int coal::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 91 of file coal/BV/BV_node.h.

◆ rightChild()

int coal::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 99 of file coal/BV/BV_node.h.

◆ setCollisionGeometry()

void coal::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 330 of file coal/collision_object.h.

◆ setIdentityTransform()

void coal::CollisionObject::setIdentityTransform ( )
inline

set the object in local coordinate

Definition at line 308 of file coal/collision_object.h.

◆ setRotation()

void coal::CollisionObject::setRotation ( const Matrix3s R)
inline

set object's rotation matrix

Definition at line 293 of file coal/collision_object.h.

◆ setTransform() [1/2]

void coal::CollisionObject::setTransform ( const Matrix3s R,
const Vec3s T 
)
inline

set object's transform

Definition at line 299 of file coal/collision_object.h.

◆ setTransform() [2/2]

void coal::CollisionObject::setTransform ( const Transform3s tf)
inline

set object's transform

Definition at line 302 of file coal/collision_object.h.

◆ setTranslation()

void coal::CollisionObject::setTranslation ( const Vec3s T)
inline

set object's translation

Definition at line 296 of file coal/collision_object.h.

◆ setUserData() [1/2]

void coal::CollisionGeometry::setUserData ( void *  data)
inline

set user data in geometry

Definition at line 139 of file coal/collision_object.h.

◆ setUserData() [2/2]

void coal::CollisionObject::setUserData ( void *  data)
inline

set user data in object

Definition at line 281 of file coal/collision_object.h.

◆ ~CollisionGeometry()

virtual coal::CollisionGeometry::~CollisionGeometry ( )
inlinevirtual

Definition at line 106 of file coal/collision_object.h.

◆ ~CollisionObject()

coal::CollisionObject::~CollisionObject ( )
inline

Definition at line 243 of file coal/collision_object.h.

Variable Documentation

◆ aabb

AABB coal::CollisionObject::aabb
mutableprotected

AABB in global coordinate.

Definition at line 352 of file coal/collision_object.h.

◆ aabb_center

Vec3s coal::CollisionGeometry::aabb_center

AABB center in local coordinate.

Definition at line 151 of file coal/collision_object.h.

◆ aabb_local

AABB coal::CollisionGeometry::aabb_local

AABB in local coordinate, used for tight AABB when only translation transform.

Definition at line 158 of file coal/collision_object.h.

◆ aabb_radius

CoalScalar coal::CollisionGeometry::aabb_radius

AABB radius.

Definition at line 154 of file coal/collision_object.h.

◆ bv

template<typename BV >
BV coal::BVNode< BV >::bv

bounding volume storing the geometry

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

◆ cgeom

shared_ptr<CollisionGeometry> coal::CollisionObject::cgeom
protected

Definition at line 347 of file coal/collision_object.h.

◆ cost_density

CoalScalar coal::CollisionGeometry::cost_density

collision cost for unit volume

Definition at line 164 of file coal/collision_object.h.

◆ first_child

int coal::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 56 of file coal/BV/BV_node.h.

◆ first_primitive

unsigned int coal::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 61 of file coal/BV/BV_node.h.

◆ num_primitives

unsigned int coal::BVNodeBase::num_primitives

The number of primitives belonging to the current node.

Definition at line 64 of file coal/BV/BV_node.h.

◆ t

Transform3s coal::CollisionObject::t
protected

Definition at line 349 of file coal/collision_object.h.

◆ threshold_free

CoalScalar coal::CollisionGeometry::threshold_free

threshold for free (<= is free)

Definition at line 170 of file coal/collision_object.h.

◆ threshold_occupied

CoalScalar coal::CollisionGeometry::threshold_occupied

threshold for occupied ( >= is occupied)

Definition at line 167 of file coal/collision_object.h.

◆ user_data [1/2]

void* coal::CollisionGeometry::user_data

pointer to user defined data specific to this object

Definition at line 161 of file coal/collision_object.h.

◆ user_data [2/2]

void* coal::CollisionObject::user_data
protected

pointer to user defined data specific to this object

Definition at line 355 of file coal/collision_object.h.



hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:59