BV_splitter.cpp
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  * 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 
39 
40 namespace hpp {
41 namespace fcl {
42 
43 template <typename BV>
44 void computeSplitVector(const BV& bv, Vec3f& split_vector) {
45  split_vector = bv.axes.col(0);
46 }
47 
48 template <>
49 void computeSplitVector<kIOS>(const kIOS& bv, Vec3f& split_vector) {
50  /*
51  switch(bv.num_spheres)
52  {
53  case 1:
54  split_vector = Vec3f(1, 0, 0);
55  break;
56  case 3:
57  {
58  Vec3f v[3];
59  v[0] = bv.spheres[1].o - bv.spheres[0].o;
60  v[0].normalize();
61  generateCoordinateSystem(v[0], v[1], v[2]);
62  split_vector = v[1];
63  }
64  break;
65  case 5:
66  {
67  Vec3f v[2];
68  v[0] = bv.spheres[1].o - bv.spheres[0].o;
69  v[1] = bv.spheres[3].o - bv.spheres[0].o;
70  split_vector = v[0].cross(v[1]);
71  split_vector.normalize();
72  }
73  break;
74  default:
75  ;
76  }
77  */
78  split_vector = bv.obb.axes.col(0);
79 }
80 
81 template <>
82 void computeSplitVector<OBBRSS>(const OBBRSS& bv, Vec3f& split_vector) {
83  split_vector = bv.obb.axes.col(0);
84 }
85 
86 template <typename BV>
87 void computeSplitValue_bvcenter(const BV& bv, FCL_REAL& split_value) {
88  Vec3f center = bv.center();
89  split_value = center[0];
90 }
91 
92 template <typename BV>
93 void computeSplitValue_mean(const BV&, Vec3f* vertices, Triangle* triangles,
94  unsigned int* primitive_indices,
95  unsigned int num_primitives, BVHModelType type,
96  const Vec3f& split_vector, FCL_REAL& split_value) {
97  if (type == BVH_MODEL_TRIANGLES) {
98  Vec3f c(Vec3f::Zero());
99 
100  for (unsigned int i = 0; i < num_primitives; ++i) {
101  const Triangle& t = triangles[primitive_indices[i]];
102  const Vec3f& p1 = vertices[t[0]];
103  const Vec3f& p2 = vertices[t[1]];
104  const Vec3f& p3 = vertices[t[2]];
105 
106  c += p1 + p2 + p3;
107  }
108  split_value = c.dot(split_vector) / (3 * num_primitives);
109  } else if (type == BVH_MODEL_POINTCLOUD) {
110  FCL_REAL sum = 0;
111  for (unsigned int i = 0; i < num_primitives; ++i) {
112  const Vec3f& p = vertices[primitive_indices[i]];
113  sum += p.dot(split_vector);
114  }
115 
116  split_value = sum / num_primitives;
117  }
118 }
119 
120 template <typename BV>
121 void computeSplitValue_median(const BV&, Vec3f* vertices, Triangle* triangles,
122  unsigned int* primitive_indices,
123  unsigned int num_primitives, BVHModelType type,
124  const Vec3f& split_vector,
125  FCL_REAL& split_value) {
126  std::vector<FCL_REAL> proj(num_primitives);
127 
128  if (type == BVH_MODEL_TRIANGLES) {
129  for (unsigned int i = 0; i < num_primitives; ++i) {
130  const Triangle& t = triangles[primitive_indices[i]];
131  const Vec3f& p1 = vertices[t[0]];
132  const Vec3f& p2 = vertices[t[1]];
133  const Vec3f& p3 = vertices[t[2]];
134  Vec3f centroid3(p1[0] + p2[0] + p3[0], p1[1] + p2[1] + p3[1],
135  p1[2] + p2[2] + p3[2]);
136 
137  proj[i] = centroid3.dot(split_vector) / 3;
138  }
139  } else if (type == BVH_MODEL_POINTCLOUD) {
140  for (unsigned int i = 0; i < num_primitives; ++i) {
141  const Vec3f& p = vertices[primitive_indices[i]];
142  Vec3f v(p[0], p[1], p[2]);
143  proj[i] = v.dot(split_vector);
144  }
145  }
146 
147  std::sort(proj.begin(), proj.end());
148 
149  if (num_primitives % 2 == 1) {
150  split_value = proj[(num_primitives - 1) / 2];
151  } else {
152  split_value = (proj[num_primitives / 2] + proj[num_primitives / 2 - 1]) / 2;
153  }
154 }
155 
156 template <>
157 void BVSplitter<OBB>::computeRule_bvcenter(const OBB& bv, unsigned int*,
158  unsigned int) {
159  computeSplitVector<OBB>(bv, split_vector);
160  computeSplitValue_bvcenter<OBB>(bv, split_value);
161 }
162 
163 template <>
165  unsigned int* primitive_indices,
166  unsigned int num_primitives) {
167  computeSplitVector<OBB>(bv, split_vector);
168  computeSplitValue_mean<OBB>(bv, vertices, tri_indices, primitive_indices,
169  num_primitives, type, split_vector, split_value);
170 }
171 
172 template <>
174  unsigned int* primitive_indices,
175  unsigned int num_primitives) {
176  computeSplitVector<OBB>(bv, split_vector);
177  computeSplitValue_median<OBB>(bv, vertices, tri_indices, primitive_indices,
178  num_primitives, type, split_vector,
179  split_value);
180 }
181 
182 template <>
183 void BVSplitter<RSS>::computeRule_bvcenter(const RSS& bv, unsigned int*,
184  unsigned int) {
185  computeSplitVector<RSS>(bv, split_vector);
186  computeSplitValue_bvcenter<RSS>(bv, split_value);
187 }
188 
189 template <>
191  unsigned int* primitive_indices,
192  unsigned int num_primitives) {
193  computeSplitVector<RSS>(bv, split_vector);
194  computeSplitValue_mean<RSS>(bv, vertices, tri_indices, primitive_indices,
195  num_primitives, type, split_vector, split_value);
196 }
197 
198 template <>
200  unsigned int* primitive_indices,
201  unsigned int num_primitives) {
202  computeSplitVector<RSS>(bv, split_vector);
203  computeSplitValue_median<RSS>(bv, vertices, tri_indices, primitive_indices,
204  num_primitives, type, split_vector,
205  split_value);
206 }
207 
208 template <>
209 void BVSplitter<kIOS>::computeRule_bvcenter(const kIOS& bv, unsigned int*,
210  unsigned int) {
211  computeSplitVector<kIOS>(bv, split_vector);
212  computeSplitValue_bvcenter<kIOS>(bv, split_value);
213 }
214 
215 template <>
217  unsigned int* primitive_indices,
218  unsigned int num_primitives) {
219  computeSplitVector<kIOS>(bv, split_vector);
220  computeSplitValue_mean<kIOS>(bv, vertices, tri_indices, primitive_indices,
221  num_primitives, type, split_vector, split_value);
222 }
223 
224 template <>
226  unsigned int* primitive_indices,
227  unsigned int num_primitives) {
228  computeSplitVector<kIOS>(bv, split_vector);
229  computeSplitValue_median<kIOS>(bv, vertices, tri_indices, primitive_indices,
230  num_primitives, type, split_vector,
231  split_value);
232 }
233 
234 template <>
235 void BVSplitter<OBBRSS>::computeRule_bvcenter(const OBBRSS& bv, unsigned int*,
236  unsigned int) {
237  computeSplitVector<OBBRSS>(bv, split_vector);
238  computeSplitValue_bvcenter<OBBRSS>(bv, split_value);
239 }
240 
241 template <>
243  unsigned int* primitive_indices,
244  unsigned int num_primitives) {
245  computeSplitVector<OBBRSS>(bv, split_vector);
246  computeSplitValue_mean<OBBRSS>(bv, vertices, tri_indices, primitive_indices,
247  num_primitives, type, split_vector,
248  split_value);
249 }
250 
251 template <>
253  unsigned int* primitive_indices,
254  unsigned int num_primitives) {
255  computeSplitVector<OBBRSS>(bv, split_vector);
256  computeSplitValue_median<OBBRSS>(bv, vertices, tri_indices, primitive_indices,
257  num_primitives, type, split_vector,
258  split_value);
259 }
260 
261 template <>
262 bool BVSplitter<OBB>::apply(const Vec3f& q) const {
263  return split_vector.dot(Vec3f(q[0], q[1], q[2])) > split_value;
264 }
265 
266 template <>
267 bool BVSplitter<RSS>::apply(const Vec3f& q) const {
268  return split_vector.dot(Vec3f(q[0], q[1], q[2])) > split_value;
269 }
270 
271 template <>
272 bool BVSplitter<kIOS>::apply(const Vec3f& q) const {
273  return split_vector.dot(Vec3f(q[0], q[1], q[2])) > split_value;
274 }
275 
276 template <>
277 bool BVSplitter<OBBRSS>::apply(const Vec3f& q) const {
278  return split_vector.dot(Vec3f(q[0], q[1], q[2])) > split_value;
279 }
280 
281 template class BVSplitter<RSS>;
282 template class BVSplitter<OBBRSS>;
283 template class BVSplitter<OBB>;
284 template class BVSplitter<kIOS>;
285 
286 } // namespace fcl
287 
288 } // namespace hpp
tuple p1
Definition: octree.py:55
Main namespace.
t
void computeSplitVector< kIOS >(const kIOS &bv, Vec3f &split_vector)
Definition: BV_splitter.cpp:49
void computeRule_bvcenter(const BV &bv, unsigned int *, unsigned int)
Split algorithm 1: Split the node from center.
c
A class describing the kIOS collision structure, which is a set of spheres.
Definition: kIOS.h:53
void computeSplitValue_bvcenter(const BV &bv, FCL_REAL &split_value)
Definition: BV_splitter.cpp:87
list v
Definition: obb.py:45
void computeSplitValue_median(const BV &, Vec3f *vertices, Triangle *triangles, unsigned int *primitive_indices, unsigned int num_primitives, BVHModelType type, const Vec3f &split_vector, FCL_REAL &split_value)
unknown model type
Definition: BVH_internal.h:82
double FCL_REAL
Definition: data_types.h:65
A class for rectangle sphere-swept bounding volume.
Definition: BV/RSS.h:53
BVHModelType
BVH model type.
Definition: BVH_internal.h:80
Triangle with 3 indices for points.
Definition: data_types.h:96
bool apply(const Vec3f &q) const
Apply the split rule on a given point.
A class describing the split rule that splits each BV node.
Definition: BVH/BVH_model.h:59
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
void computeSplitVector(const BV &bv, Vec3f &split_vector)
Definition: BV_splitter.cpp:44
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: BV/OBBRSS.h:54
void computeRule_mean(const BV &bv, unsigned int *primitive_indices, unsigned int num_primitives)
Split algorithm 2: Split the node according to the mean of the data contained.
void computeRule_median(const BV &bv, unsigned int *primitive_indices, unsigned int num_primitives)
Split algorithm 3: Split the node according to the median of the data contained.
void computeSplitValue_mean(const BV &, Vec3f *vertices, Triangle *triangles, unsigned int *primitive_indices, unsigned int num_primitives, BVHModelType type, const Vec3f &split_vector, FCL_REAL &split_value)
Definition: BV_splitter.cpp:93
void computeSplitVector< OBBRSS >(const OBBRSS &bv, Vec3f &split_vector)
Definition: BV_splitter.cpp:82
Oriented bounding box class.


hpp-fcl
Author(s):
autogenerated on Fri Jun 2 2023 02:39:00