38 #ifndef FCL_BVH_MODEL_INL_H 39 #define FCL_BVH_MODEL_INL_H 49 template <
typename BV>
52 if(num_tris && num_vertices)
61 template <
typename BV>
64 prev_vertices(nullptr),
69 bv_fitter(new detail::BVFitter<BV>()),
70 num_tris_allocated(0),
71 num_vertices_allocated(0),
73 num_vertex_updated(0),
74 primitive_indices(nullptr),
82 template <
typename BV>
85 num_tris(other.num_tris),
86 num_vertices(other.num_vertices),
87 build_state(other.build_state),
88 bv_splitter(other.bv_splitter),
89 bv_fitter(other.bv_fitter),
90 num_tris_allocated(other.num_tris),
91 num_vertices_allocated(other.num_vertices)
103 tri_indices =
new Triangle[num_tris];
107 tri_indices =
nullptr;
115 prev_vertices =
nullptr;
119 int num_primitives = 0;
123 num_primitives = num_tris;
126 num_primitives = num_vertices;
132 primitive_indices =
new unsigned int[num_primitives];
136 primitive_indices =
nullptr;
138 num_bvs = num_bvs_allocated = other.
num_bvs;
142 std::copy(other.
bvs, other.
bvs + num_bvs, bvs);
149 template <
typename BV>
153 delete [] tri_indices;
156 delete [] prev_vertices;
157 delete [] primitive_indices;
161 template <
typename BV>
168 template <
typename BV>
175 template <
typename BV>
182 template <
typename BV>
189 template <
typename BV>
199 template <
typename BV>
206 template <
typename BV>
211 delete [] vertices; vertices =
nullptr;
212 delete [] tri_indices; tri_indices =
nullptr;
213 delete [] bvs; bvs =
nullptr;
214 delete [] prev_vertices; prev_vertices =
nullptr;
215 delete [] primitive_indices; primitive_indices =
nullptr;
217 num_vertices_allocated = num_vertices = num_tris_allocated = num_tris = num_bvs_allocated = num_bvs = 0;
220 if(num_tris_ < 0) num_tris_ = 8;
221 if(num_vertices_ <= 0) num_vertices_ = 8;
223 num_vertices_allocated = num_vertices_;
224 num_tris_allocated = num_tris_;
228 tri_indices =
new(std::nothrow)
Triangle[num_tris_allocated];
231 std::cerr <<
"BVH Error! Out of memory for tri_indices array on BeginModel() call!\n";
236 vertices =
new Vector3<S>[num_vertices_allocated];
239 std::cerr <<
"BVH Error! Out of memory for vertices array on BeginModel() call!\n";
245 std::cerr <<
"BVH Warning! Call beginModel() on a BVHModel that is not empty. This model was cleared and previous triangles/vertices were lost.\n";
256 template <
typename BV>
261 std::cerr <<
"BVH Warning! Call addVertex() in a wrong order. addVertex() was ignored. Must do a beginModel() to clear the model for addition of new vertices.\n";
265 if(num_vertices >= num_vertices_allocated)
270 std::cerr <<
"BVH Error! Out of memory for vertices array on addVertex() call!\n";
274 std::copy(vertices, vertices + num_vertices, temp);
277 num_vertices_allocated *= 2;
280 vertices[num_vertices] = p;
287 template <
typename BV>
292 std::cerr <<
"BVH Warning! Call addTriangle() in a wrong order. addTriangle() was ignored. Must do a beginModel() to clear the model for addition of new triangles.\n";
296 if(num_vertices + 2 >= num_vertices_allocated)
301 std::cerr <<
"BVH Error! Out of memory for vertices array on addTriangle() call!\n";
305 std::copy(vertices, vertices + num_vertices, temp);
308 num_vertices_allocated = num_vertices_allocated * 2 + 2;
311 int offset = num_vertices;
313 vertices[num_vertices] = p1;
315 vertices[num_vertices] = p2;
317 vertices[num_vertices] = p3;
320 if(num_tris >= num_tris_allocated)
322 if(num_tris_allocated == 0)
324 num_tris_allocated = 1;
329 std::cerr <<
"BVH Error! Out of memory for tri_indices array on addTriangle() call!\n";
333 std::copy(tri_indices, tri_indices + num_tris, temp);
334 delete [] tri_indices;
336 num_tris_allocated *= 2;
339 tri_indices[num_tris].
set(offset, offset + 1, offset + 2);
346 template <
typename BV>
351 std::cerr <<
"BVH Warning! Call addSubModel() in a wrong order. addSubModel() was ignored. Must do a beginModel() to clear the model for addition of new vertices.\n";
355 int num_vertices_to_add = ps.size();
357 if(num_vertices + num_vertices_to_add - 1 >= num_vertices_allocated)
362 std::cerr <<
"BVH Error! Out of memory for vertices array on addSubModel() call!\n";
366 std::copy(vertices, vertices + num_vertices, temp);
369 num_vertices_allocated = num_vertices_allocated * 2 + num_vertices_to_add - 1;
372 for(
int i = 0; i < num_vertices_to_add; ++i)
374 vertices[num_vertices] = ps[i];
382 template <
typename BV>
387 std::cerr <<
"BVH Warning! Call addSubModel() in a wrong order. addSubModel() was ignored. Must do a beginModel() to clear the model for addition of new vertices.\n";
391 int num_vertices_to_add = ps.size();
393 if(num_vertices + num_vertices_to_add - 1 >= num_vertices_allocated)
398 std::cerr <<
"BVH Error! Out of memory for vertices array on addSubModel() call!\n";
402 std::copy(vertices, vertices + num_vertices, temp);
405 num_vertices_allocated = num_vertices_allocated * 2 + num_vertices_to_add - 1;
408 int offset = num_vertices;
410 for(
int i = 0; i < num_vertices_to_add; ++i)
412 vertices[num_vertices] = ps[i];
417 int num_tris_to_add = ts.size();
419 if(num_tris + num_tris_to_add - 1 >= num_tris_allocated)
421 if(num_tris_allocated == 0)
423 num_tris_allocated = 1;
425 Triangle* temp =
new(std::nothrow)
Triangle[num_tris_allocated * 2 + num_tris_to_add - 1];
428 std::cerr <<
"BVH Error! Out of memory for tri_indices array on addSubModel() call!\n";
432 std::copy(tri_indices, tri_indices + num_tris, temp);
433 delete [] tri_indices;
435 num_tris_allocated = num_tris_allocated * 2 + num_tris_to_add - 1;
438 for(
int i = 0; i < num_tris_to_add; ++i)
441 tri_indices[num_tris].
set(t[0] + offset, t[1] + offset, t[2] + offset);
449 template <
typename BV>
454 std::cerr <<
"BVH Warning! Call endModel() in wrong order. endModel() was ignored.\n";
458 if(num_tris == 0 && num_vertices == 0)
460 std::cerr <<
"BVH Error! endModel() called on model with no triangles and vertices.\n";
464 if(num_tris_allocated > num_tris)
469 std::cerr <<
"BVH Error! Out of memory for tri_indices array in endModel() call!\n";
472 std::copy(tri_indices, tri_indices + num_tris, new_tris);
473 delete [] tri_indices;
474 tri_indices = new_tris;
475 num_tris_allocated = num_tris;
478 if(num_vertices_allocated > num_vertices)
483 std::cerr <<
"BVH Error! Out of memory for vertices array in endModel() call!\n";
486 std::copy(vertices, vertices + num_vertices, new_vertices);
488 vertices = new_vertices;
489 num_vertices_allocated = num_vertices;
494 int num_bvs_to_be_allocated = 0;
496 num_bvs_to_be_allocated = 2 * num_vertices - 1;
498 num_bvs_to_be_allocated = 2 * num_tris - 1;
501 bvs =
new(std::nothrow)
BVNode<BV> [num_bvs_to_be_allocated];
502 primitive_indices =
new(std::nothrow)
unsigned int [num_bvs_to_be_allocated];
503 if(!bvs || !primitive_indices)
505 std::cerr <<
"BVH Error! Out of memory for BV array in endModel()!\n";
508 num_bvs_allocated = num_bvs_to_be_allocated;
520 template <
typename BV>
525 std::cerr <<
"BVH Error! Call beginReplaceModel() on a BVHModel that has no previous frame.\n";
531 delete [] prev_vertices;
532 prev_vertices =
nullptr;
535 num_vertex_updated = 0;
543 template <
typename BV>
548 std::cerr <<
"BVH Warning! Call replaceVertex() in a wrong order. replaceVertex() was ignored. Must do a beginReplaceModel() for initialization.\n";
552 vertices[num_vertex_updated] = p;
553 num_vertex_updated++;
559 template <
typename BV>
564 std::cerr <<
"BVH Warning! Call replaceTriangle() in a wrong order. replaceTriangle() was ignored. Must do a beginReplaceModel() for initialization.\n";
568 vertices[num_vertex_updated] = p1; num_vertex_updated++;
569 vertices[num_vertex_updated] = p2; num_vertex_updated++;
570 vertices[num_vertex_updated] = p3; num_vertex_updated++;
575 template <
typename BV>
580 std::cerr <<
"BVH Warning! Call replaceSubModel() in a wrong order. replaceSubModel() was ignored. Must do a beginReplaceModel() for initialization.\n";
584 for(
unsigned int i = 0; i < ps.size(); ++i)
586 vertices[num_vertex_updated] = ps[i];
587 num_vertex_updated++;
593 template <
typename BV>
598 std::cerr <<
"BVH Warning! Call endReplaceModel() in a wrong order. endReplaceModel() was ignored. \n";
602 if(num_vertex_updated != num_vertices)
604 std::cerr <<
"BVH Error! The replaced model should have the same number of vertices as the old model.\n";
623 template <
typename BV>
628 std::cerr <<
"BVH Error! Call beginUpdatemodel() on a BVHModel that has no previous frame.\n";
635 prev_vertices = vertices;
640 prev_vertices = vertices;
644 num_vertex_updated = 0;
652 template <
typename BV>
657 std::cerr <<
"BVH Warning! Call updateVertex() in a wrong order. updateVertex() was ignored. Must do a beginUpdateModel() for initialization.\n";
661 vertices[num_vertex_updated] = p;
662 num_vertex_updated++;
668 template <
typename BV>
673 std::cerr <<
"BVH Warning! Call updateTriangle() in a wrong order. updateTriangle() was ignored. Must do a beginUpdateModel() for initialization.\n";
677 vertices[num_vertex_updated] = p1; num_vertex_updated++;
678 vertices[num_vertex_updated] = p2; num_vertex_updated++;
679 vertices[num_vertex_updated] = p3; num_vertex_updated++;
684 template <
typename BV>
689 std::cerr <<
"BVH Warning! Call updateSubModel() in a wrong order. updateSubModel() was ignored. Must do a beginUpdateModel() for initialization.\n";
693 for(
unsigned int i = 0; i < ps.size(); ++i)
695 vertices[num_vertex_updated] = ps[i];
696 num_vertex_updated++;
702 template <
typename BV>
707 std::cerr <<
"BVH Warning! Call endUpdateModel() in a wrong order. endUpdateModel() was ignored. \n";
711 if(num_vertex_updated != num_vertices)
713 std::cerr <<
"BVH Error! The updated model should have the same number of vertices as the old model.\n";
737 template <
typename BV>
740 int mem_bv_list =
sizeof(BV) * num_bvs;
741 int mem_tri_list =
sizeof(
Triangle) * num_tris;
742 int mem_vertex_list =
sizeof(
Vector3<S>) * num_vertices;
744 int total_mem = mem_bv_list + mem_tri_list + mem_vertex_list +
sizeof(
BVHModel<BV>);
747 std::cerr <<
"Total for model " << total_mem <<
" bytes.\n";
748 std::cerr <<
"BVs: " << num_bvs <<
" allocated.\n";
749 std::cerr <<
"Tris: " << num_tris <<
" allocated.\n";
750 std::cerr <<
"Vertices: " << num_vertices <<
" allocated.\n";
757 template <
typename BV>
760 makeParentRelativeRecurse(
765 template <
typename BV>
770 for(
int i = 0; i < num_tris; ++i)
772 const Triangle& tri = tri_indices[i];
773 S d_six_vol = (vertices[tri[0]].cross(vertices[tri[1]])).dot(vertices[tri[2]]);
775 com.noalias() += (vertices[tri[0]] + vertices[tri[1]] + vertices[tri[2]]) * d_six_vol;
778 return com / (vol * 4);
782 template <
typename BV>
786 for(
int i = 0; i < num_tris; ++i)
788 const Triangle& tri = tri_indices[i];
789 S d_six_vol = (vertices[tri[0]].cross(vertices[tri[1]])).dot(vertices[tri[2]]);
797 template <
typename BV>
803 C_canonical << 1/ 60.0, 1/120.0, 1/120.0,
804 1/120.0, 1/ 60.0, 1/120.0,
805 1/120.0, 1/120.0, 1/ 60.0;
807 for(
int i = 0; i < num_tris; ++i)
809 const Triangle& tri = tri_indices[i];
813 S d_six_vol = (v1.cross(v2)).dot(v3);
818 C.noalias() += A.transpose() * C_canonical * A * d_six_vol;
821 S trace_C = C(0, 0) + C(1, 1) + C(2, 2);
824 m << trace_C - C(0, 0), -C(0, 1), -C(0, 2),
825 -C(1, 0), trace_C - C(1, 1), -C(1, 2),
826 -C(2, 0), -C(2, 1), trace_C - C(2, 2);
832 template <
typename BV>
836 bv_fitter->set(vertices, tri_indices, getModelType());
838 bv_splitter->set(vertices, tri_indices, getModelType());
842 int num_primitives = 0;
843 switch(getModelType())
846 num_primitives = num_tris;
849 num_primitives = num_vertices;
852 std::cerr <<
"BVH Error: Model type not supported!\n";
856 for(
int i = 0; i < num_primitives; ++i)
857 primitive_indices[i] = i;
858 recursiveBuildTree(0, 0, num_primitives);
861 bv_splitter->clear();
867 template <
typename BV>
872 unsigned int* cur_primitive_indices = primitive_indices + first_primitive;
875 BV bv = bv_fitter->fit(cur_primitive_indices, num_primitives);
876 bv_splitter->computeRule(bv, cur_primitive_indices, num_primitives);
882 if(num_primitives == 1)
884 bvnode->
first_child = -((*cur_primitive_indices) + 1);
892 for(
int i = 0; i < num_primitives; ++i)
898 const Triangle& t = tri_indices[cur_primitive_indices[i]];
902 p.noalias() = (p1 + p2 + p3) / 3.0;
906 std::cerr <<
"BVH Error: Model type not supported!\n";
917 if(bv_splitter->apply(p))
923 std::swap(cur_primitive_indices[i], cur_primitive_indices[c1]);
929 if((c1 == 0) || (c1 == num_primitives)) c1 = num_primitives / 2;
931 int num_first_half = c1;
933 recursiveBuildTree(bvnode->
leftChild(), first_primitive, num_first_half);
934 recursiveBuildTree(bvnode->
rightChild(), first_primitive + num_first_half, num_primitives - num_first_half);
941 template <
typename BV>
945 return refitTree_bottomup();
947 return refitTree_topdown();
951 template <
typename BV>
954 int res = recursiveRefitTree_bottomup(0);
960 template <
typename BV>
975 v[0] = prev_vertices[primitive_id];
976 v[1] = vertices[primitive_id];
980 fit(vertices + primitive_id, 1, bv);
987 const Triangle& triangle = tri_indices[primitive_id];
992 for(
int i = 0; i < 3; ++i)
994 v[i] = prev_vertices[triangle[i]];
995 v[i + 3] = vertices[triangle[i]];
1003 for(
int i = 0; i < 3; ++i)
1005 v[i] = vertices[triangle[i]];
1015 std::cerr <<
"BVH Error: Model type not supported!\n";
1021 recursiveRefitTree_bottomup(bvnode->
leftChild());
1022 recursiveRefitTree_bottomup(bvnode->
rightChild());
1030 template <
typename S,
typename BV>
1038 if(!model.
bvs[bv_id].isLeaf())
1041 tmp1(model, model.
bvs[bv_id].first_child, parent_axis, model.
bvs[bv_id].getCenter());
1044 tmp2(model, model.
bvs[bv_id].first_child + 1, parent_axis, model.
bvs[bv_id].getCenter());
1052 template <
typename BV>
1059 *
this, bv_id, parent_axis, parent_c);
1063 template <
typename BV>
1066 bv_fitter->set(vertices, prev_vertices, tri_indices, getModelType());
1067 for(
int i = 0; i < num_bvs; ++i)
1069 BV bv = bv_fitter->fit(primitive_indices + bvs[i].first_primitive, bvs[i].num_primitives);
1079 template <
typename BV>
1083 for(
int i = 0; i < num_vertices; ++i)
1085 aabb_ += vertices[i];
1088 this->aabb_center = aabb_.
center();
1090 this->aabb_radius = 0;
1091 for(
int i = 0; i < num_vertices; ++i)
1093 S r = (this->aabb_center - vertices[i]).squaredNorm();
1094 if(r > this->aabb_radius) this->aabb_radius =
r;
1097 this->aabb_radius = sqrt(this->aabb_radius);
1099 this->aabb_local = aabb_;
1103 template <
typename S>
1111 OBB<S>& obb = model.bvs[bv_id].bv;
1112 if(!model.bvs[bv_id].isLeaf())
1115 tmp1(model, model.bvs[bv_id].first_child, obb.
axis, obb.
To);
1118 tmp2(model, model.bvs[bv_id].first_child + 1, obb.
axis, obb.
To);
1122 obb.
axis = parent_axis.transpose() * obb.
axis;
1123 obb.
To = (obb.
To - parent_c).transpose() * parent_axis;
1128 template <
typename S>
1136 RSS<S>& rss = model.bvs[bv_id].bv;
1137 if(!model.bvs[bv_id].isLeaf())
1140 tmp1(model, model.bvs[bv_id].first_child, rss.
axis, rss.
To);
1143 tmp2(model, model.bvs[bv_id].first_child + 1, rss.
axis, rss.
To);
1147 rss.
axis = parent_axis.transpose() * rss.
axis;
1148 rss.
To = (rss.
To - parent_c).transpose() * parent_axis;
1153 template <
typename S>
1161 OBB<S>& obb = model.bvs[bv_id].bv.obb;
1162 RSS<S>& rss = model.bvs[bv_id].bv.rss;
1163 if(!model.bvs[bv_id].isLeaf())
1166 tmp1(model, model.bvs[bv_id].first_child, obb.
axis, obb.
To);
1169 tmp2(model, model.bvs[bv_id].first_child + 1, obb.
axis, obb.
To);
1173 obb.
axis = parent_axis.transpose() * obb.
axis;
1176 obb.
To = (obb.
To - parent_c).transpose() * parent_axis;
1182 template <
typename S>
1192 template <
typename S>
1202 template <
typename S>
1212 template <
typename S>
1222 template <
typename S>
1232 template <
typename S>
1242 template <
typename S>
1252 template <
typename S>
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
void set(std::size_t p1, std::size_t p2, std::size_t p3)
Set the vertex indices of the triangle.
static void run(BVHModel< BV > &model, int bv_id, const Matrix3< S > &parent_axis, const Vector3< S > &parent_c)
BVHModelType getModelType() const
Model type described by the instance.
AABB< S > translate(const AABB< S > &aabb, const Eigen::MatrixBase< Derived > &t)
translate the center of AABB by t
BVHModelType
BVH model type.
BVHModel()
Constructing an empty BVH.
int rightChild() const
Return the index of the second child. The index is referred to the bounding volume array (i...
static void run(BVHModel< OBB< S >> &model, int bv_id, const Matrix3< S > &parent_axis, const Vector3< S > &parent_c)
Vector3< S > * prev_vertices
Geometry point data in previous frame.
Eigen::Matrix< S, 3, 3 > Matrix3
Vector3< S > center() const
Center of the AABB.
Vector3< S > * vertices
Geometry point data.
BVNode< BV > * bvs
Bounding volume hierarchy.
Eigen::Matrix< S, 3, 1 > Vector3
BVH geometry is not prepared.
The geometry for the object for collision or distance computation.
Cannot allocate memory for vertices and triangles.
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Triangle with 3 indices for points.
BVH geometry in previous frame is not prepared.
int first_child
An index for first child node or primitive If the value is positive, it is the index of the first chi...
int num_bvs
Number of BV nodes in bounding volume hierarchy.
KDOP class describes the KDOP collision structures. K is set as the template parameter, which should be 16, 18, or 24 The KDOP structure is defined by some pairs of parallel planes defined by some axes. For K = 16, the planes are 6 AABB planes and 10 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 8 (0,-1,0) and (0,1,0) -> indices 1 and 9 (0,0,-1) and (0,0,1) -> indices 2 and 10 (-1,-1,0) and (1,1,0) -> indices 3 and 11 (-1,0,-1) and (1,0,1) -> indices 4 and 12 (0,-1,-1) and (0,1,1) -> indices 5 and 13 (-1,1,0) and (1,-1,0) -> indices 6 and 14 (-1,0,1) and (1,0,-1) -> indices 7 and 15 For K = 18, the planes are 6 AABB planes and 12 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 9 (0,-1,0) and (0,1,0) -> indices 1 and 10 (0,0,-1) and (0,0,1) -> indices 2 and 11 (-1,-1,0) and (1,1,0) -> indices 3 and 12 (-1,0,-1) and (1,0,1) -> indices 4 and 13 (0,-1,-1) and (0,1,1) -> indices 5 and 14 (-1,1,0) and (1,-1,0) -> indices 6 and 15 (-1,0,1) and (1,0,-1) -> indices 7 and 16 (0,-1,1) and (0,1,-1) -> indices 8 and 17 For K = 18, the planes are 6 AABB planes and 18 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 12 (0,-1,0) and (0,1,0) -> indices 1 and 13 (0,0,-1) and (0,0,1) -> indices 2 and 14 (-1,-1,0) and (1,1,0) -> indices 3 and 15 (-1,0,-1) and (1,0,1) -> indices 4 and 16 (0,-1,-1) and (0,1,1) -> indices 5 and 17 (-1,1,0) and (1,-1,0) -> indices 6 and 18 (-1,0,1) and (1,0,-1) -> indices 7 and 19 (0,-1,1) and (0,1,-1) -> indices 8 and 20 (-1, -1, 1) and (1, 1, -1) –> indices 9 and 21 (-1, 1, -1) and (1, -1, 1) –> indices 10 and 22 (1, -1, -1) and (-1, 1, 1) –> indices 11 and 23.
int num_primitives
The number of primitives belonging to the current node.
int leftChild() const
Return the index of the first child. The index is referred to the bounding volume array (i...
unsigned int * primitive_indices
for ccd vertex update
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
after beginModel(), state for adding geometry primitives
bool isLeaf() const
Whether current node is a leaf node (i.e. contains a primitive index.
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
BV bv
bounding volume storing the geometry
Matrix3< S > axis
Orientation of OBB. The axes of the rotation matrix are the principle directions of the box...
after tree has been build, ready for cd use
static void swap(T &x, T &y)
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
BVH construction does not follow correct sequence.
after tree has been build for updated geometry, ready for ccd use
empty state, immediately after constructor
FCL_EXPORT void fit(const Vector3< typename BV::S > *const ps, int n, BV &bv)
Compute a bounding volume that fits a set of n points.
Vector3< S > To
Center of OBB.
after beginUpdateModel(), state for updating geometry primitives
A class describing the kIOS collision structure, which is a set of spheres.
int first_primitive
The start id the primitive belonging to the current node. The index is referred to the primitive_indi...
Oriented bounding box class.