Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
coal::BVHModelBase Class Referenceabstract

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>

Inheritance diagram for coal::BVHModelBase:
Inheritance graph
[legend]

Public Member Functions

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...
 
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< 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
virtual CollisionGeometryclone () const =0
 Clone *this into a new CollisionGeometry. More...
 
 CollisionGeometry ()
 
 CollisionGeometry (const CollisionGeometry &other)=default
 Copy constructor. More...
 
virtual Matrix3s 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< ConvexBaseconvex
 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

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
 

Detailed Description

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 65 of file coal/BVH/BVH_model.h.

Constructor & Destructor Documentation

◆ BVHModelBase() [1/2]

coal::BVHModelBase::BVHModelBase ( )

Constructing an empty BVH.

Definition at line 53 of file BVH_model.cpp.

◆ BVHModelBase() [2/2]

coal::BVHModelBase::BVHModelBase ( const BVHModelBase other)

copy from another BVH

Definition at line 61 of file BVH_model.cpp.

◆ ~BVHModelBase()

virtual coal::BVHModelBase::~BVHModelBase ( )
inlinevirtual

deconstruction, delete mesh data related.

Definition at line 105 of file coal/BVH/BVH_model.h.

Member Function Documentation

◆ addSubModel() [1/2]

int coal::BVHModelBase::addSubModel ( const std::vector< Vec3s > &  ps)

Add a set of points in the new BVH model.

Definition at line 401 of file BVH_model.cpp.

◆ addSubModel() [2/2]

int coal::BVHModelBase::addSubModel ( const std::vector< Vec3s > &  ps,
const std::vector< Triangle > &  ts 
)

Add a set of triangles in the new BVH model.

Definition at line 439 of file BVH_model.cpp.

◆ addTriangle()

int coal::BVHModelBase::addTriangle ( const Vec3s p1,
const Vec3s p2,
const Vec3s p3 
)

Add one triangle in the new BVH model.

Definition at line 340 of file BVH_model.cpp.

◆ addTriangles()

int coal::BVHModelBase::addTriangles ( const Matrixx3i triangles)

Add triangles in the new BVH model.

Definition at line 267 of file BVH_model.cpp.

◆ addVertex()

int coal::BVHModelBase::addVertex ( const Vec3s p)

Add one point in the new BVH model.

Definition at line 235 of file BVH_model.cpp.

◆ addVertices()

int coal::BVHModelBase::addVertices ( const MatrixX3s points)

Add points in the new BVH model.

Definition at line 307 of file BVH_model.cpp.

◆ allocateBVs()

virtual bool coal::BVHModelBase::allocateBVs ( )
protectedpure virtual

Implemented in coal::BVHModel< BV >.

◆ beginModel()

int coal::BVHModelBase::beginModel ( unsigned int  num_tris = 0,
unsigned int  num_vertices = 0 
)

Begin a new BVH model.

Definition at line 179 of file BVH_model.cpp.

◆ beginReplaceModel()

int coal::BVHModelBase::beginReplaceModel ( )

Replace the geometry information of current frame (i.e. should have the same mesh topology with the previous frame)

Definition at line 577 of file BVH_model.cpp.

◆ beginUpdateModel()

int coal::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 673 of file BVH_model.cpp.

◆ buildConvexHull()

bool coal::BVHModelBase::buildConvexHull ( bool  keepTriangle,
const char *  qhullCommand = NULL 
)

Build a convex hull and store it in attribute convex.

Parameters
keepTrianglewhether the convex should be triangulated.
qhullCommandsee ConvexBase::convexHull.
Returns
true if this object is convex, hence the convex hull represents the same object.
See also
ConvexBase::convexHull
Warning
At the moment, the return value only checks whether there are as many points in the convex hull as in the original object. This is neither necessary (duplicated vertices get merged) nor sufficient (think of a U with 4 vertices and 3 edges).

Definition at line 154 of file BVH_model.cpp.

◆ buildConvexRepresentation()

void coal::BVHModelBase::buildConvexRepresentation ( bool  share_memory)

Build this Convex<Triangle> representation of this model. The result is stored in attribute convex.

Note
this only takes the points of this model. It does not check that the object is convex. It does not compute a convex hull.

Definition at line 128 of file BVH_model.cpp.

◆ buildTree()

virtual int coal::BVHModelBase::buildTree ( )
protectedpure virtual

Build the bounding volume hierarchy.

Implemented in coal::BVHModel< BV >.

◆ computeCOM()

Vec3s coal::BVHModelBase::computeCOM ( ) const
inlinevirtual

compute center of mass

Reimplemented from coal::CollisionGeometry.

Definition at line 201 of file coal/BVH/BVH_model.h.

◆ computeLocalAABB()

void coal::BVHModelBase::computeLocalAABB ( )
virtual

Compute the AABB for the BVH, used for broad-phase collision.

Implements coal::CollisionGeometry.

Definition at line 781 of file BVH_model.cpp.

◆ computeMomentofInertia()

Matrix3s coal::BVHModelBase::computeMomentofInertia ( ) const
inlinevirtual

compute the inertia matrix, related to the origin

Reimplemented from coal::CollisionGeometry.

Definition at line 257 of file coal/BVH/BVH_model.h.

◆ computeVolume()

CoalScalar coal::BVHModelBase::computeVolume ( ) const
inlinevirtual

compute the volume

