Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | List of all members
hpp::fcl::BVHModel< BV > Class Template Reference

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>

Inheritance diagram for hpp::fcl::BVHModel< BV >:
Inheritance graph
[legend]

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...
 
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...
 
BVNode< BV > & getBV (unsigned int i)
 Access the bv giving the its index. More...
 
NODE_TYPE getNodeType () const
 Get the BV type: default is unknown. More...
 
template<>
NODE_TYPE getNodeType () const
 Specialization of getNodeType() for BVHModel with different BV types. More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
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 hpp::fcl::BVHModelBase
int addSubModel (const std::vector< Vec3f > &ps, const std::vector< Triangle > &ts)
 Add a set of triangles in the new BVH model. More...
 
int addSubModel (const std::vector< Vec3f > &ps)
 Add a set of points 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...
 
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
 CollisionGeometry ()
 
 CollisionGeometry (const CollisionGeometry &other)=default
 Copy constructor. More...
 
virtual Matrix3f 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 hpp::fcl::BVHModelBase
BVHBuildState build_state
 The state of BVH building process. More...
 
shared_ptr< ConvexBaseconvex
 Convex<Triangle> representation of this object. More...
 
unsigned int num_tris
 Number of triangles. More...
 
unsigned int num_vertices
 Number of points. More...
 
Vec3fprev_vertices
 Geometry point data in previous frame. More...
 
Triangletri_indices
 Geometry triangle index data, will be NULL for point clouds. More...
 
Vec3fvertices
 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

bool allocateBVs ()
 
int buildTree ()
 Build the bounding volume hierarchy. More...
 
void deleteBVs ()
 
void makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c)
 
template<>
void makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c)
 
template<>
void makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c)
 
template<>
void makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c)
 
template<>
void makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c)
 
template<>
void makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c)
 
template<>
void makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &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

BVNode< BV > * bvs
 Bounding volume hierarchy. More...
 
unsigned int num_bvs
 Number of BV nodes in bounding volume hierarchy. More...
 
unsigned int num_bvs_allocated
 
unsigned int * primitive_indices
 
- Protected Attributes inherited from hpp::fcl::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...
 

Detailed Description

template<typename BV>
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)

Template Parameters
BVone of the bounding volume class in Bounding volumes.

Definition at line 273 of file BVH/BVH_model.h.

Member Typedef Documentation

◆ Base

template<typename BV>
typedef BVHModelBase hpp::fcl::BVHModel< BV >::Base
private

Definition at line 274 of file BVH/BVH_model.h.

Constructor & Destructor Documentation

◆ BVHModel() [1/2]

template<typename BV >
hpp::fcl::BVHModel< BV >::BVHModel ( )

Default constructor to build an empty BVH.

Constructing an empty BVH.

Definition at line 757 of file BVH_model.cpp.

◆ BVHModel() [2/2]

template<typename BV >
hpp::fcl::BVHModel< BV >::BVHModel ( const BVHModel< BV > &  other)

Copy constructor from another BVH.

Parameters
[in]otherBVHModel to copy.

Definition at line 140 of file BVH_model.cpp.

◆ ~BVHModel()

template<typename BV>
hpp::fcl::BVHModel< BV >::~BVHModel ( )
inline

deconstruction, delete mesh data related.

Definition at line 296 of file BVH/BVH_model.h.

Member Function Documentation

◆ allocateBVs()

template<typename BV >
bool hpp::fcl::BVHModel< BV >::allocateBVs ( )
protectedvirtual

Implements hpp::fcl::BVHModelBase.

Definition at line 776 of file BVH_model.cpp.

◆ buildTree()

template<typename BV >
int hpp::fcl::BVHModel< BV >::buildTree ( )
protectedvirtual

Build the bounding volume hierarchy.

Implements hpp::fcl::BVHModelBase.

Definition at line 815 of file BVH_model.cpp.

◆ clone()

template<typename BV>
virtual BVHModel<BV>* hpp::fcl::BVHModel< BV >::clone ( ) const
inlinevirtual

Clone *this into a new BVHModel.

