coal/BVH/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 COAL_BVH_MODEL_H
40 #define COAL_BVH_MODEL_H
41 
42 #include "coal/fwd.hh"
43 #include "coal/collision_object.h"
44 #include "coal/BVH/BVH_internal.h"
45 #include "coal/BV/BV_node.h"
46 
47 #include <vector>
48 #include <memory>
49 #include <iostream>
50 
51 namespace coal {
52 
55 
56 class ConvexBase;
57 
58 template <typename BV>
59 class BVFitter;
60 template <typename BV>
61 class BVSplitter;
62 
65 class COAL_DLLAPI BVHModelBase : public CollisionGeometry {
66  public:
68  std::shared_ptr<std::vector<Vec3s>> vertices;
69 
71  std::shared_ptr<std::vector<Triangle>> tri_indices;
72 
74  std::shared_ptr<std::vector<Vec3s>> prev_vertices;
75 
77  unsigned int num_tris;
78 
80  unsigned int num_vertices;
81 
84 
86  shared_ptr<ConvexBase> convex;
87 
90  if (num_tris && num_vertices)
91  return BVH_MODEL_TRIANGLES;
92  else if (num_vertices)
93  return BVH_MODEL_POINTCLOUD;
94  else
95  return BVH_MODEL_UNKNOWN;
96  }
97 
99  BVHModelBase();
100 
102  BVHModelBase(const BVHModelBase& other);
103 
105  virtual ~BVHModelBase() {}
106 
108  OBJECT_TYPE getObjectType() const { return OT_BVH; }
109 
111  void computeLocalAABB();
112 
114  int beginModel(unsigned int num_tris = 0, unsigned int num_vertices = 0);
115 
117  int addVertex(const Vec3s& p);
118 
120  int addVertices(const MatrixX3s& points);
121 
123  int addTriangles(const Matrixx3i& triangles);
124 
126  int addTriangle(const Vec3s& p1, const Vec3s& p2, const Vec3s& p3);
127 
129  int addSubModel(const std::vector<Vec3s>& ps,
130  const std::vector<Triangle>& ts);
131 
133  int addSubModel(const std::vector<Vec3s>& ps);
134 
137  int endModel();
138 
141  int beginReplaceModel();
142 
144  int replaceVertex(const Vec3s& p);
145 
147  int replaceTriangle(const Vec3s& p1, const Vec3s& p2, const Vec3s& p3);
148 
150  int replaceSubModel(const std::vector<Vec3s>& ps);
151 
154  int endReplaceModel(bool refit = true, bool bottomup = true);
155 
159  int beginUpdateModel();
160 
162  int updateVertex(const Vec3s& p);
163 
165  int updateTriangle(const Vec3s& p1, const Vec3s& p2, const Vec3s& p3);
166 
168  int updateSubModel(const std::vector<Vec3s>& ps);
169 
172  int endUpdateModel(bool refit = true, bool bottomup = true);
173 
178  void buildConvexRepresentation(bool share_memory);
179 
191  bool buildConvexHull(bool keepTriangle, const char* qhullCommand = NULL);
192 
193  virtual int memUsage(const bool msg = false) const = 0;
194 
199  virtual void makeParentRelative() = 0;
200 
201  Vec3s computeCOM() const {
202  CoalScalar vol = 0;
203  Vec3s com(0, 0, 0);
204  if (!(vertices.get())) {
205  std::cerr << "BVH Error in `computeCOM`! The BVHModel does not contain "
206  "vertices."
207  << std::endl;
208  return com;
209  }
210  const std::vector<Vec3s>& vertices_ = *vertices;
211  if (!(tri_indices.get())) {
212  std::cerr << "BVH Error in `computeCOM`! The BVHModel does not contain "
213  "triangles."
214  << std::endl;
215  return com;
216  }
217  const std::vector<Triangle>& tri_indices_ = *tri_indices;
218 
219  for (unsigned int i = 0; i < num_tris; ++i) {
220  const Triangle& tri = tri_indices_[i];
221  CoalScalar d_six_vol =
222  (vertices_[tri[0]].cross(vertices_[tri[1]])).dot(vertices_[tri[2]]);
223  vol += d_six_vol;
224  com += (vertices_[tri[0]] + vertices_[tri[1]] + vertices_[tri[2]]) *
225  d_six_vol;
226  }
227 
228  return com / (vol * 4);
229  }
230 
232  CoalScalar vol = 0;
233  if (!(vertices.get())) {
234  std::cerr << "BVH Error in `computeCOM`! The BVHModel does not contain "
235  "vertices."
236  << std::endl;
237  return vol;
238  }
239  const std::vector<Vec3s>& vertices_ = *vertices;
240  if (!(tri_indices.get())) {
241  std::cerr << "BVH Error in `computeCOM`! The BVHModel does not contain "
242  "triangles."
243  << std::endl;
244  return vol;
245  }
246  const std::vector<Triangle>& tri_indices_ = *tri_indices;
247  for (unsigned int i = 0; i < num_tris; ++i) {
248  const Triangle& tri = tri_indices_[i];
249  CoalScalar d_six_vol =
250  (vertices_[tri[0]].cross(vertices_[tri[1]])).dot(vertices_[tri[2]]);
251  vol += d_six_vol;
252  }
253 
254  return vol / 6;
255  }
256 
258  Matrix3s C = Matrix3s::Zero();
259 
260  Matrix3s C_canonical;
261  C_canonical << 1 / 60.0, 1 / 120.0, 1 / 120.0, 1 / 120.0, 1 / 60.0,
262  1 / 120.0, 1 / 120.0, 1 / 120.0, 1 / 60.0;
263 
264  if (!(vertices.get())) {
265  std::cerr << "BVH Error in `computeMomentofInertia`! The BVHModel does "
266  "not contain vertices."
267  << std::endl;
268  return C;
269  }
270  const std::vector<Vec3s>& vertices_ = *vertices;
271  if (!(vertices.get())) {
272  std::cerr << "BVH Error in `computeMomentofInertia`! The BVHModel does "
273  "not contain vertices."
274  << std::endl;
275  return C;
276  }
277  const std::vector<Triangle>& tri_indices_ = *tri_indices;
278  for (unsigned int i = 0; i < num_tris; ++i) {
279  const Triangle& tri = tri_indices_[i];
280  const Vec3s& v1 = vertices_[tri[0]];
281  const Vec3s& v2 = vertices_[tri[1]];
282  const Vec3s& v3 = vertices_[tri[2]];
283  Matrix3s A;
284  A << v1.transpose(), v2.transpose(), v3.transpose();
285  C += A.derived().transpose() * C_canonical * A * (v1.cross(v2)).dot(v3);
286  }
287 
288  return C.trace() * Matrix3s::Identity() - C;
289  }
290 
291  protected:
292  virtual void deleteBVs() = 0;
293  virtual bool allocateBVs() = 0;
294 
296  virtual int buildTree() = 0;
297 
299  virtual int refitTree(bool bottomup) = 0;
300 
301  unsigned int num_tris_allocated;
303  unsigned int num_vertex_updated;
304 
305  protected:
307  virtual bool isEqual(const CollisionGeometry& other) const;
308 };
309 
313 template <typename BV>
314 class COAL_DLLAPI BVHModel : public BVHModelBase {
316 
317  public:
318  using bv_node_vector_t =
319  std::vector<BVNode<BV>, Eigen::aligned_allocator<BVNode<BV>>>;
320 
322  shared_ptr<BVSplitter<BV>> bv_splitter;
323 
325  shared_ptr<BVFitter<BV>> bv_fitter;
326 
328  BVHModel();
329 
334  BVHModel(const BVHModel& other);
335 
337  virtual BVHModel<BV>* clone() const { return new BVHModel(*this); }
338 
341 
344 
346  const BVNode<BV>& getBV(unsigned int i) const {
347  assert(i < num_bvs);
348  return (*bvs)[i];
349  }
350 
352  BVNode<BV>& getBV(unsigned int i) {
353  assert(i < num_bvs);
354  return (*bvs)[i];
355  }
356 
358  unsigned int getNumBVs() const { return num_bvs; }
359 
361  NODE_TYPE getNodeType() const { return BV_UNKNOWN; }
362 
364  int memUsage(const bool msg) const;
365 
371  Matrix3s I(Matrix3s::Identity());
372  makeParentRelativeRecurse(0, I, Vec3s::Zero());
373  }
374 
375  protected:
376  void deleteBVs();
377  bool allocateBVs();
378 
379  unsigned int num_bvs_allocated;
380  std::shared_ptr<std::vector<unsigned int>> primitive_indices;
381 
383  std::shared_ptr<bv_node_vector_t> bvs;
384 
386  unsigned int num_bvs;
387 
389  int buildTree();
390 
392  int refitTree(bool bottomup);
393 
396  int refitTree_topdown();
397 
400  int refitTree_bottomup();
401 
403  int recursiveBuildTree(int bv_id, unsigned int first_primitive,
404  unsigned int num_primitives);
405 
407  int recursiveRefitTree_bottomup(int bv_id);
408 
412  void makeParentRelativeRecurse(int bv_id, Matrix3s& parent_axes,
413  const Vec3s& parent_c) {
414  bv_node_vector_t& bvs_ = *bvs;
415  if (!bvs_[static_cast<size_t>(bv_id)].isLeaf()) {
416  makeParentRelativeRecurse(bvs_[static_cast<size_t>(bv_id)].first_child,
417  parent_axes,
418  bvs_[static_cast<size_t>(bv_id)].getCenter());
419 
420  makeParentRelativeRecurse(
421  bvs_[static_cast<size_t>(bv_id)].first_child + 1, parent_axes,
422  bvs_[static_cast<size_t>(bv_id)].getCenter());
423  }
424 
425  bvs_[static_cast<size_t>(bv_id)].bv =
426  translate(bvs_[static_cast<size_t>(bv_id)].bv, -parent_c);
427  }
428 
429  private:
430  virtual bool isEqual(const CollisionGeometry& _other) const {
431  const BVHModel* other_ptr = dynamic_cast<const BVHModel*>(&_other);
432  if (other_ptr == nullptr) return false;
433  const BVHModel& other = *other_ptr;
434 
435  bool res = Base::isEqual(other);
436  if (!res) return false;
437 
438  // unsigned int other_num_primitives = 0;
439  // if(other.primitive_indices)
440  // {
441 
442  // switch(other.getModelType())
443  // {
444  // case BVH_MODEL_TRIANGLES:
445  // other_num_primitives = num_tris;
446  // break;
447  // case BVH_MODEL_POINTCLOUD:
448  // other_num_primitives = num_vertices;
449  // break;
450  // default:
451  // ;
452  // }
453  // }
454 
455  // unsigned int num_primitives = 0;
456  // if(primitive_indices)
457  // {
458  //
459  // switch(other.getModelType())
460  // {
461  // case BVH_MODEL_TRIANGLES:
462  // num_primitives = num_tris;
463  // break;
464  // case BVH_MODEL_POINTCLOUD:
465  // num_primitives = num_vertices;
466  // break;
467  // default:
468  // ;
469  // }
470  // }
471  //
472  // if(num_primitives != other_num_primitives)
473  // return false;
474  //
475  // for(int k = 0; k < num_primitives; ++k)
476  // {
477  // if(primitive_indices[k] != other.primitive_indices[k])
478  // return false;
479  // }
480 
481  if (num_bvs != other.num_bvs) return false;
482 
483  if ((!(bvs.get()) && other.bvs.get()) || (bvs.get() && !(other.bvs.get())))
484  return false;
485  if (bvs.get() && other.bvs.get()) {
486  const bv_node_vector_t& bvs_ = *bvs;
487  const bv_node_vector_t& other_bvs_ = *(other.bvs);
488  for (unsigned int k = 0; k < num_bvs; ++k) {
489  if (bvs_[k] != other_bvs_[k]) return false;
490  }
491  }
492 
493  return true;
494  }
495 };
496 
498 
499 template <>
500 void BVHModel<OBB>::makeParentRelativeRecurse(int bv_id, Matrix3s& parent_axes,
501  const Vec3s& parent_c);
502 
503 template <>
504 void BVHModel<RSS>::makeParentRelativeRecurse(int bv_id, Matrix3s& parent_axes,
505  const Vec3s& parent_c);
506 
507 template <>
509  Matrix3s& parent_axes,
510  const Vec3s& parent_c);
511 
513 template <>
515 
516 template <>
518 
519 template <>
521 
522 template <>
524 
525 template <>
527 
528 template <>
529 NODE_TYPE BVHModel<KDOP<16>>::getNodeType() const;
530 
531 template <>
532 NODE_TYPE BVHModel<KDOP<18>>::getNodeType() const;
533 
534 template <>
535 NODE_TYPE BVHModel<KDOP<24>>::getNodeType() const;
536 
537 } // namespace coal
538 
539 #endif
coal::BV_UNKNOWN
@ BV_UNKNOWN
Definition: coal/collision_object.h:65
coal::BVH_MODEL_UNKNOWN
@ BVH_MODEL_UNKNOWN
Definition: coal/BVH/BVH_internal.h:80
coal::BVHModel::num_bvs_allocated
unsigned int num_bvs_allocated
Definition: coal/BVH/BVH_model.h:379
coal::BVHModelBase::num_vertex_updated
unsigned int num_vertex_updated
Definition: coal/BVH/BVH_model.h:303
coal::BVHModel::makeParentRelativeRecurse
void makeParentRelativeRecurse(int bv_id, Matrix3s &parent_axes, const Vec3s &parent_c)
Definition: coal/BVH/BVH_model.h:412
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::BVHModelType
BVHModelType
BVH model type.
Definition: coal/BVH/BVH_internal.h:79
coal::BVHModelBase::vertices
std::shared_ptr< std::vector< Vec3s > > vertices
Geometry point data.
Definition: coal/BVH/BVH_model.h:68
coal::OT_BVH
@ OT_BVH
Definition: coal/collision_object.h:54
coal::BVHModelBase
A base class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewe...
Definition: coal/BVH/BVH_model.h:65
coal::BVHModel::num_bvs
unsigned int num_bvs
Number of BV nodes in bounding volume hierarchy.
Definition: coal/BVH/BVH_model.h:386
coal::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: coal/collision_object.h:64
coal::BVHModel::getBV
BVNode< BV > & getBV(unsigned int i)
Access the bv giving the its index.
Definition: coal/BVH/BVH_model.h:352
coal::BVHModelBase::num_vertices_allocated
unsigned int num_vertices_allocated
Definition: coal/BVH/BVH_model.h:302
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::BVHModel::getNumBVs
unsigned int getNumBVs() const
Get the number of bv in the BVH.
Definition: coal/BVH/BVH_model.h:358
coal::BVHModelBase::computeMomentofInertia
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: coal/BVH/BVH_model.h:257
coal::BVHModelBase::computeVolume
CoalScalar computeVolume() const
compute the volume
Definition: coal/BVH/BVH_model.h:231
coal::BVHModel::getBV
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: coal/BVH/BVH_model.h:346
coal::BVHModelBase::num_tris_allocated
unsigned int num_tris_allocated
Definition: coal/BVH/BVH_model.h:301
collision_object.h
coal::BVSplitter
A class describing the split rule that splits each BV node.
Definition: coal/BVH/BVH_model.h:61
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::BVHModel::Base
BVHModelBase Base
Definition: coal/BVH/BVH_model.h:315
res
res
coal::BVH_MODEL_POINTCLOUD
@ BVH_MODEL_POINTCLOUD
triangle model
Definition: coal/BVH/BVH_internal.h:82
coal::BVH_MODEL_TRIANGLES
@ BVH_MODEL_TRIANGLES
unknown model type
Definition: coal/BVH/BVH_internal.h:81
coal::isEqual
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const CoalScalar tol=std::numeric_limits< CoalScalar >::epsilon() *100)
Definition: coal/internal/tools.h:204
fwd.hh
coal::BVHModelBase::getModelType
BVHModelType getModelType() const
Model type described by the instance.
Definition: coal/BVH/BVH_model.h:89
coal::BVHModelBase::convex
shared_ptr< ConvexBase > convex
Convex<Triangle> representation of this object.
Definition: coal/BVH/BVH_model.h:86
coal::BVHModel::primitive_indices
std::shared_ptr< std::vector< unsigned int > > primitive_indices
Definition: coal/BVH/BVH_model.h:380
coal::BVHModelBase::~BVHModelBase
virtual ~BVHModelBase()
deconstruction, delete mesh data related.
Definition: coal/BVH/BVH_model.h:105
coal::translate
static AABB translate(const AABB &aabb, const Vec3s &t)
translate the center of AABB by t
Definition: coal/BV/AABB.h:233
coal::MatrixX3s
Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3, Eigen::RowMajor > MatrixX3s
Definition: coal/data_types.h:82
coal::BVHModelBase::build_state
BVHBuildState build_state
The state of BVH building process.
Definition: coal/BVH/BVH_model.h:83
coal::BVHModel::bv_splitter
shared_ptr< BVSplitter< BV > > bv_splitter
Split rule to split one BV node into two children.
Definition: coal/BVH/BVH_model.h:322
coal::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: coal/collision_object.h:52
coal::BVHModel::bvs
std::shared_ptr< bv_node_vector_t > bvs
Bounding volume hierarchy.
Definition: coal/BVH/BVH_model.h:383
BVH_internal.h
octree.p1
tuple p1
Definition: octree.py:54
coal::BVNode
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Definition: coal/BV/BV_node.h:106
coal::BVHModel::getNodeType
NODE_TYPE getNodeType() const
Get the BV type: default is unknown.
Definition: coal/BVH/BVH_model.h:361
A
A
coal::BVHModel::~BVHModel
~BVHModel()
deconstruction, delete mesh data related.
Definition: coal/BVH/BVH_model.h:340
coal::BVHModelBase::tri_indices
std::shared_ptr< std::vector< Triangle > > tri_indices
Geometry triangle index data, will be NULL for point clouds.
Definition: coal/BVH/BVH_model.h:71
coal::BVHModel::clone
virtual BVHModel< BV > * clone() const
Clone *this into a new BVHModel.
Definition: coal/BVH/BVH_model.h:337
coal::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: coal/BVH/BVH_model.h:314
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
coal::BVHModel::bv_fitter
shared_ptr< BVFitter< BV > > bv_fitter
Fitting rule to fit a BV node to a set of geometry primitives.
Definition: coal/BVH/BVH_model.h:325
coal::BVHModel::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
for ccd vertex update
Definition: coal/BVH/BVH_model.h:430
coal::BVHBuildState
BVHBuildState
States for BVH construction empty->begun->processed ->replace_begun->processed -> ....
Definition: coal/BVH/BVH_internal.h:49
coal::BVHModel::makeParentRelative
void makeParentRelative()
This is a special acceleration: BVH_model default stores the BV's transform in world coordinate....
Definition: coal/BVH/BVH_model.h:370
coal::BVFitter
The class for the default algorithm fitting a bounding volume to a set of points.
Definition: coal/BVH/BVH_model.h:59
coal::BVHModelBase::num_vertices
unsigned int num_vertices
Number of points.
Definition: coal/BVH/BVH_model.h:80
coal::BVHModelBase::computeCOM
Vec3s computeCOM() const
compute center of mass
Definition: coal/BVH/BVH_model.h:201
coal::Triangle
Triangle with 3 indices for points.
Definition: coal/data_types.h:111
coal::BVHModelBase::num_tris
unsigned int num_tris
Number of triangles.
Definition: coal/BVH/BVH_model.h:77
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::BVHModelBase::prev_vertices
std::shared_ptr< std::vector< Vec3s > > prev_vertices
Geometry point data in previous frame.
Definition: coal/BVH/BVH_model.h:74
coal::Matrixx3i
Eigen::Matrix< Eigen::DenseIndex, Eigen::Dynamic, 3, Eigen::RowMajor > Matrixx3i
Definition: coal/data_types.h:85
coal::BVHModel::bv_node_vector_t
std::vector< BVNode< BV >, Eigen::aligned_allocator< BVNode< BV > >> bv_node_vector_t
Definition: coal/BVH/BVH_model.h:319
coal::BVHModelBase::getObjectType
OBJECT_TYPE getObjectType() const
Get the object type: it is a BVH.
Definition: coal/BVH/BVH_model.h:108
BV_node.h


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57