hpp-fcl  3.0.0
HPP fork of FCL -- The Flexible Collision Library
BVH_model.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * Copyright (c) 2020-2022, INRIA
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Open Source Robotics Foundation nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  */
36 
39 #ifndef HPP_FCL_BVH_MODEL_H
40 #define HPP_FCL_BVH_MODEL_H
41 
42 #include "hpp/fcl/fwd.hh"
45 #include "hpp/fcl/BV/BV_node.h"
46 
47 #include <vector>
48 #include <memory>
49 #include <iostream>
50 
51 namespace hpp {
52 namespace fcl {
53 
56 
57 class ConvexBase;
58 
59 template <typename BV>
60 class BVFitter;
61 template <typename BV>
62 class BVSplitter;
63 
67  public:
69  std::shared_ptr<std::vector<Vec3f>> vertices;
70 
72  std::shared_ptr<std::vector<Triangle>> tri_indices;
73 
75  std::shared_ptr<std::vector<Vec3f>> prev_vertices;
76 
78  unsigned int num_tris;
79 
81  unsigned int num_vertices;
82 
85 
87  shared_ptr<ConvexBase> convex;
88 
91  if (num_tris && num_vertices)
92  return BVH_MODEL_TRIANGLES;
93  else if (num_vertices)
94  return BVH_MODEL_POINTCLOUD;
95  else
96  return BVH_MODEL_UNKNOWN;
97  }
98 
101 
103  BVHModelBase(const BVHModelBase& other);
104 
106  virtual ~BVHModelBase() {}
107 
109  OBJECT_TYPE getObjectType() const { return OT_BVH; }
110 
113 
115  int beginModel(unsigned int num_tris = 0, unsigned int num_vertices = 0);
116 
118  int addVertex(const Vec3f& p);
119 
121  int addVertices(const Matrixx3f& points);
122 
124  int addTriangles(const Matrixx3i& triangles);
125 
127  int addTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3);
128 
130  int addSubModel(const std::vector<Vec3f>& ps,
131  const std::vector<Triangle>& ts);
132 
134  int addSubModel(const std::vector<Vec3f>& ps);
135 
138  int endModel();
139 
143 
145  int replaceVertex(const Vec3f& p);
146 
148  int replaceTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3);
149 
151  int replaceSubModel(const std::vector<Vec3f>& ps);
152 
155  int endReplaceModel(bool refit = true, bool bottomup = true);
156 
161 
163  int updateVertex(const Vec3f& p);
164 
166  int updateTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3);
167 
169  int updateSubModel(const std::vector<Vec3f>& ps);
170 
173  int endUpdateModel(bool refit = true, bool bottomup = true);
174 
179  void buildConvexRepresentation(bool share_memory);
180 
192  bool buildConvexHull(bool keepTriangle, const char* qhullCommand = NULL);
193 
194  virtual int memUsage(const bool msg = false) const = 0;
195 
200  virtual void makeParentRelative() = 0;
201 
202  Vec3f computeCOM() const {
203  FCL_REAL vol = 0;
204  Vec3f com(0, 0, 0);
205  if (!(vertices.get())) {
206  std::cerr << "BVH Error in `computeCOM`! The BVHModel does not contain "
207  "vertices."
208  << std::endl;
209  return com;
210  }
211  const std::vector<Vec3f>& vertices_ = *vertices;
212  if (!(tri_indices.get())) {
213  std::cerr << "BVH Error in `computeCOM`! The BVHModel does not contain "
214  "triangles."
215  << std::endl;
216  return com;
217  }
218  const std::vector<Triangle>& tri_indices_ = *tri_indices;
219 
220  for (unsigned int i = 0; i < num_tris; ++i) {
221  const Triangle& tri = tri_indices_[i];
222  FCL_REAL d_six_vol =
223  (vertices_[tri[0]].cross(vertices_[tri[1]])).dot(vertices_[tri[2]]);
224  vol += d_six_vol;
225  com += (vertices_[tri[0]] + vertices_[tri[1]] + vertices_[tri[2]]) *
226  d_six_vol;
227  }
228 
229  return com / (vol * 4);
230  }
231 
233  FCL_REAL vol = 0;
234  if (!(vertices.get())) {
235  std::cerr << "BVH Error in `computeCOM`! The BVHModel does not contain "
236  "vertices."
237  << std::endl;
238  return vol;
239  }
240  const std::vector<Vec3f>& vertices_ = *vertices;
241  if (!(tri_indices.get())) {
242  std::cerr << "BVH Error in `computeCOM`! The BVHModel does not contain "
243  "triangles."
244  << std::endl;
245  return vol;
246  }
247  const std::vector<Triangle>& tri_indices_ = *tri_indices;
248  for (unsigned int i = 0; i < num_tris; ++i) {
249  const Triangle& tri = tri_indices_[i];
250  FCL_REAL d_six_vol =
251  (vertices_[tri[0]].cross(vertices_[tri[1]])).dot(vertices_[tri[2]]);
252  vol += d_six_vol;
253  }
254 
255  return vol / 6;
256  }
257 
259  Matrix3f C = Matrix3f::Zero();
260 
261  Matrix3f C_canonical;
262  C_canonical << 1 / 60.0, 1 / 120.0, 1 / 120.0, 1 / 120.0, 1 / 60.0,
263  1 / 120.0, 1 / 120.0, 1 / 120.0, 1 / 60.0;
264 
265  if (!(vertices.get())) {
266  std::cerr << "BVH Error in `computeMomentofInertia`! The BVHModel does "
267  "not contain vertices."
268  << std::endl;
269  return C;
270  }
271  const std::vector<Vec3f>& vertices_ = *vertices;
272  if (!(vertices.get())) {
273  std::cerr << "BVH Error in `computeMomentofInertia`! The BVHModel does "
274  "not contain vertices."
275  << std::endl;
276  return C;
277  }
278  const std::vector<Triangle>& tri_indices_ = *tri_indices;
279  for (unsigned int i = 0; i < num_tris; ++i) {
280  const Triangle& tri = tri_indices_[i];
281  const Vec3f& v1 = vertices_[tri[0]];
282  const Vec3f& v2 = vertices_[tri[1]];
283  const Vec3f& v3 = vertices_[tri[2]];
284  Matrix3f A;
285  A << v1.transpose(), v2.transpose(), v3.transpose();
286  C += A.derived().transpose() * C_canonical * A * (v1.cross(v2)).dot(v3);
287  }
288 
289  return C.trace() * Matrix3f::Identity() - C;
290  }
291 
292  protected:
293  virtual void deleteBVs() = 0;
294  virtual bool allocateBVs() = 0;
295 
297  virtual int buildTree() = 0;
298 
300  virtual int refitTree(bool bottomup) = 0;
301 
302  unsigned int num_tris_allocated;
304  unsigned int num_vertex_updated;
305 
306  protected:
308  virtual bool isEqual(const CollisionGeometry& other) const;
309 };
310 
314 template <typename BV>
316  typedef BVHModelBase Base;
317 
318  public:
320  std::vector<BVNode<BV>, Eigen::aligned_allocator<BVNode<BV>>>;
321 
323  shared_ptr<BVSplitter<BV>> bv_splitter;
324 
326  shared_ptr<BVFitter<BV>> bv_fitter;
327 
330 
335  BVHModel(const BVHModel& other);
336 
338  virtual BVHModel<BV>* clone() const { return new BVHModel(*this); }
339 
342 
345 
347  const BVNode<BV>& getBV(unsigned int i) const {
348  assert(i < num_bvs);
349  return (*bvs)[i];
350  }
351 
353  BVNode<BV>& getBV(unsigned int i) {
354  assert(i < num_bvs);
355  return (*bvs)[i];
356  }
357 
359  unsigned int getNumBVs() const { return num_bvs; }
360 
362  NODE_TYPE getNodeType() const { return BV_UNKNOWN; }
363 
365  int memUsage(const bool msg) const;
366 
372  Matrix3f I(Matrix3f::Identity());
373  makeParentRelativeRecurse(0, I, Vec3f::Zero());
374  }
375 
376  protected:
377  void deleteBVs();
378  bool allocateBVs();
379 
380  unsigned int num_bvs_allocated;
381  std::shared_ptr<std::vector<unsigned int>> primitive_indices;
382 
384  std::shared_ptr<bv_node_vector_t> bvs;
385 
387  unsigned int num_bvs;
388 
390  int buildTree();
391 
393  int refitTree(bool bottomup);
394 
398 
402 
404  int recursiveBuildTree(int bv_id, unsigned int first_primitive,
405  unsigned int num_primitives);
406 
409 
413  void makeParentRelativeRecurse(int bv_id, Matrix3f& parent_axes,
414  const Vec3f& parent_c) {
415  bv_node_vector_t& bvs_ = *bvs;
416  if (!bvs_[static_cast<size_t>(bv_id)].isLeaf()) {
417  makeParentRelativeRecurse(bvs_[static_cast<size_t>(bv_id)].first_child,
418  parent_axes,
419  bvs_[static_cast<size_t>(bv_id)].getCenter());
420 
421  makeParentRelativeRecurse(
422  bvs_[static_cast<size_t>(bv_id)].first_child + 1, parent_axes,
423  bvs_[static_cast<size_t>(bv_id)].getCenter());
424  }
425 
426  bvs_[static_cast<size_t>(bv_id)].bv =
427  translate(bvs_[static_cast<size_t>(bv_id)].bv, -parent_c);
428  }
429 
430  private:
431  virtual bool isEqual(const CollisionGeometry& _other) const {
432  const BVHModel* other_ptr = dynamic_cast<const BVHModel*>(&_other);
433  if (other_ptr == nullptr) return false;
434  const BVHModel& other = *other_ptr;
435 
436  bool res = Base::isEqual(other);
437  if (!res) return false;
438 
439  // unsigned int other_num_primitives = 0;
440  // if(other.primitive_indices)
441  // {
442 
443  // switch(other.getModelType())
444  // {
445  // case BVH_MODEL_TRIANGLES:
446  // other_num_primitives = num_tris;
447  // break;
448  // case BVH_MODEL_POINTCLOUD:
449  // other_num_primitives = num_vertices;
450  // break;
451  // default:
452  // ;
453  // }
454  // }
455 
456  // unsigned int num_primitives = 0;
457  // if(primitive_indices)
458  // {
459  //
460  // switch(other.getModelType())
461  // {
462  // case BVH_MODEL_TRIANGLES:
463  // num_primitives = num_tris;
464  // break;
465  // case BVH_MODEL_POINTCLOUD:
466  // num_primitives = num_vertices;
467  // break;
468  // default:
469  // ;
470  // }
471  // }
472  //
473  // if(num_primitives != other_num_primitives)
474  // return false;
475  //
476  // for(int k = 0; k < num_primitives; ++k)
477  // {
478  // if(primitive_indices[k] != other.primitive_indices[k])
479  // return false;
480  // }
481 
482  if (num_bvs != other.num_bvs) return false;
483 
484  if ((!(bvs.get()) && other.bvs.get()) || (bvs.get() && !(other.bvs.get())))
485  return false;
486  if (bvs.get() && other.bvs.get()) {
487  const bv_node_vector_t& bvs_ = *bvs;
488  const bv_node_vector_t& other_bvs_ = *(other.bvs);
489  for (unsigned int k = 0; k < num_bvs; ++k) {
490  if (bvs_[k] != other_bvs_[k]) return false;
491  }
492  }
493 
494  return true;
495  }
496 };
497 
499 
500 template <>
502  const Vec3f& parent_c);
503 
504 template <>
506  const Vec3f& parent_c);
507 
508 template <>
510  Matrix3f& parent_axes,
511  const Vec3f& parent_c);
512 
514 template <>
516 
517 template <>
519 
520 template <>
522 
523 template <>
525 
526 template <>
528 
529 template <>
530 NODE_TYPE BVHModel<KDOP<16>>::getNodeType() const;
531 
532 template <>
533 NODE_TYPE BVHModel<KDOP<18>>::getNodeType() const;
534 
535 template <>
536 NODE_TYPE BVHModel<KDOP<24>>::getNodeType() const;
537 
538 } // namespace fcl
539 
540 } // namespace hpp
541 
542 #endif
A base class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewe...
Definition: BVH_model.h:66
unsigned int num_tris
Number of triangles.
Definition: BVH_model.h:78
int addTriangles(const Matrixx3i &triangles)
Add triangles in the new 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 updateTriangle(const Vec3f &p1, const Vec3f &p2, const Vec3f &p3)
Update one triangle in the old BVH model.
std::shared_ptr< std::vector< Vec3f > > prev_vertices
Geometry point data in previous frame.
Definition: BVH_model.h:75
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
unsigned int num_vertices_allocated
Definition: BVH_model.h:303
int updateVertex(const Vec3f &p)
Update one point in the old BVH model.
std::shared_ptr< std::vector< Vec3f > > vertices
Geometry point data.
Definition: BVH_model.h:69
int addSubModel(const std::vector< Vec3f > &ps)
Add a set of points in the new BVH model.
int beginUpdateModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
virtual bool isEqual(const CollisionGeometry &other) const
for ccd vertex update
BVHBuildState build_state
The state of BVH building process.
Definition: BVH_model.h:84
virtual void makeParentRelative()=0
This is a special acceleration: BVH_model default stores the BV's transform in world coordinate....
virtual int refitTree(bool bottomup)=0
Refit the bounding volume hierarchy.
int addSubModel(const std::vector< Vec3f > &ps, const std::vector< Triangle > &ts)
Add a set of triangles in the new BVH model.
unsigned int num_vertex_updated
Definition: BVH_model.h:304
BVHModelType getModelType() const
Model type described by the instance.
Definition: BVH_model.h:90
int beginReplaceModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
int addTriangle(const Vec3f &p1, const Vec3f &p2, const Vec3f &p3)
Add one triangle in the new BVH model.
virtual ~BVHModelBase()
deconstruction, delete mesh data related.
Definition: BVH_model.h:106
virtual bool allocateBVs()=0
int replaceVertex(const Vec3f &p)
Replace one point in the old BVH model.
BVHModelBase(const BVHModelBase &other)
copy from another BVH
virtual int buildTree()=0
Build the bounding volume hierarchy.
unsigned int num_vertices
Number of points.
Definition: BVH_model.h:81
Matrix3f computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: BVH_model.h:258
unsigned int num_tris_allocated
Definition: BVH_model.h:302
std::shared_ptr< std::vector< Triangle > > tri_indices
Geometry triangle index data, will be NULL for point clouds.
Definition: BVH_model.h:72
int addVertices(const Matrixx3f &points)
Add points in the new BVH model.
int endModel()
End BVH model construction, will build the bounding volume hierarchy.
BVHModelBase()
Constructing an empty BVH.
void computeLocalAABB()
Compute the AABB for the BVH, used for broad-phase collision.
shared_ptr< ConvexBase > convex
Convex<Triangle> representation of this object.
Definition: BVH_model.h:87
int addVertex(const Vec3f &p)
Add one point in the new BVH model.
int endUpdateModel(bool refit=true, bool bottomup=true)
End BVH model update, will also refit or rebuild the bounding volume hierarchy.
virtual void deleteBVs()=0
bool buildConvexHull(bool keepTriangle, const char *qhullCommand=NULL)
Build a convex hull and store it in attribute convex.
FCL_REAL computeVolume() const
compute the volume
Definition: BVH_model.h:232
OBJECT_TYPE getObjectType() const
Get the object type: it is a BVH.
Definition: BVH_model.h:109
int updateSubModel(const std::vector< Vec3f > &ps)
Update a set of points in the old BVH model.
virtual int memUsage(const bool msg=false) const =0
Vec3f computeCOM() const
compute center of mass
Definition: BVH_model.h:202
int beginModel(unsigned int num_tris=0, unsigned int num_vertices=0)
Begin a new BVH model.
void buildConvexRepresentation(bool share_memory)
Build this Convex<Triangle> representation of this model. The result is stored in attribute convex.
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:315
~BVHModel()
deconstruction, delete mesh data related.
Definition: BVH_model.h:341
int refitTree_bottomup()
Refit the bounding volume hierarchy in a bottom-up way (fast but less compact)
std::vector< BVNode< BV >, Eigen::aligned_allocator< BVNode< BV > >> bv_node_vector_t
Definition: BVH_model.h:320
BVHModel(const BVHModel &other)
Copy constructor from another BVH.
unsigned int getNumBVs() const
Get the number of bv in the BVH.
Definition: BVH_model.h:359
void makeParentRelative()
This is a special acceleration: BVH_model default stores the BV's transform in world coordinate....
Definition: BVH_model.h:371
std::shared_ptr< bv_node_vector_t > bvs
Bounding volume hierarchy.
Definition: BVH_model.h:384
int buildTree()
Build the bounding volume hierarchy.
shared_ptr< BVFitter< BV > > bv_fitter
Fitting rule to fit a BV node to a set of geometry primitives.
Definition: BVH_model.h:326
int recursiveRefitTree_bottomup(int bv_id)
Recursive kernel for bottomup refitting.
shared_ptr< BVSplitter< BV > > bv_splitter
Split rule to split one BV node into two children.
Definition: BVH_model.h:323
void makeParentRelativeRecurse(int bv_id, Matrix3f &parent_axes, const Vec3f &parent_c)
Definition: BVH_model.h:413
unsigned int num_bvs_allocated
Definition: BVH_model.h:380
BVHModel()
Default constructor to build an empty BVH.
std::shared_ptr< std::vector< unsigned int > > primitive_indices
Definition: BVH_model.h:381
unsigned int num_bvs
Number of BV nodes in bounding volume hierarchy.
Definition: BVH_model.h:387
virtual BVHModel< BV > * clone() const
Clone *this into a new BVHModel.
Definition: BVH_model.h:338
int memUsage(const bool msg) const
Check the number of memory used.
NODE_TYPE getNodeType() const
Get the BV type: default is unknown.
Definition: BVH_model.h:362
int refitTree_topdown()
Refit the bounding volume hierarchy in a top-down way (slow but more compact)
BVNode< BV > & getBV(unsigned int i)
Access the bv giving the its index.
Definition: BVH_model.h:353
int recursiveBuildTree(int bv_id, unsigned int first_primitive, unsigned int num_primitives)
Recursive kernel for hierarchy construction.
int refitTree(bool bottomup)
Refit the bounding volume hierarchy.
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...
Definition: BVH_model.h:347
The geometry for the object for collision or distance computation.
Definition: collision_object.h:95
Triangle with 3 indices for points.
Definition: data_types.h:101
#define HPP_FCL_DLLAPI
Definition: config.hh:88
KDOP< N > translate(const KDOP< N > &bv, const Vec3f &t)
translate the KDOP BV
@ OT_BVH
Definition: collision_object.h:55
@ BV_UNKNOWN
Definition: collision_object.h:66
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
Definition: data_types.h:71
BVHBuildState
States for BVH construction empty->begun->processed ->replace_begun->processed -> ....
Definition: BVH_internal.h:50
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:67
Eigen::Matrix< Eigen::DenseIndex, Eigen::Dynamic, 3, Eigen::RowMajor > Matrixx3i
Definition: data_types.h:75
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: collision_object.h:53
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_object.h:65
BVHModelType
BVH model type.
Definition: BVH_internal.h:80
@ BVH_MODEL_POINTCLOUD
triangle model
Definition: BVH_internal.h:83
@ BVH_MODEL_UNKNOWN
Definition: BVH_internal.h:81
@ BVH_MODEL_TRIANGLES
unknown model type
Definition: BVH_internal.h:82
Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 3, Eigen::RowMajor > Matrixx3f
Definition: data_types.h:72
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const FCL_REAL tol=std::numeric_limits< FCL_REAL >::epsilon() *100)
Definition: tools.h:205
double FCL_REAL
Definition: data_types.h:66
Main namespace.
Definition: broadphase_bruteforce.h:44
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Definition: BV_node.h:107