Class BVHModelBase

Inheritance Relationships

Base Type

Derived Types

Class Documentation

class BVHModelBase : public hpp::fcl::CollisionGeometry

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)

Subclassed by boost::serialization::internal::BVHModelBaseAccessor, hpp::fcl::BVHModel< BV >

Public Functions

inline BVHModelType getModelType() const

Model type described by the instance.

BVHModelBase()

Constructing an empty BVH.

BVHModelBase(const BVHModelBase &other)

copy from another BVH

inline virtual ~BVHModelBase()

deconstruction, delete mesh data related.

inline virtual OBJECT_TYPE getObjectType() const

Get the object type: it is a BVH.

virtual void computeLocalAABB()

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

int beginModel(unsigned int num_tris = 0, unsigned int num_vertices = 0)

Begin a new BVH model.

int addVertex(const Vec3f &p)

Add one point in the new BVH model.

int addVertices(const Matrixx3f &points)

Add points in the new BVH model.

int addTriangles(const Matrixx3i &triangles)

Add triangles in the new BVH model.

int addTriangle(const Vec3f &p1, const Vec3f &p2, const Vec3f &p3)

Add one triangle in the new BVH model.

int addSubModel(const std::vector<Vec3f> &ps, const std::vector<Triangle> &ts)

Add a set of triangles in the new BVH model.

int addSubModel(const std::vector<Vec3f> &ps)

Add a set of points in the new BVH model.

int endModel()

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

int beginReplaceModel()

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

int replaceVertex(const Vec3f &p)

Replace one point in the old BVH model.

int replaceTriangle(const Vec3f &p1, const Vec3f &p2, const Vec3f &p3)

Replace one triangle in the old BVH model.

int replaceSubModel(const std::vector<Vec3f> &ps)

Replace a set of points in the old BVH model.

int endReplaceModel(bool refit = true, bool bottomup = true)

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

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.

int updateVertex(const Vec3f &p)

Update one point in the old BVH model.

int updateTriangle(const Vec3f &p1, const Vec3f &p2, const Vec3f &p3)

Update one triangle in the old BVH model.

int updateSubModel(const std::vector<Vec3f> &ps)

Update a set of points in the old BVH model.

int endUpdateModel(bool refit = true, bool bottomup = true)

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

void 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.

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

Build a convex hull and store it in attribute convex.

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).

Parameters:
Returns:

true if this object is convex, hence the convex hull represents the same object.

virtual int memUsage(const bool msg = false) const = 0
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.

inline virtual Vec3f computeCOM() const

compute center of mass

inline virtual FCL_REAL computeVolume() const

compute the volume

inline virtual Matrix3f computeMomentofInertia() const

compute the inertia matrix, related to the origin

Public Members

Vec3f *vertices

Geometry point data.

Triangle *tri_indices

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

Vec3f *prev_vertices

Geometry point data in previous frame.

unsigned int num_tris

Number of triangles.

unsigned int num_vertices

Number of points.

BVHBuildState build_state

The state of BVH building process.

shared_ptr<ConvexBase> convex

Convex<Triangle> representation of this object.

Protected Functions

virtual void deleteBVs() = 0
virtual bool allocateBVs() = 0
virtual int buildTree() = 0

Build the bounding volume hierarchy.

virtual int refitTree(bool bottomup) = 0

Refit the bounding volume hierarchy.

virtual bool isEqual(const CollisionGeometry &other) const

for ccd vertex update

Comparison operators

Protected Attributes

unsigned int num_tris_allocated
unsigned int num_vertices_allocated
unsigned int num_vertex_updated