#include <BVH_model.h>

| Public Types | |
| typedef hpp::fcl::BVHModel< BV > | Base | 
| Additional Inherited Members | |
|  Public Member Functions inherited from hpp::fcl::BVHModel< BV > | |
| 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 hpp::fcl::BVHModelBase | |
| 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... | |
| 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 inherited from hpp::fcl::BVHModel< BV > | |
| 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< 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 inherited from hpp::fcl::BVHModel< BV > | |
| bool | allocateBVs () | 
| int | buildTree () | 
| Build the bounding volume hierarchy.  More... | |
| void | deleteBVs () | 
| void | makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c) | 
| void | makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c) | 
| void | makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c) | 
| void | makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c) | 
| void | makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c) | 
| void | makeParentRelativeRecurse (int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c) | 
| 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 inherited from hpp::fcl::BVHModel< BV > | |
| 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 | 
Definition at line 167 of file serialization/BVH_model.h.
| typedef hpp::fcl::BVHModel<BV> boost::serialization::internal::BVHModelAccessor< BV >::Base | 
Definition at line 168 of file serialization/BVH_model.h.