38 #ifndef FCL_BVH_MODEL_H 39 #define FCL_BVH_MODEL_H 56 template <
typename BV>
61 using S =
typename BV::S;
85 int getNumBVs()
const;
94 void computeLocalAABB()
override;
97 int beginModel(
int num_tris = 0,
int num_vertices = 0);
106 int addSubModel(
const std::vector<
Vector3<S>>& ps,
const std::vector<Triangle>& ts);
109 int addSubModel(
const std::vector<
Vector3<S>>& ps);
116 int beginReplaceModel();
125 int replaceSubModel(
const std::vector<
Vector3<S>>& ps);
128 int endReplaceModel(
bool refit =
true,
bool bottomup =
true);
133 int beginUpdateModel();
142 int updateSubModel(
const std::vector<
Vector3<S>>& ps);
145 int endUpdateModel(
bool refit =
true,
bool bottomup =
true);
148 int memUsage(
int msg)
const;
152 void makeParentRelative();
156 S computeVolume()
const override;
158 Matrix3<S> computeMomentofInertia()
const override;
203 int refitTree(
bool bottomup);
206 int refitTree_topdown();
209 int refitTree_bottomup();
212 int recursiveBuildTree(
int bv_id,
int first_primitive,
int num_primitives);
215 int recursiveRefitTree_bottomup(
int bv_id);
220 void makeParentRelativeRecurse(
225 template <
typename,
typename>
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, halfspace, triangle), and octree
int num_vertices_allocated
BVHBuildState
States for BVH construction empty->begun->processed ->replace_begun->processed -> ...
BVHModelType
BVH model type.
Vector3< S > * prev_vertices
Geometry point data in previous frame.
Eigen::Matrix< S, 3, 3 > Matrix3
Vector3< S > * vertices
Geometry point data.
BVNode< BV > * bvs
Bounding volume hierarchy.
Eigen::Matrix< S, 3, 1 > Vector3
int num_vertices
Number of points.
The geometry for the object for collision or distance computation.
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Triangle with 3 indices for points.
int num_tris
Number of triangles.
std::shared_ptr< detail::BVFitterBase< BV > > bv_fitter
Fitting rule to fit a BV node to a set of geometry primitives.
int num_bvs
Number of BV nodes in bounding volume hierarchy.
unsigned int * primitive_indices
for ccd vertex update
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
std::shared_ptr< detail::BVSplitterBase< BV > > bv_splitter
Split rule to split one BV node into two children.
BVHBuildState build_state
The state of BVH building process.