Go to the documentation of this file.
   39 #ifndef COAL_BVH_MODEL_H 
   40 #define COAL_BVH_MODEL_H 
   58 template <
typename BV>
 
   60 template <
typename BV>
 
   90     if (num_tris && num_vertices)
 
   92     else if (num_vertices)
 
  111   void computeLocalAABB();
 
  114   int beginModel(
unsigned int num_tris = 0, 
unsigned int num_vertices = 0);
 
  117   int addVertex(
const Vec3s& p);
 
  120   int addVertices(
const MatrixX3s& points);
 
  123   int addTriangles(
const Matrixx3i& triangles);
 
  129   int addSubModel(
const std::vector<Vec3s>& ps,
 
  130                   const std::vector<Triangle>& ts);
 
  133   int addSubModel(
const std::vector<Vec3s>& ps);
 
  141   int beginReplaceModel();
 
  144   int replaceVertex(
const Vec3s& p);
 
  150   int replaceSubModel(
const std::vector<Vec3s>& ps);
 
  154   int endReplaceModel(
bool refit = 
true, 
bool bottomup = 
true);
 
  159   int beginUpdateModel();
 
  162   int updateVertex(
const Vec3s& p);
 
  168   int updateSubModel(
const std::vector<Vec3s>& ps);
 
  172   int endUpdateModel(
bool refit = 
true, 
bool bottomup = 
true);
 
  178   void buildConvexRepresentation(
bool share_memory);
 
  191   bool buildConvexHull(
bool keepTriangle, 
const char* qhullCommand = NULL);
 
  193   virtual int memUsage(
const bool msg = 
false) 
const = 0;
 
  199   virtual void makeParentRelative() = 0;
 
  204     if (!(vertices.get())) {
 
  205       std::cerr << 
"BVH Error in `computeCOM`! The BVHModel does not contain " 
  210     const std::vector<Vec3s>& vertices_ = *vertices;
 
  211     if (!(tri_indices.get())) {
 
  212       std::cerr << 
"BVH Error in `computeCOM`! The BVHModel does not contain " 
  217     const std::vector<Triangle>& tri_indices_ = *tri_indices;
 
  219     for (
unsigned int i = 0; i < num_tris; ++i) {
 
  220       const Triangle& tri = tri_indices_[i];
 
  222           (vertices_[tri[0]].cross(vertices_[tri[1]])).dot(vertices_[tri[2]]);
 
  224       com += (vertices_[tri[0]] + vertices_[tri[1]] + vertices_[tri[2]]) *
 
  228     return com / (vol * 4);
 
  233     if (!(vertices.get())) {
 
  234       std::cerr << 
"BVH Error in `computeCOM`! The BVHModel does not contain " 
  239     const std::vector<Vec3s>& vertices_ = *vertices;
 
  240     if (!(tri_indices.get())) {
 
  241       std::cerr << 
"BVH Error in `computeCOM`! The BVHModel does not contain " 
  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];
 
  250           (vertices_[tri[0]].cross(vertices_[tri[1]])).dot(vertices_[tri[2]]);
 
  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;
 
  264     if (!(vertices.get())) {
 
  265       std::cerr << 
"BVH Error in `computeMomentofInertia`! The BVHModel does " 
  266                    "not contain vertices." 
  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." 
  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]];
 
  284       A << v1.transpose(), v2.transpose(), v3.transpose();
 
  285       C += 
A.derived().transpose() * C_canonical * 
A * (v1.cross(v2)).dot(v3);
 
  288     return C.trace() * Matrix3s::Identity() - C;
 
  292   virtual void deleteBVs() = 0;
 
  293   virtual bool allocateBVs() = 0;
 
  296   virtual int buildTree() = 0;
 
  299   virtual int refitTree(
bool bottomup) = 0;
 
  313 template <
typename BV>
 
  319       std::vector<BVNode<BV>, Eigen::aligned_allocator<BVNode<BV>>>;
 
  364   int memUsage(
const bool msg) 
const;
 
  372     makeParentRelativeRecurse(0, I, Vec3s::Zero());
 
  383   std::shared_ptr<bv_node_vector_t> 
bvs;
 
  392   int refitTree(
bool bottomup);
 
  396   int refitTree_topdown();
 
  400   int refitTree_bottomup();
 
  403   int recursiveBuildTree(
int bv_id, 
unsigned int first_primitive,
 
  404                          unsigned int num_primitives);
 
  407   int recursiveRefitTree_bottomup(
int bv_id);
 
  413                                  const Vec3s& parent_c) {
 
  415     if (!bvs_[
static_cast<size_t>(bv_id)].isLeaf()) {
 
  416       makeParentRelativeRecurse(bvs_[
static_cast<size_t>(bv_id)].first_child,
 
  418                                 bvs_[
static_cast<size_t>(bv_id)].getCenter());
 
  420       makeParentRelativeRecurse(
 
  421           bvs_[
static_cast<size_t>(bv_id)].first_child + 1, parent_axes,
 
  422           bvs_[
static_cast<size_t>(bv_id)].getCenter());
 
  425     bvs_[
static_cast<size_t>(bv_id)].bv =
 
  426         translate(bvs_[
static_cast<size_t>(bv_id)].bv, -parent_c);
 
  432     if (other_ptr == 
nullptr) 
return false;
 
  436     if (!
res) 
return false;
 
  481     if (num_bvs != other.
num_bvs) 
return false;
 
  483     if ((!(bvs.get()) && other.
bvs.get()) || (bvs.get() && !(other.
bvs.get())))
 
  485     if (bvs.get() && other.
bvs.get()) {
 
  488       for (
unsigned int k = 0; k < num_bvs; ++k) {
 
  489         if (bvs_[k] != other_bvs_[k]) 
return false;
 
  501                                               const Vec3s& parent_c);
 
  505                                               const Vec3s& parent_c);
 
  510                                                  const Vec3s& parent_c);
 
  529 NODE_TYPE BVHModel<KDOP<16>>::getNodeType() 
const;
 
  532 NODE_TYPE BVHModel<KDOP<18>>::getNodeType() 
const;
 
  535 NODE_TYPE BVHModel<KDOP<24>>::getNodeType() 
const;
 
  
unsigned int num_bvs_allocated
unsigned int num_vertex_updated
void makeParentRelativeRecurse(int bv_id, Matrix3s &parent_axes, const Vec3s &parent_c)
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
BVHModelType
BVH model type.
std::shared_ptr< std::vector< Vec3s > > vertices
Geometry point data.
A base class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewe...
unsigned int num_bvs
Number of BV nodes in bounding volume hierarchy.
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
BVNode< BV > & getBV(unsigned int i)
Access the bv giving the its index.
unsigned int num_vertices_allocated
unsigned int getNumBVs() const
Get the number of bv in the BVH.
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
CoalScalar computeVolume() const
compute the volume
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...
unsigned int num_tris_allocated
A class describing the split rule that splits each BV node.
The geometry for the object for collision or distance computation.
@ BVH_MODEL_POINTCLOUD
triangle model
@ BVH_MODEL_TRIANGLES
unknown model type
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const CoalScalar tol=std::numeric_limits< CoalScalar >::epsilon() *100)
BVHModelType getModelType() const
Model type described by the instance.
shared_ptr< ConvexBase > convex
Convex<Triangle> representation of this object.
std::shared_ptr< std::vector< unsigned int > > primitive_indices
virtual ~BVHModelBase()
deconstruction, delete mesh data related.
static AABB translate(const AABB &aabb, const Vec3s &t)
translate the center of AABB by t
Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3, Eigen::RowMajor > MatrixX3s
BVHBuildState build_state
The state of BVH building process.
shared_ptr< BVSplitter< BV > > bv_splitter
Split rule to split one BV node into two children.
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
std::shared_ptr< bv_node_vector_t > bvs
Bounding volume hierarchy.
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
NODE_TYPE getNodeType() const
Get the BV type: default is unknown.
~BVHModel()
deconstruction, delete mesh data related.
std::shared_ptr< std::vector< Triangle > > tri_indices
Geometry triangle index data, will be NULL for point clouds.
virtual BVHModel< BV > * clone() const
Clone *this into a new BVHModel.
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
shared_ptr< BVFitter< BV > > bv_fitter
Fitting rule to fit a BV node to a set of geometry primitives.
virtual bool isEqual(const CollisionGeometry &_other) const
for ccd vertex update
BVHBuildState
States for BVH construction empty->begun->processed ->replace_begun->processed -> ....
void makeParentRelative()
This is a special acceleration: BVH_model default stores the BV's transform in world coordinate....
The class for the default algorithm fitting a bounding volume to a set of points.
unsigned int num_vertices
Number of points.
Vec3s computeCOM() const
compute center of mass
Triangle with 3 indices for points.
unsigned int num_tris
Number of triangles.
std::shared_ptr< std::vector< Vec3s > > prev_vertices
Geometry point data in previous frame.
Eigen::Matrix< Eigen::DenseIndex, Eigen::Dynamic, 3, Eigen::RowMajor > Matrixx3i
std::vector< BVNode< BV >, Eigen::aligned_allocator< BVNode< BV > >> bv_node_vector_t
OBJECT_TYPE getObjectType() const
Get the object type: it is a BVH.
hpp-fcl
Author(s): 
autogenerated on Fri Feb 14 2025 03:45:50