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-2016, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef FCL_BVH_MODEL_H
39 #define FCL_BVH_MODEL_H
40 
41 #include <vector>
42 #include <memory>
43 
44 #include "fcl/math/bv/OBB.h"
45 #include "fcl/math/bv/kDOP.h"
51 
52 namespace fcl
53 {
54 
56 template <typename BV>
57 class FCL_EXPORT BVHModel : public CollisionGeometry<typename BV::S>
58 {
59 public:
60 
61  using S = typename BV::S;
62 
64  BVHModelType getModelType() const;
65 
67  BVHModel();
68 
70  BVHModel(const BVHModel& other);
71 
73  ~BVHModel();
74 
77 
79  const BVNode<BV>& getBV(int id) const;
80 
82  BVNode<BV>& getBV(int id);
83 
85  int getNumBVs() const;
86 
88  OBJECT_TYPE getObjectType() const override;
89 
91  NODE_TYPE getNodeType() const override;
92 
94  void computeLocalAABB() override;
95 
97  int beginModel(int num_tris = 0, int num_vertices = 0);
98 
100  int addVertex(const Vector3<S>& p);
101 
103  int addTriangle(const Vector3<S>& p1, const Vector3<S>& p2, const Vector3<S>& p3);
104 
106  int addSubModel(const std::vector<Vector3<S>>& ps, const std::vector<Triangle>& ts);
107 
109  int addSubModel(const std::vector<Vector3<S>>& ps);
110 
112  int endModel();
113 
114 
116  int beginReplaceModel();
117 
119  int replaceVertex(const Vector3<S>& p);
120 
122  int replaceTriangle(const Vector3<S>& p1, const Vector3<S>& p2, const Vector3<S>& p3);
123 
125  int replaceSubModel(const std::vector<Vector3<S>>& ps);
126 
128  int endReplaceModel(bool refit = true, bool bottomup = true);
129 
130 
133  int beginUpdateModel();
134 
136  int updateVertex(const Vector3<S>& p);
137 
139  int updateTriangle(const Vector3<S>& p1, const Vector3<S>& p2, const Vector3<S>& p3);
140 
142  int updateSubModel(const std::vector<Vector3<S>>& ps);
143 
145  int endUpdateModel(bool refit = true, bool bottomup = true);
146 
148  int memUsage(int msg) const;
149 
152  void makeParentRelative();
153 
154  Vector3<S> computeCOM() const override;
155 
156  S computeVolume() const override;
157 
158  Matrix3<S> computeMomentofInertia() const override;
159 
160 public:
163 
166 
169 
171  int num_tris;
172 
175 
178 
180  std::shared_ptr<detail::BVSplitterBase<BV>> bv_splitter;
181 
183  std::shared_ptr<detail::BVFitterBase<BV>> bv_fitter;
184 
185 private:
186 
191  unsigned int* primitive_indices;
192 
195 
197  int num_bvs;
198 
200  int buildTree();
201 
203  int refitTree(bool bottomup);
204 
206  int refitTree_topdown();
207 
209  int refitTree_bottomup();
210 
212  int recursiveBuildTree(int bv_id, int first_primitive, int num_primitives);
213 
215  int recursiveRefitTree_bottomup(int bv_id);
216 
220  void makeParentRelativeRecurse(
221  int bv_id,
222  const Matrix3<S>& parent_axis,
223  const Vector3<S>& parent_c);
224 
225  template <typename, typename>
227 };
228 
229 } // namespace fcl
230 
232 
233 #endif
fcl::BVHModel::bv_splitter
std::shared_ptr< detail::BVSplitterBase< BV > > bv_splitter
Split rule to split one BV node into two children.
Definition: BVH_model.h:180
BVH_internal.h
BV_node.h
fcl::BVHModel::vertices
Vector3< S > * vertices
Geometry point data.
Definition: BVH_model.h:162
fcl::BVHModel::num_tris_allocated
int num_tris_allocated
Definition: BVH_model.h:187
fcl::BVHModel< OBB< S > >::S
typename OBB< S > ::S S
Definition: BVH_model.h:61
fcl::BVHBuildState
BVHBuildState
States for BVH construction empty->begun->processed ->replace_begun->processed -> ....
Definition: BVH_internal.h:50
fcl::BVHModelType
BVHModelType
BVH model type.
Definition: BVH_internal.h:75
fcl::Triangle
Triangle with 3 indices for points.
Definition: triangle.h:48
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
fcl::BVHModel::num_tris
int num_tris
Number of triangles.
Definition: BVH_model.h:171
fcl::BVHModel::num_vertex_updated
int num_vertex_updated
Definition: BVH_model.h:190
fcl::BVHModel::build_state
BVHBuildState build_state
The state of BVH building process.
Definition: BVH_model.h:177
fcl::Matrix3
Eigen::Matrix< S, 3, 3 > Matrix3
Definition: types.h:85
fcl::BVHModel::primitive_indices
unsigned int * primitive_indices
for ccd vertex update
Definition: BVH_model.h:191
fcl::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: collision_geometry.h:58
fcl::BVHModel::num_bvs
int num_bvs
Number of BV nodes in bounding volume hierarchy.
Definition: BVH_model.h:197
fcl::BVHModel::tri_indices
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Definition: BVH_model.h:165
fcl::BVNode
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Definition: BV_node.h:52
fcl::BVHModel::prev_vertices
Vector3< S > * prev_vertices
Geometry point data in previous frame.
Definition: BVH_model.h:168
fcl::MakeParentRelativeRecurseImpl
Definition: BVH_model-inl.h:1031
fcl::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: collision_geometry.h:50
fcl::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:57
BV_splitter.h
fcl::BVHModel::num_bvs_allocated
int num_bvs_allocated
Definition: BVH_model.h:189
kDOP.h
fcl::BVHModel::num_vertices
int num_vertices
Number of points.
Definition: BVH_model.h:174
fcl::BVHModel::bv_fitter
std::shared_ptr< detail::BVFitterBase< BV > > bv_fitter
Fitting rule to fit a BV node to a set of geometry primitives.
Definition: BVH_model.h:183
BVH_model-inl.h
OBB.h
fcl::BVHModel::num_vertices_allocated
int num_vertices_allocated
Definition: BVH_model.h:188
fcl::BVHModel::bvs
BVNode< BV > * bvs
Bounding volume hierarchy.
Definition: BVH_model.h:194
fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_geometry.h:53
collision_geometry.h
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
BV_fitter.h


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:48