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...
#include <BVH_model.h>
Public Member Functions | |
int | addSubModel (const std::vector< Vec3f > &ps) |
Add a set of points in the new BVH model. More... | |
int | addSubModel (const std::vector< Vec3f > &ps, const std::vector< Triangle > &ts) |
Add a set of triangles in the new BVH model. More... | |
int | addTriangle (const Vec3f &p1, const Vec3f &p2, const Vec3f &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 Vec3f &p) |
Add one point in the new BVH model. More... | |
int | addVertices (const Matrixx3f &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... | |
Vec3f | computeCOM () const |
compute center of mass More... | |
void | computeLocalAABB () |
Compute the AABB for the BVH, used for broad-phase collision. More... | |
Matrix3f | computeMomentofInertia () const |
compute the inertia matrix, related to the origin More... | |
FCL_REAL | 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... | |
virtual void | makeParentRelative ()=0 |
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... | |
virtual int | memUsage (const bool msg=false) const =0 |
int | replaceSubModel (const std::vector< Vec3f > &ps) |
Replace a set of points in the old BVH model. More... | |
int | replaceTriangle (const Vec3f &p1, const Vec3f &p2, const Vec3f &p3) |
Replace one triangle in the old BVH model. More... | |
int | replaceVertex (const Vec3f &p) |
Replace one point in the old BVH model. More... | |
int | updateSubModel (const std::vector< Vec3f > &ps) |
Update a set of points in the old BVH model. More... | |
int | updateTriangle (const Vec3f &p1, const Vec3f &p2, const Vec3f &p3) |
Update one triangle in the old BVH model. More... | |
int | updateVertex (const Vec3f &p) |
Update one point in the old BVH model. More... | |
virtual | ~BVHModelBase () |
deconstruction, delete mesh data related. More... | |
Public Member Functions inherited from hpp::fcl::CollisionGeometry | |
virtual CollisionGeometry * | clone () const =0 |
Clone *this into a new CollisionGeometry. More... | |
CollisionGeometry () | |
CollisionGeometry (const CollisionGeometry &other)=default | |
Copy constructor. More... | |
virtual Matrix3f | computeMomentofInertiaRelatedToCOM () const |
compute the inertia matrix, related to the com More... | |
virtual NODE_TYPE | getNodeType () const |
get the node type 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 | |
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... | |
Vec3f * | prev_vertices |
Geometry point data in previous frame. More... | |
Triangle * | tri_indices |
Geometry triangle index data, will be NULL for point clouds. More... | |
Vec3f * | vertices |
Geometry point data. More... | |
Public Attributes inherited from hpp::fcl::CollisionGeometry | |
Vec3f | aabb_center |
AABB center in local coordinate. More... | |
AABB | aabb_local |
AABB in local coordinate, used for tight AABB when only translation transform. More... | |
FCL_REAL | aabb_radius |
AABB radius. More... | |
FCL_REAL | cost_density |
collision cost for unit volume More... | |
FCL_REAL | threshold_free |
threshold for free (<= is free) More... | |
FCL_REAL | threshold_occupied |
threshold for occupied ( >= is occupied) More... | |
void * | user_data |
pointer to user defined data specific to this object More... | |
Protected Member Functions | |
virtual bool | allocateBVs ()=0 |
virtual int | buildTree ()=0 |
Build the bounding volume hierarchy. More... | |
virtual void | deleteBVs ()=0 |
virtual bool | isEqual (const CollisionGeometry &other) const |
for ccd vertex update More... | |
virtual int | refitTree (bool bottomup)=0 |
Refit the bounding volume hierarchy. More... | |
Protected Attributes | |
unsigned int | num_tris_allocated |
unsigned int | num_vertex_updated |
unsigned int | num_vertices_allocated |
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)
Definition at line 63 of file BVH/BVH_model.h.
hpp::fcl::BVHModelBase::BVHModelBase | ( | ) |
Constructing an empty BVH.
Definition at line 53 of file BVH_model.cpp.
hpp::fcl::BVHModelBase::BVHModelBase | ( | const BVHModelBase & | other | ) |
copy from another BVH
Definition at line 64 of file BVH_model.cpp.
|
inlinevirtual |
deconstruction, delete mesh data related.
Definition at line 103 of file BVH/BVH_model.h.
int hpp::fcl::BVHModelBase::addSubModel | ( | const std::vector< Vec3f > & | ps | ) |
Add a set of points in the new BVH model.
Definition at line 374 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::addSubModel | ( | const std::vector< Vec3f > & | ps, |
const std::vector< Triangle > & | ts | ||
) |
Add a set of triangles in the new BVH model.
Definition at line 410 of file BVH_model.cpp.
Add one triangle in the new BVH model.
Definition at line 317 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::addTriangles | ( | const Matrixx3i & | triangles | ) |
Add triangles in the new BVH model.
Definition at line 251 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::addVertex | ( | const Vec3f & | p | ) |
Add one point in the new BVH model.
Definition at line 221 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::addVertices | ( | const Matrixx3f & | points | ) |
Add points in the new BVH model.
Definition at line 287 of file BVH_model.cpp.
|
protectedpure virtual |
Implemented in hpp::fcl::BVHModel< BV >.
int hpp::fcl::BVHModelBase::beginModel | ( | unsigned int | num_tris = 0 , |
unsigned int | num_vertices = 0 |
||
) |
Begin a new BVH model.
Definition at line 170 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::beginReplaceModel | ( | ) |
Replace the geometry information of current frame (i.e. should have the same mesh topology with the previous frame)
Definition at line 533 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::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.
Definition at line 629 of file BVH_model.cpp.
bool hpp::fcl::BVHModelBase::buildConvexHull | ( | bool | keepTriangle, |
const char * | qhullCommand = NULL |
||
) |
Build a convex hull and store it in attribute convex.
keepTriangle | whether the convex should be triangulated. |
qhullCommand | see ConvexBase::convexHull. |
true
if this object is convex, hence the convex hull represents the same object. Definition at line 132 of file BVH_model.cpp.
void hpp::fcl::BVHModelBase::buildConvexRepresentation | ( | bool | share_memory | ) |
Build this Convex<Triangle> representation of this model. The result is stored in attribute convex.
Definition at line 116 of file BVH_model.cpp.
|
protectedpure virtual |
Build the bounding volume hierarchy.
Implemented in hpp::fcl::BVHModel< BV >.
|
inlinevirtual |
compute center of mass
Reimplemented from hpp::fcl::CollisionGeometry.
Definition at line 203 of file BVH/BVH_model.h.
|
virtual |
Compute the AABB for the BVH, used for broad-phase collision.
Implements hpp::fcl::CollisionGeometry.
Definition at line 736 of file BVH_model.cpp.
|
inlinevirtual |
compute the inertia matrix, related to the origin
Reimplemented from hpp::fcl::CollisionGeometry.
Definition at line 230 of file BVH/BVH_model.h.
|
inlinevirtual |
compute the volume
Reimplemented from hpp::fcl::CollisionGeometry.
Definition at line 218 of file BVH/BVH_model.h.
|
protectedpure virtual |
Implemented in hpp::fcl::BVHModel< BV >.
int hpp::fcl::BVHModelBase::endModel | ( | ) |
End BVH model construction, will build the bounding volume hierarchy.
Definition at line 473 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::endReplaceModel | ( | bool | refit = true , |
bool | bottomup = true |
||
) |
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
Definition at line 601 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::endUpdateModel | ( | bool | refit = true , |
bool | bottomup = true |
||
) |
End BVH model update, will also refit or rebuild the bounding volume hierarchy.
Definition at line 704 of file BVH_model.cpp.
|
inline |
Model type described by the instance.
Definition at line 87 of file BVH/BVH_model.h.
|
inlinevirtual |
Get the object type: it is a BVH.
Reimplemented from hpp::fcl::CollisionGeometry.
Definition at line 110 of file BVH/BVH_model.h.
|
protectedvirtual |
for ccd vertex update
Comparison operators
Implements hpp::fcl::CollisionGeometry.
Reimplemented in hpp::fcl::BVHModel< BV >.
Definition at line 91 of file BVH_model.cpp.
|
pure virtual |
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.
Implemented in hpp::fcl::BVHModel< BV >.
|
pure virtual |
Implemented in hpp::fcl::BVHModel< BV >.
|
protectedpure virtual |
Refit the bounding volume hierarchy.
Implemented in hpp::fcl::BVHModel< BV >.
int hpp::fcl::BVHModelBase::replaceSubModel | ( | const std::vector< Vec3f > & | ps | ) |
Replace a set of points in the old BVH model.
Definition at line 585 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::replaceTriangle | ( | const Vec3f & | p1, |
const Vec3f & | p2, | ||
const Vec3f & | p3 | ||
) |
Replace one triangle in the old BVH model.
Definition at line 566 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::replaceVertex | ( | const Vec3f & | p | ) |
Replace one point in the old BVH model.
Definition at line 551 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::updateSubModel | ( | const std::vector< Vec3f > & | ps | ) |
Update a set of points in the old BVH model.
Definition at line 688 of file BVH_model.cpp.
Update one triangle in the old BVH model.
Definition at line 669 of file BVH_model.cpp.
int hpp::fcl::BVHModelBase::updateVertex | ( | const Vec3f & | p | ) |
Update one point in the old BVH model.
Definition at line 654 of file BVH_model.cpp.
BVHBuildState hpp::fcl::BVHModelBase::build_state |
The state of BVH building process.
Definition at line 81 of file BVH/BVH_model.h.
shared_ptr<ConvexBase> hpp::fcl::BVHModelBase::convex |
Convex<Triangle> representation of this object.
Definition at line 84 of file BVH/BVH_model.h.
unsigned int hpp::fcl::BVHModelBase::num_tris |
Number of triangles.
Definition at line 75 of file BVH/BVH_model.h.
|
protected |
Definition at line 260 of file BVH/BVH_model.h.
|
protected |
Definition at line 262 of file BVH/BVH_model.h.
unsigned int hpp::fcl::BVHModelBase::num_vertices |
Number of points.
Definition at line 78 of file BVH/BVH_model.h.
|
protected |
Definition at line 261 of file BVH/BVH_model.h.
Vec3f* hpp::fcl::BVHModelBase::prev_vertices |
Geometry point data in previous frame.
Definition at line 72 of file BVH/BVH_model.h.
Triangle* hpp::fcl::BVHModelBase::tri_indices |
Geometry triangle index data, will be NULL for point clouds.
Definition at line 69 of file BVH/BVH_model.h.
Vec3f* hpp::fcl::BVHModelBase::vertices |
Geometry point data.
Definition at line 66 of file BVH/BVH_model.h.