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 CollisionGeometry * | coal::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 CollisionGeometry > | coal::CollisionObject::collisionGeometry () const |
get shared pointer to collision geometry of the object instance More... | |
coal::CollisionGeometry::CollisionGeometry (const CollisionGeometry &other)=default | |
Copy constructor. More... | |
CollisionGeometry * | coal::CollisionObject::collisionGeometryPtr () |
get raw pointer to collision geometry of the object instance More... | |
const CollisionGeometry * | coal::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... | |
AABB & | coal::CollisionObject::getAABB () |
get the AABB in world space More... | |
const AABB & | coal::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 Matrix3s & | coal::BVNode< BV >::getOrientation () const |
Access to the orientation of the BV. More... | |
const Matrix3s & | coal::CollisionObject::getRotation () const |
get matrix rotation of the object More... | |
const Transform3s & | coal::CollisionObject::getTransform () const |
get object's transform More... | |
const Vec3s & | coal::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< CollisionGeometry > | coal::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... | |
Classes which are used to build a BVHModel (Bounding Volume Hierarchy)
typedef BVNodeBase coal::BVNode< BV >::Base |
Definition at line 107 of file coal/BV/BV_node.h.
|
inline |
Default constructor.
Definition at line 67 of file coal/BV/BV_node.h.
|
pure virtual |
Clone *this into a new CollisionGeometry.
Implemented in coal::Plane, coal::Halfspace, coal::ConvexBase, coal::Cylinder, coal::Cone, coal::Capsule, coal::BVHModel< BV >, coal::Ellipsoid, coal::HeightField< BV >, coal::Sphere, coal::Box, coal::TriangleP, and coal::OcTree.
|
inline |
Definition at line 96 of file coal/collision_object.h.
|
inline |
get shared pointer to collision geometry of the object instance
Definition at line 316 of file coal/collision_object.h.
|
inline |
get shared pointer to collision geometry of the object instance
Definition at line 311 of file coal/collision_object.h.
|
default |
Copy constructor.
|
inline |
get raw pointer to collision geometry of the object instance
Definition at line 322 of file coal/collision_object.h.
|
inline |
get raw pointer to collision geometry of the object instance
Definition at line 319 of file coal/collision_object.h.
|
inline |
Definition at line 216 of file coal/collision_object.h.
|
inline |
Definition at line 228 of file coal/collision_object.h.
|
inline |
Definition at line 222 of file coal/collision_object.h.
|
inline |
compute the AABB in world space
Definition at line 258 of file coal/collision_object.h.
|
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.
|
pure virtual |
compute the AABB for object in local coordinate
Implemented in coal::Plane, coal::Halfspace, coal::ConvexBase, coal::Cylinder, coal::Cone, coal::Capsule, coal::Ellipsoid, coal::HeightField< BV >, coal::Sphere, coal::Box, coal::TriangleP, coal::BVHModelBase, and coal::OcTree.
|
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.
|
inlinevirtual |
compute the inertia matrix, related to the com
Definition at line 184 of file coal/collision_object.h.
|
inlinevirtual |
compute the volume
Reimplemented in coal::Cylinder, coal::Cone, coal::Capsule, coal::Ellipsoid, coal::HeightField< BV >, coal::Sphere, coal::BVHModelBase, and coal::Box.
Definition at line 181 of file coal/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 130 of file coal/BV/BV_node.h.
|
inline |
get the AABB in world space
Definition at line 255 of file coal/collision_object.h.
|
inline |
get the AABB in world space
Definition at line 252 of file coal/collision_object.h.
|
inline |
Access to the center of the BV.
Definition at line 136 of file coal/BV/BV_node.h.
|
inlinevirtual |
get the node type
Reimplemented in coal::BVHModel< BV >, coal::BVHModel< BV >, coal::BVHModel< BV >, coal::BVHModel< BV >, coal::BVHModel< BV >, coal::BVHModel< BV >, coal::BVHModel< BV >, coal::BVHModel< BV >, coal::Plane, coal::Halfspace, coal::ConvexBase, coal::Cylinder, coal::HeightField< BV >, coal::BVHModel< BV >, coal::HeightField< BV >, coal::BVHModel< BV >, coal::HeightField< BV >, coal::BVHModel< BV >, coal::HeightField< BV >, coal::BVHModel< BV >, coal::HeightField< BV >, coal::BVHModel< BV >, coal::HeightField< BV >, coal::BVHModel< BV >, coal::HeightField< BV >, coal::BVHModel< BV >, coal::HeightField< BV >, coal::BVHModel< BV >, coal::HeightField< BV >, coal::Cone, coal::Capsule, coal::BVHModel< BV >, coal::Ellipsoid, coal::OcTree, coal::Sphere, coal::Box, coal::TriangleP, coal::HeightField< BV >, coal::HeightField< BV >, coal::HeightField< BV >, coal::HeightField< BV >, coal::HeightField< BV >, coal::HeightField< BV >, coal::HeightField< BV >, and coal::HeightField< BV >.
Definition at line 130 of file coal/collision_object.h.
|
inline |
get the node type
Definition at line 249 of file coal/collision_object.h.
|
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.
|
inline |
get the type of the object
Definition at line 246 of file coal/collision_object.h.
|
inline |
Access to the orientation of the BV.
Definition at line 139 of file coal/BV/BV_node.h.
|
inline |
get matrix rotation of the object
Definition at line 287 of file coal/collision_object.h.
|
inline |
get object's transform
Definition at line 290 of file coal/collision_object.h.
|
inline |
get translation of the object
Definition at line 284 of file coal/collision_object.h.
|
inline |
get user data in geometry
Definition at line 136 of file coal/collision_object.h.
|
inline |
get user data in object
Definition at line 278 of file coal/collision_object.h.
|
inlineprotected |
Definition at line 340 of file coal/collision_object.h.
|
privatepure virtual |
equal operator with another object of derived type.
Implemented in coal::BVHModelBase, coal::Plane, coal::Halfspace, coal::ConvexBase, coal::Cylinder, coal::Cone, coal::HeightField< BV >, coal::Capsule, coal::BVHModel< BV >, coal::Ellipsoid, coal::Sphere, coal::OcTree, coal::Box, and coal::TriangleP.
|
inline |
whether the object is completely free
Definition at line 145 of file coal/collision_object.h.
|
inline |
whether the object is in local coordinate
Definition at line 305 of file coal/collision_object.h.
|
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.
|
inlineprivatevirtual |
not equal operator with another object of derived type.
Definition at line 204 of file coal/collision_object.h.
|
inline |
whether the object is completely occupied
Definition at line 142 of file coal/collision_object.h.
bool coal::CollisionGeometry::isUncertain | ( | ) | const |
whether the object has some uncertainty
Definition at line 41 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 95 of file coal/BV/BV_node.h.
|
inline |
Difference operator.
Definition at line 118 of file coal/BV/BV_node.h.
|
inline |
Difference operator.
Definition at line 83 of file coal/BV/BV_node.h.
|
inline |
Difference operator.
Definition at line 122 of file coal/collision_object.h.
|
inline |
Definition at line 239 of file coal/collision_object.h.
|
inline |
Equality operator.
Definition at line 113 of file coal/BV/BV_node.h.
|
inline |
Equality operator.
Definition at line 76 of file coal/BV/BV_node.h.
|
inline |
Equality operator.
Definition at line 112 of file coal/collision_object.h.
|
inline |
Definition at line 235 of file coal/collision_object.h.
|
inline |
Check whether two BVNode collide.
Definition at line 121 of file coal/BV/BV_node.h.
|
inline |
Check whether two BVNode collide.
Definition at line 123 of file coal/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 91 of file coal/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 99 of file coal/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 330 of file coal/collision_object.h.
|
inline |
set the object in local coordinate
Definition at line 308 of file coal/collision_object.h.
|
inline |
set object's rotation matrix
Definition at line 293 of file coal/collision_object.h.
set object's transform
Definition at line 299 of file coal/collision_object.h.
|
inline |
set object's transform
Definition at line 302 of file coal/collision_object.h.
|
inline |
set object's translation
Definition at line 296 of file coal/collision_object.h.
|
inline |
set user data in geometry
Definition at line 139 of file coal/collision_object.h.
|
inline |
set user data in object
Definition at line 281 of file coal/collision_object.h.
|
inlinevirtual |
Definition at line 106 of file coal/collision_object.h.
|
inline |
Definition at line 243 of file coal/collision_object.h.
|
mutableprotected |
AABB in global coordinate.
Definition at line 352 of file coal/collision_object.h.
Vec3s coal::CollisionGeometry::aabb_center |
AABB center in local coordinate.
Definition at line 151 of file coal/collision_object.h.
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.
CoalScalar coal::CollisionGeometry::aabb_radius |
AABB radius.
Definition at line 154 of file coal/collision_object.h.
BV coal::BVNode< BV >::bv |
bounding volume storing the geometry
Definition at line 110 of file coal/BV/BV_node.h.
|
protected |
Definition at line 347 of file coal/collision_object.h.
CoalScalar coal::CollisionGeometry::cost_density |
collision cost for unit volume
Definition at line 164 of file coal/collision_object.h.
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.
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.
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.
|
protected |
Definition at line 349 of file coal/collision_object.h.
CoalScalar coal::CollisionGeometry::threshold_free |
threshold for free (<= is free)
Definition at line 170 of file coal/collision_object.h.
CoalScalar coal::CollisionGeometry::threshold_occupied |
threshold for occupied ( >= is occupied)
Definition at line 167 of file coal/collision_object.h.
void* coal::CollisionGeometry::user_data |
pointer to user defined data specific to this object
Definition at line 161 of file coal/collision_object.h.
|
protected |
pointer to user defined data specific to this object
Definition at line 355 of file coal/collision_object.h.