Reimplemented from coal::CollisionGeometry.

Definition at line 231 of file coal/BVH/BVH_model.h.

◆ deleteBVs()

virtual void coal::BVHModelBase::deleteBVs ( )
protectedpure virtual

Implemented in coal::BVHModel< BV >.

◆ endModel()

int coal::BVHModelBase::endModel ( )

End BVH model construction, will build the bounding volume hierarchy.

Definition at line 507 of file BVH_model.cpp.

◆ endReplaceModel()

int coal::BVHModelBase::endReplaceModel ( bool  refit = true,
bool  bottomup = true 
)

End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.

Definition at line 645 of file BVH_model.cpp.

◆ endUpdateModel()

int coal::BVHModelBase::endUpdateModel ( bool  refit = true,
bool  bottomup = true 
)

End BVH model update, will also refit or rebuild the bounding volume hierarchy.

Definition at line 749 of file BVH_model.cpp.

◆ getModelType()

BVHModelType coal::BVHModelBase::getModelType ( ) const
inline

Model type described by the instance.

Definition at line 89 of file coal/BVH/BVH_model.h.

◆ getObjectType()

OBJECT_TYPE coal::BVHModelBase::getObjectType ( ) const
inlinevirtual

Get the object type: it is a BVH.

Reimplemented from coal::CollisionGeometry.

Definition at line 108 of file coal/BVH/BVH_model.h.

◆ isEqual()

bool coal::BVHModelBase::isEqual ( const CollisionGeometry other) const
protectedvirtual

for ccd vertex update

Comparison operators

Implements coal::CollisionGeometry.

Reimplemented in coal::BVHModel< BV >.

Definition at line 84 of file BVH_model.cpp.

◆ makeParentRelative()

virtual void coal::BVHModelBase::makeParentRelative ( )
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 coal::BVHModel< BV >.

◆ memUsage()

virtual int coal::BVHModelBase::memUsage ( const bool  msg = false) const
pure virtual

Implemented in coal::BVHModel< BV >.

◆ refitTree()

virtual int coal::BVHModelBase::refitTree ( bool  bottomup)
protectedpure virtual

Refit the bounding volume hierarchy.

Implemented in coal::BVHModel< BV >.

◆ replaceSubModel()

int coal::BVHModelBase::replaceSubModel ( const std::vector< Vec3s > &  ps)

Replace a set of points in the old BVH model.

Definition at line 628 of file BVH_model.cpp.

◆ replaceTriangle()

int coal::BVHModelBase::replaceTriangle ( const Vec3s p1,
const Vec3s p2,
const Vec3s p3 
)

Replace one triangle in the old BVH model.

Definition at line 609 of file BVH_model.cpp.

◆ replaceVertex()

int coal::BVHModelBase::replaceVertex ( const Vec3s p)

Replace one point in the old BVH model.

Definition at line 594 of file BVH_model.cpp.

◆ updateSubModel()

int coal::BVHModelBase::updateSubModel ( const std::vector< Vec3s > &  ps)

Update a set of points in the old BVH model.

Definition at line 732 of file BVH_model.cpp.

◆ updateTriangle()

int coal::BVHModelBase::updateTriangle ( const Vec3s p1,
const Vec3s p2,
const Vec3s p3 
)

Update one triangle in the old BVH model.

Definition at line 713 of file BVH_model.cpp.

◆ updateVertex()

int coal::BVHModelBase::updateVertex ( const Vec3s p)

Update one point in the old BVH model.

Definition at line 698 of file BVH_model.cpp.

Member Data Documentation

◆ build_state

BVHBuildState coal::BVHModelBase::build_state

The state of BVH building process.

Definition at line 83 of file coal/BVH/BVH_model.h.

◆ convex

shared_ptr<ConvexBase> coal::BVHModelBase::convex

Convex<Triangle> representation of this object.

Definition at line 86 of file coal/BVH/BVH_model.h.

◆ num_tris

unsigned int coal::BVHModelBase::num_tris

Number of triangles.

Definition at line 77 of file coal/BVH/BVH_model.h.

◆ num_tris_allocated

unsigned int coal::BVHModelBase::num_tris_allocated
protected

Definition at line 301 of file coal/BVH/BVH_model.h.

◆ num_vertex_updated

unsigned int coal::BVHModelBase::num_vertex_updated
protected

Definition at line 303 of file coal/BVH/BVH_model.h.

◆ num_vertices

unsigned int coal::BVHModelBase::num_vertices

Number of points.

Definition at line 80 of file coal/BVH/BVH_model.h.

◆ num_vertices_allocated

unsigned int coal::BVHModelBase::num_vertices_allocated
protected

Definition at line 302 of file coal/BVH/BVH_model.h.

◆ prev_vertices

std::shared_ptr<std::vector<Vec3s> > coal::BVHModelBase::prev_vertices

Geometry point data in previous frame.

Definition at line 74 of file coal/BVH/BVH_model.h.

◆ tri_indices

std::shared_ptr<std::vector<Triangle> > coal::BVHModelBase::tri_indices

Geometry triangle index data, will be NULL for point clouds.

Definition at line 71 of file coal/BVH/BVH_model.h.

◆ vertices

std::shared_ptr<std::vector<Vec3s> > coal::BVHModelBase::vertices

Geometry point data.

Definition at line 68 of file coal/BVH/BVH_model.h.


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


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:45:00