Implements hpp::fcl::CollisionGeometry.

Definition at line 293 of file BVH/BVH_model.h.

◆ deleteBVs()

template<typename BV >
void hpp::fcl::BVHModel< BV >::deleteBVs ( )
protectedvirtual

Implements hpp::fcl::BVHModelBase.

Definition at line 767 of file BVH_model.cpp.

◆ getBV() [1/2]

template<typename BV>
const BVNode<BV>& hpp::fcl::BVHModel< BV >::getBV ( unsigned int  i) const
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 305 of file BVH/BVH_model.h.

◆ getBV() [2/2]

template<typename BV>
BVNode<BV>& hpp::fcl::BVHModel< BV >::getBV ( unsigned int  i)
inline

Access the bv giving the its index.

Definition at line 311 of file BVH/BVH_model.h.

◆ getNodeType() [1/17]

template<typename BV>
NODE_TYPE hpp::fcl::BVHModel< BV >::getNodeType ( ) const
inlinevirtual

Get the BV type: default is unknown.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 320 of file BVH/BVH_model.h.

◆ getNodeType() [2/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< AABB >::getNodeType ( ) const
virtual

Specialization of getNodeType() for BVHModel with different BV types.

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [3/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< OBB >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [4/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< RSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [5/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< kIOS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [6/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< OBBRSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [7/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< KDOP< 16 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [8/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< KDOP< 18 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [9/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< KDOP< 24 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [10/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< AABB >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 1066 of file BVH_model.cpp.

◆ getNodeType() [11/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< OBB >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 1071 of file BVH_model.cpp.

◆ getNodeType() [12/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< RSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 1076 of file BVH_model.cpp.

◆ getNodeType() [13/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< kIOS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 1081 of file BVH_model.cpp.

◆ getNodeType() [14/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< OBBRSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 1086 of file BVH_model.cpp.

◆ getNodeType() [15/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< KDOP< 16 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 1091 of file BVH_model.cpp.

◆ getNodeType() [16/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< KDOP< 18 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 1096 of file BVH_model.cpp.

◆ getNodeType() [17/17]

template<>
NODE_TYPE hpp::fcl::BVHModel< KDOP< 24 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 1101 of file BVH_model.cpp.

◆ getNumBVs()

template<typename BV>
unsigned int hpp::fcl::BVHModel< BV >::getNumBVs ( ) const
inline

Get the number of bv in the BVH.

Definition at line 317 of file BVH/BVH_model.h.

◆ isEqual()

template<typename BV>
virtual bool hpp::fcl::BVHModel< BV >::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

for ccd vertex update

Comparison operators

Reimplemented from hpp::fcl::BVHModelBase.

Definition at line 385 of file BVH/BVH_model.h.

◆ makeParentRelative()

template<typename BV>
void hpp::fcl::BVHModel< BV >::makeParentRelative ( )
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 hpp::fcl::BVHModelBase.

Definition at line 329 of file BVH/BVH_model.h.

◆ makeParentRelativeRecurse() [1/7]

template<typename BV>
void hpp::fcl::BVHModel< BV >::makeParentRelativeRecurse ( int  bv_id,
Matrix3f parent_axes,
const Vec3f parent_c 
)
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 371 of file BVH/BVH_model.h.

◆ makeParentRelativeRecurse() [2/7]

template<>
void hpp::fcl::BVHModel< OBB >::makeParentRelativeRecurse ( int  bv_id,
Matrix3f parent_axes,
const Vec3f parent_c 
)
protected

◆ makeParentRelativeRecurse() [3/7]

template<>
void hpp::fcl::BVHModel< RSS >::makeParentRelativeRecurse ( int  bv_id,
Matrix3f parent_axes,
const Vec3f parent_c 
)
protected

◆ makeParentRelativeRecurse() [4/7]

template<>
void hpp::fcl::BVHModel< OBBRSS >::makeParentRelativeRecurse ( int  bv_id,
Matrix3f parent_axes,
const Vec3f parent_c 
)
protected

◆ makeParentRelativeRecurse() [5/7]

template<>
void hpp::fcl::BVHModel< OBB >::makeParentRelativeRecurse ( int  bv_id,
Matrix3f parent_axes,
const Vec3f parent_c 
)
protected

Definition at line 1009 of file BVH_model.cpp.

◆ makeParentRelativeRecurse() [6/7]

template<>
void hpp::fcl::BVHModel< RSS >::makeParentRelativeRecurse ( int  bv_id,
Matrix3f parent_axes,
const Vec3f parent_c 
)
protected

Definition at line 1027 of file BVH_model.cpp.

◆ makeParentRelativeRecurse() [7/7]

template<>
void hpp::fcl::BVHModel< OBBRSS >::makeParentRelativeRecurse ( int  bv_id,
Matrix3f parent_axes,
const Vec3f parent_c 
)
protected

Definition at line 1045 of file BVH_model.cpp.

◆ memUsage()

template<typename BV >
int hpp::fcl::BVHModel< BV >::memUsage ( const bool  msg) const
virtual

Check the number of memory used.

Implements hpp::fcl::BVHModelBase.

Definition at line 797 of file BVH_model.cpp.

◆ recursiveBuildTree()

template<typename BV >
int hpp::fcl::BVHModel< BV >::recursiveBuildTree ( int  bv_id,
unsigned int  first_primitive,
unsigned int  num_primitives 
)
protected

Recursive kernel for hierarchy construction.

Definition at line 846 of file BVH_model.cpp.

◆ recursiveRefitTree_bottomup()

template<typename BV >
int hpp::fcl::BVHModel< BV >::recursiveRefitTree_bottomup ( int  bv_id)
protected

Recursive kernel for bottomup refitting.

Definition at line 934 of file BVH_model.cpp.

◆ refitTree()

template<typename BV >
int hpp::fcl::BVHModel< BV >::refitTree ( bool  bottomup)
protectedvirtual

Refit the bounding volume hierarchy.

Implements hpp::fcl::BVHModelBase.

Definition at line 913 of file BVH_model.cpp.

◆ refitTree_bottomup()

template<typename BV >
int hpp::fcl::BVHModel< BV >::refitTree_bottomup ( )
protected

Refit the bounding volume hierarchy in a bottom-up way (fast but less compact)

Definition at line 921 of file BVH_model.cpp.

◆ refitTree_topdown()

template<typename BV >
int hpp::fcl::BVHModel< BV >::refitTree_topdown ( )
protected

Refit the bounding volume hierarchy in a top-down way (slow but more compact)

Definition at line 995 of file BVH_model.cpp.

Member Data Documentation

◆ bv_fitter

template<typename BV>
shared_ptr<BVFitter<BV> > hpp::fcl::BVHModel< BV >::bv_fitter

Fitting rule to fit a BV node to a set of geometry primitives.

Definition at line 281 of file BVH/BVH_model.h.

◆ bv_splitter

template<typename BV>
shared_ptr<BVSplitter<BV> > hpp::fcl::BVHModel< BV >::bv_splitter

Split rule to split one BV node into two children.

Definition at line 278 of file BVH/BVH_model.h.

◆ bvs

template<typename BV>
BVNode<BV>* hpp::fcl::BVHModel< BV >::bvs
protected

Bounding volume hierarchy.

Definition at line 342 of file BVH/BVH_model.h.

◆ num_bvs

template<typename BV>
unsigned int hpp::fcl::BVHModel< BV >::num_bvs
protected

Number of BV nodes in bounding volume hierarchy.

Definition at line 345 of file BVH/BVH_model.h.

◆ num_bvs_allocated

template<typename BV>
unsigned int hpp::fcl::BVHModel< BV >::num_bvs_allocated
protected

Definition at line 338 of file BVH/BVH_model.h.

◆ primitive_indices

template<typename BV>
unsigned int* hpp::fcl::BVHModel< BV >::primitive_indices
protected

Definition at line 339 of file BVH/BVH_model.h.


The documentation for this class was generated from the following files:


hpp-fcl
Author(s):
autogenerated on Fri Jun 2 2023 02:39:03