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...
#include <BVH_model.h>
Public Types | |
using | bv_node_vector_t = std::vector< BVNode< BV >, Eigen::aligned_allocator< BVNode< BV > >> |
Public Member Functions | |
BVHModel () | |
Default constructor to build an empty BVH. More... | |
BVHModel (const BVHModel &other) | |
Copy constructor from another BVH. More... | |
virtual BVHModel< BV > * | clone () const |
Clone *this into a new BVHModel. More... | |
BVNode< BV > & | getBV (unsigned int i) |
Access the bv giving the its index. More... | |
const BVNode< BV > & | getBV (unsigned int i) const |
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some flexibility here. More... | |
NODE_TYPE | getNodeType () const |
Get the BV type: default is unknown. More... | |
NODE_TYPE | getNodeType () const |
Specialization of getNodeType() for BVHModel with different BV types. More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
NODE_TYPE | getNodeType () const |
get the node type More... | |
unsigned int | getNumBVs () const |
Get the number of bv in the BVH. More... | |
void | makeParentRelative () |
This is a special acceleration: BVH_model default stores the BV's transform in world coordinate. However, we can also store each BV's transform related to its parent BV node. When traversing the BVH, this can save one matrix transformation. More... | |
int | memUsage (const bool msg) const |
Check the number of memory used. More... | |
~BVHModel () | |
deconstruction, delete mesh data related. More... | |
Public Member Functions inherited from coal::BVHModelBase | |
int | addSubModel (const std::vector< Vec3s > &ps) |
Add a set of points in the new BVH model. More... | |
int | addSubModel (const std::vector< Vec3s > &ps, const std::vector< Triangle > &ts) |
Add a set of triangles in the new BVH model. More... | |
int | addTriangle (const Vec3s &p1, const Vec3s &p2, const Vec3s &p3) |
Add one triangle in the new BVH model. More... | |
int | addTriangles (const Matrixx3i &triangles) |
Add triangles in the new BVH model. More... | |
int | addVertex (const Vec3s &p) |
Add one point in the new BVH model. More... | |
int | addVertices (const MatrixX3s &points) |
Add points in the new BVH model. More... | |
int | beginModel (unsigned int num_tris=0, unsigned int num_vertices=0) |
Begin a new BVH model. More... | |
int | beginReplaceModel () |
Replace the geometry information of current frame (i.e. should have the same mesh topology with the previous frame) More... | |
int | beginUpdateModel () |
Replace the geometry information of current frame (i.e. should have the same mesh topology with the previous frame). The current frame will be saved as the previous frame in prev_vertices. More... | |
bool | buildConvexHull (bool keepTriangle, const char *qhullCommand=NULL) |
Build a convex hull and store it in attribute convex. More... | |
void | buildConvexRepresentation (bool share_memory) |
Build this Convex<Triangle> representation of this model. The result is stored in attribute convex. More... | |
BVHModelBase () | |
Constructing an empty BVH. More... | |
BVHModelBase (const BVHModelBase &other) | |
copy from another BVH More... | |
Vec3s | computeCOM () const |
compute center of mass More... | |
void | computeLocalAABB () |
Compute the AABB for the BVH, used for broad-phase collision. More... | |
Matrix3s | computeMomentofInertia () const |
compute the inertia matrix, related to the origin More... | |
CoalScalar | computeVolume () const |
compute the volume More... | |
int | endModel () |
End BVH model construction, will build the bounding volume hierarchy. More... | |
int | endReplaceModel (bool refit=true, bool bottomup=true) |
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy. More... | |
int | endUpdateModel (bool refit=true, bool bottomup=true) |
End BVH model update, will also refit or rebuild the bounding volume hierarchy. More... | |
BVHModelType | getModelType () const |
Model type described by the instance. More... | |
OBJECT_TYPE | getObjectType () const |
Get the object type: it is a BVH. More... | |
int | replaceSubModel (const std::vector< Vec3s > &ps) |
Replace a set of points in the old BVH model. More... | |
int | replaceTriangle (const Vec3s &p1, const Vec3s &p2, const Vec3s &p3) |
Replace one triangle in the old BVH model. More... | |
int | replaceVertex (const Vec3s &p) |
Replace one point in the old BVH model. More... | |
int | updateSubModel (const std::vector< Vec3s > &ps) |
Update a set of points in the old BVH model. More... | |
int | updateTriangle (const Vec3s &p1, const Vec3s &p2, const Vec3s &p3) |
Update one triangle in the old BVH model. More... | |
int | updateVertex (const Vec3s &p) |
Update one point in the old BVH model. More... | |
virtual | ~BVHModelBase () |
deconstruction, delete mesh data related. More... | |
Public Member Functions inherited from coal::CollisionGeometry | |
CollisionGeometry () | |
CollisionGeometry (const CollisionGeometry &other)=default | |
Copy constructor. More... | |
virtual Matrix3s | computeMomentofInertiaRelatedToCOM () const |
compute the inertia matrix, related to the com More... | |
void * | getUserData () const |
get user data in geometry More... | |
bool | isFree () const |
whether the object is completely free More... | |
bool | isOccupied () const |
whether the object is completely occupied More... | |
bool | isUncertain () const |
whether the object has some uncertainty More... | |
bool | operator!= (const CollisionGeometry &other) const |
Difference operator. More... | |
bool | operator== (const CollisionGeometry &other) const |
Equality operator. More... | |
void | setUserData (void *data) |
set user data in geometry More... | |
virtual | ~CollisionGeometry () |
Public Attributes | |
shared_ptr< BVFitter< BV > > | bv_fitter |
Fitting rule to fit a BV node to a set of geometry primitives. More... | |
shared_ptr< BVSplitter< BV > > | bv_splitter |
Split rule to split one BV node into two children. More... | |
Public Attributes inherited from coal::BVHModelBase | |
BVHBuildState | build_state |
The state of BVH building process. More... | |
shared_ptr< ConvexBase > | convex |
Convex<Triangle> representation of this object. More... | |
unsigned int | num_tris |
Number of triangles. More... | |
unsigned int | num_vertices |
Number of points. More... | |
std::shared_ptr< std::vector< Vec3s > > | prev_vertices |
Geometry point data in previous frame. More... | |
std::shared_ptr< std::vector< Triangle > > | tri_indices |
Geometry triangle index data, will be NULL for point clouds. More... | |
std::shared_ptr< std::vector< Vec3s > > | vertices |
Geometry point data. More... | |
Public Attributes inherited from coal::CollisionGeometry | |
Vec3s | aabb_center |
AABB center in local coordinate. More... | |
AABB | aabb_local |
AABB in local coordinate, used for tight AABB when only translation transform. More... | |
CoalScalar | aabb_radius |
AABB radius. More... | |
CoalScalar | cost_density |
collision cost for unit volume More... | |
CoalScalar | threshold_free |
threshold for free (<= is free) More... | |
CoalScalar | threshold_occupied |
threshold for occupied ( >= is occupied) More... | |
void * | user_data |
pointer to user defined data specific to this object More... | |
Protected Member Functions | |
bool | allocateBVs () |
int | buildTree () |
Build the bounding volume hierarchy. More... | |
void | deleteBVs () |
void | makeParentRelativeRecurse (int bv_id, Matrix3s &parent_axes, const Vec3s &parent_c) |
void | makeParentRelativeRecurse (int bv_id, Matrix3s &parent_axes, const Vec3s &parent_c) |
void | makeParentRelativeRecurse (int bv_id, Matrix3s &parent_axes, const Vec3s &parent_c) |
void | makeParentRelativeRecurse (int bv_id, Matrix3s &parent_axes, const Vec3s &parent_c) |
void | makeParentRelativeRecurse (int bv_id, Matrix3s &parent_axes, const Vec3s &parent_c) |
void | makeParentRelativeRecurse (int bv_id, Matrix3s &parent_axes, const Vec3s &parent_c) |
void | makeParentRelativeRecurse (int bv_id, Matrix3s &parent_axes, const Vec3s &parent_c) |
int | recursiveBuildTree (int bv_id, unsigned int first_primitive, unsigned int num_primitives) |
Recursive kernel for hierarchy construction. More... | |
int | recursiveRefitTree_bottomup (int bv_id) |
Recursive kernel for bottomup refitting. More... | |
int | refitTree (bool bottomup) |
Refit the bounding volume hierarchy. More... | |
int | refitTree_bottomup () |
Refit the bounding volume hierarchy in a bottom-up way (fast but less compact) More... | |
int | refitTree_topdown () |
Refit the bounding volume hierarchy in a top-down way (slow but more compact) More... | |
Protected Attributes | |
std::shared_ptr< bv_node_vector_t > | bvs |
Bounding volume hierarchy. More... | |
unsigned int | num_bvs |
Number of BV nodes in bounding volume hierarchy. More... | |
unsigned int | num_bvs_allocated |
std::shared_ptr< std::vector< unsigned int > > | primitive_indices |
Protected Attributes inherited from coal::BVHModelBase | |
unsigned int | num_tris_allocated |
unsigned int | num_vertex_updated |
unsigned int | num_vertices_allocated |
Private Types | |
typedef BVHModelBase | Base |
Private Member Functions | |
virtual bool | isEqual (const CollisionGeometry &_other) const |
for ccd vertex update More... | |
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh)
BV | one of the bounding volume class in Bounding volumes. |
Definition at line 314 of file coal/BVH/BVH_model.h.
|
private |
Definition at line 315 of file coal/BVH/BVH_model.h.
using coal::BVHModel< BV >::bv_node_vector_t = std::vector<BVNode<BV>, Eigen::aligned_allocator<BVNode<BV> >> |
Definition at line 319 of file coal/BVH/BVH_model.h.
coal::BVHModel< BV >::BVHModel |
Default constructor to build an empty BVH.
Constructing an empty BVH.
Definition at line 803 of file BVH_model.cpp.
coal::BVHModel< BV >::BVHModel | ( | const BVHModel< BV > & | other | ) |
Copy constructor from another BVH.
[in] | other | BVHModel to copy. |
Definition at line 162 of file BVH_model.cpp.
|
inline |
deconstruction, delete mesh data related.
Definition at line 340 of file coal/BVH/BVH_model.h.
|
protectedvirtual |
Implements coal::BVHModelBase.
Definition at line 818 of file BVH_model.cpp.
|
protectedvirtual |
Build the bounding volume hierarchy.
Implements coal::BVHModelBase.
Definition at line 858 of file BVH_model.cpp.
|
inlinevirtual |
Clone *this into a new BVHModel.
Implements coal::CollisionGeometry.
Definition at line 337 of file coal/BVH/BVH_model.h.
|
protectedvirtual |
Implements coal::BVHModelBase.
Definition at line 811 of file BVH_model.cpp.
|
inline |
Access the bv giving the its index.
Definition at line 352 of file coal/BVH/BVH_model.h.
|
inline |
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some flexibility here.
Access the bv giving the its index
Definition at line 346 of file coal/BVH/BVH_model.h.
|
inlinevirtual |
Get the BV type: default is unknown.
Reimplemented from coal::CollisionGeometry.
Definition at line 361 of file coal/BVH/BVH_model.h.
|
virtual |
Specialization of getNodeType() for BVHModel with different BV types.
Reimplemented from coal::CollisionGeometry.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
Definition at line 1131 of file BVH_model.cpp.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
Definition at line 1136 of file BVH_model.cpp.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
Definition at line 1141 of file BVH_model.cpp.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
Definition at line 1146 of file BVH_model.cpp.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
Definition at line 1151 of file BVH_model.cpp.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
Definition at line 1156 of file BVH_model.cpp.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
Definition at line 1161 of file BVH_model.cpp.
|
virtual |
get the node type
Reimplemented from coal::CollisionGeometry.
Definition at line 1166 of file BVH_model.cpp.
|
inline |
Get the number of bv in the BVH.
Definition at line 358 of file coal/BVH/BVH_model.h.
|
inlineprivatevirtual |
for ccd vertex update
Comparison operators
Reimplemented from coal::BVHModelBase.
Definition at line 430 of file coal/BVH/BVH_model.h.
|
inlinevirtual |
This is a special acceleration: BVH_model default stores the BV's transform in world coordinate. However, we can also store each BV's transform related to its parent BV node. When traversing the BVH, this can save one matrix transformation.
Implements coal::BVHModelBase.
Definition at line 370 of file coal/BVH/BVH_model.h.
|
inlineprotected |
@ recursively compute each bv's transform related to its parent. For default BV, only the translation works. For oriented BV (OBB, RSS, OBBRSS), special implementation is provided.
Definition at line 412 of file coal/BVH/BVH_model.h.
|
protected |
|
protected |
|
protected |
|
protected |
Definition at line 1065 of file BVH_model.cpp.
|
protected |
Definition at line 1086 of file BVH_model.cpp.
|
protected |
Definition at line 1107 of file BVH_model.cpp.
|
virtual |
Check the number of memory used.
Implements coal::BVHModelBase.
Definition at line 840 of file BVH_model.cpp.
|
protected |
Recursive kernel for hierarchy construction.
Definition at line 892 of file BVH_model.cpp.
|
protected |
Recursive kernel for bottomup refitting.
Definition at line 983 of file BVH_model.cpp.
|
protectedvirtual |
Refit the bounding volume hierarchy.
Implements coal::BVHModelBase.
Definition at line 962 of file BVH_model.cpp.
|
protected |
Refit the bounding volume hierarchy in a bottom-up way (fast but less compact)
Definition at line 970 of file BVH_model.cpp.
|
protected |
Refit the bounding volume hierarchy in a top-down way (slow but more compact)
Definition at line 1046 of file BVH_model.cpp.
shared_ptr<BVFitter<BV> > coal::BVHModel< BV >::bv_fitter |
Fitting rule to fit a BV node to a set of geometry primitives.
Definition at line 325 of file coal/BVH/BVH_model.h.
shared_ptr<BVSplitter<BV> > coal::BVHModel< BV >::bv_splitter |
Split rule to split one BV node into two children.
Definition at line 322 of file coal/BVH/BVH_model.h.
|
protected |
Bounding volume hierarchy.
Definition at line 383 of file coal/BVH/BVH_model.h.
|
protected |
Number of BV nodes in bounding volume hierarchy.
Definition at line 386 of file coal/BVH/BVH_model.h.
|
protected |
Definition at line 379 of file coal/BVH/BVH_model.h.
|
protected |
Definition at line 380 of file coal/BVH/BVH_model.h.