BVH_utility.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 
41 
42 namespace hpp {
43 namespace fcl {
44 
45 namespace details {
46 template <typename BV>
47 BVHModel<BV>* BVHExtract(const BVHModel<BV>& model, const Transform3f& pose,
48  const AABB& _aabb) {
49  assert(model.getModelType() == BVH_MODEL_TRIANGLES);
50  const Matrix3f& q = pose.getRotation();
51  AABB aabb = translate(_aabb, -pose.getTranslation());
52 
53  Transform3f box_pose;
54  Box box;
55  constructBox(_aabb, box, box_pose);
56  box_pose = pose.inverseTimes(box_pose);
57 
58  GJKSolver gjk;
59 
60  // Check what triangles should be kept.
61  // TODO use the BV hierarchy
62  std::vector<bool> keep_vertex(model.num_vertices, false);
63  std::vector<bool> keep_tri(model.num_tris, false);
64  unsigned int ntri = 0;
65  for (unsigned int i = 0; i < model.num_tris; ++i) {
66  const Triangle& t = model.tri_indices[i];
67 
68  bool keep_this_tri =
69  keep_vertex[t[0]] || keep_vertex[t[1]] || keep_vertex[t[2]];
70 
71  if (!keep_this_tri) {
72  for (unsigned int j = 0; j < 3; ++j) {
73  if (aabb.contain(q * model.vertices[t[j]])) {
74  keep_this_tri = true;
75  break;
76  }
77  }
78  const Vec3f& p0 = model.vertices[t[0]];
79  const Vec3f& p1 = model.vertices[t[1]];
80  const Vec3f& p2 = model.vertices[t[2]];
81  Vec3f c1, c2, normal;
83  if (!keep_this_tri &&
84  gjk.shapeTriangleInteraction(box, box_pose, p0, p1, p2, Transform3f(),
85  distance, c1, c2, normal)) {
86  keep_this_tri = true;
87  }
88  }
89  if (keep_this_tri) {
90  keep_vertex[t[0]] = keep_vertex[t[1]] = keep_vertex[t[2]] = true;
91  keep_tri[i] = true;
92  ntri++;
93  }
94  }
95 
96  if (ntri == 0) return NULL;
97 
98  BVHModel<BV>* new_model(new BVHModel<BV>());
99  new_model->beginModel(ntri, std::min(ntri * 3, model.num_vertices));
100  std::vector<unsigned int> idxConversion(model.num_vertices);
101  assert(new_model->num_vertices == 0);
102  for (unsigned int i = 0; i < keep_vertex.size(); ++i) {
103  if (keep_vertex[i]) {
104  idxConversion[i] = new_model->num_vertices;
105  new_model->vertices[new_model->num_vertices] = model.vertices[i];
106  new_model->num_vertices++;
107  }
108  }
109  assert(new_model->num_tris == 0);
110  for (unsigned int i = 0; i < keep_tri.size(); ++i) {
111  if (keep_tri[i]) {
112  new_model->tri_indices[new_model->num_tris].set(
113  idxConversion[model.tri_indices[i][0]],
114  idxConversion[model.tri_indices[i][1]],
115  idxConversion[model.tri_indices[i][2]]);
116  new_model->num_tris++;
117  }
118  }
119  if (new_model->endModel() != BVH_OK) {
120  delete new_model;
121  return NULL;
122  }
123  return new_model;
124 }
125 } // namespace details
126 
127 template <>
129  const AABB& aabb) {
130  return details::BVHExtract(model, pose, aabb);
131 }
132 template <>
134  const AABB& aabb) {
135  return details::BVHExtract(model, pose, aabb);
136 }
137 template <>
139  const AABB& aabb) {
140  return details::BVHExtract(model, pose, aabb);
141 }
142 template <>
144  const AABB& aabb) {
145  return details::BVHExtract(model, pose, aabb);
146 }
147 template <>
149  const Transform3f& pose, const AABB& aabb) {
150  return details::BVHExtract(model, pose, aabb);
151 }
152 template <>
154  const Transform3f& pose, const AABB& aabb) {
155  return details::BVHExtract(model, pose, aabb);
156 }
157 template <>
159  const Transform3f& pose, const AABB& aabb) {
160  return details::BVHExtract(model, pose, aabb);
161 }
162 template <>
164  const Transform3f& pose, const AABB& aabb) {
165  return details::BVHExtract(model, pose, aabb);
166 }
167 
168 void getCovariance(Vec3f* ps, Vec3f* ps2, Triangle* ts, unsigned int* indices,
169  unsigned int n, Matrix3f& M) {
170  Vec3f S1(Vec3f::Zero());
171  Vec3f S2[3] = {Vec3f::Zero(), Vec3f::Zero(), Vec3f::Zero()};
172 
173  if (ts) {
174  for (unsigned int i = 0; i < n; ++i) {
175  const Triangle& t = (indices) ? ts[indices[i]] : ts[i];
176 
177  const Vec3f& p1 = ps[t[0]];
178  const Vec3f& p2 = ps[t[1]];
179  const Vec3f& p3 = ps[t[2]];
180 
181  S1[0] += (p1[0] + p2[0] + p3[0]);
182  S1[1] += (p1[1] + p2[1] + p3[1]);
183  S1[2] += (p1[2] + p2[2] + p3[2]);
184  S2[0][0] += (p1[0] * p1[0] + p2[0] * p2[0] + p3[0] * p3[0]);
185  S2[1][1] += (p1[1] * p1[1] + p2[1] * p2[1] + p3[1] * p3[1]);
186  S2[2][2] += (p1[2] * p1[2] + p2[2] * p2[2] + p3[2] * p3[2]);
187  S2[0][1] += (p1[0] * p1[1] + p2[0] * p2[1] + p3[0] * p3[1]);
188  S2[0][2] += (p1[0] * p1[2] + p2[0] * p2[2] + p3[0] * p3[2]);
189  S2[1][2] += (p1[1] * p1[2] + p2[1] * p2[2] + p3[1] * p3[2]);
190 
191  if (ps2) {
192  const Vec3f& p1 = ps2[t[0]];
193  const Vec3f& p2 = ps2[t[1]];
194  const Vec3f& p3 = ps2[t[2]];
195 
196  S1[0] += (p1[0] + p2[0] + p3[0]);
197  S1[1] += (p1[1] + p2[1] + p3[1]);
198  S1[2] += (p1[2] + p2[2] + p3[2]);
199 
200  S2[0][0] += (p1[0] * p1[0] + p2[0] * p2[0] + p3[0] * p3[0]);
201  S2[1][1] += (p1[1] * p1[1] + p2[1] * p2[1] + p3[1] * p3[1]);
202  S2[2][2] += (p1[2] * p1[2] + p2[2] * p2[2] + p3[2] * p3[2]);
203  S2[0][1] += (p1[0] * p1[1] + p2[0] * p2[1] + p3[0] * p3[1]);
204  S2[0][2] += (p1[0] * p1[2] + p2[0] * p2[2] + p3[0] * p3[2]);
205  S2[1][2] += (p1[1] * p1[2] + p2[1] * p2[2] + p3[1] * p3[2]);
206  }
207  }
208  } else {
209  for (unsigned int i = 0; i < n; ++i) {
210  const Vec3f& p = (indices) ? ps[indices[i]] : ps[i];
211  S1 += p;
212  S2[0][0] += (p[0] * p[0]);
213  S2[1][1] += (p[1] * p[1]);
214  S2[2][2] += (p[2] * p[2]);
215  S2[0][1] += (p[0] * p[1]);
216  S2[0][2] += (p[0] * p[2]);
217  S2[1][2] += (p[1] * p[2]);
218 
219  if (ps2) // another frame
220  {
221  const Vec3f& p = (indices) ? ps2[indices[i]] : ps2[i];
222  S1 += p;
223  S2[0][0] += (p[0] * p[0]);
224  S2[1][1] += (p[1] * p[1]);
225  S2[2][2] += (p[2] * p[2]);
226  S2[0][1] += (p[0] * p[1]);
227  S2[0][2] += (p[0] * p[2]);
228  S2[1][2] += (p[1] * p[2]);
229  }
230  }
231  }
232 
233  unsigned int n_points = ((ps2) ? 2 : 1) * ((ts) ? 3 : 1) * n;
234 
235  M(0, 0) = S2[0][0] - S1[0] * S1[0] / n_points;
236  M(1, 1) = S2[1][1] - S1[1] * S1[1] / n_points;
237  M(2, 2) = S2[2][2] - S1[2] * S1[2] / n_points;
238  M(0, 1) = S2[0][1] - S1[0] * S1[1] / n_points;
239  M(1, 2) = S2[1][2] - S1[1] * S1[2] / n_points;
240  M(0, 2) = S2[0][2] - S1[0] * S1[2] / n_points;
241  M(1, 0) = M(0, 1);
242  M(2, 0) = M(0, 2);
243  M(2, 1) = M(1, 2);
244 }
245 
250  unsigned int* indices, unsigned int n,
251  const Matrix3f& axes, Vec3f& origin,
252  FCL_REAL l[2], FCL_REAL& r) {
253  bool indirect_index = true;
254  if (!indices) indirect_index = false;
255 
256  unsigned int size_P = ((ps2) ? 2 : 1) * ((ts) ? 3 : 1) * n;
257 
258  FCL_REAL(*P)[3] = new FCL_REAL[size_P][3];
259 
260  int P_id = 0;
261 
262  if (ts) {
263  for (unsigned int i = 0; i < n; ++i) {
264  unsigned int index = indirect_index ? indices[i] : i;
265  const Triangle& t = ts[index];
266 
267  for (Triangle::index_type j = 0; j < 3; ++j) {
268  Triangle::index_type point_id = t[j];
269  const Vec3f& p = ps[point_id];
270  Vec3f v(p[0], p[1], p[2]);
271  P[P_id][0] = axes.col(0).dot(v);
272  P[P_id][1] = axes.col(1).dot(v);
273  P[P_id][2] = axes.col(2).dot(v);
274  P_id++;
275  }
276 
277  if (ps2) {
278  for (Triangle::index_type j = 0; j < 3; ++j) {
279  Triangle::index_type point_id = t[j];
280  const Vec3f& p = ps2[point_id];
281  // FIXME Is this right ?????
282  Vec3f v(p[0], p[1], p[2]);
283  P[P_id][0] = axes.col(0).dot(v);
284  P[P_id][1] = axes.col(0).dot(v);
285  P[P_id][2] = axes.col(1).dot(v);
286  P_id++;
287  }
288  }
289  }
290  } else {
291  for (unsigned int i = 0; i < n; ++i) {
292  unsigned int index = indirect_index ? indices[i] : i;
293 
294  const Vec3f& p = ps[index];
295  Vec3f v(p[0], p[1], p[2]);
296  P[P_id][0] = axes.col(0).dot(v);
297  P[P_id][1] = axes.col(1).dot(v);
298  P[P_id][2] = axes.col(2).dot(v);
299  P_id++;
300 
301  if (ps2) {
302  const Vec3f& v = ps2[index];
303  P[P_id][0] = axes.col(0).dot(v);
304  P[P_id][1] = axes.col(1).dot(v);
305  P[P_id][2] = axes.col(2).dot(v);
306  P_id++;
307  }
308  }
309  }
310 
311  FCL_REAL minx, maxx, miny, maxy, minz, maxz;
312 
313  FCL_REAL cz, radsqr;
314 
315  minz = maxz = P[0][2];
316 
317  for (unsigned int i = 1; i < size_P; ++i) {
318  FCL_REAL z_value = P[i][2];
319  if (z_value < minz)
320  minz = z_value;
321  else if (z_value > maxz)
322  maxz = z_value;
323  }
324 
325  r = (FCL_REAL)0.5 * (maxz - minz);
326  radsqr = r * r;
327  cz = (FCL_REAL)0.5 * (maxz + minz);
328 
329  // compute an initial norm of rectangle along x direction
330 
331  // find minx and maxx as starting points
332 
333  unsigned int minindex = 0, maxindex = 0;
334  FCL_REAL mintmp, maxtmp;
335  mintmp = maxtmp = P[0][0];
336 
337  for (unsigned int i = 1; i < size_P; ++i) {
338  FCL_REAL x_value = P[i][0];
339  if (x_value < mintmp) {
340  minindex = i;
341  mintmp = x_value;
342  } else if (x_value > maxtmp) {
343  maxindex = i;
344  maxtmp = x_value;
345  }
346  }
347 
348  FCL_REAL x, dz;
349  dz = P[minindex][2] - cz;
350  minx = P[minindex][0] + std::sqrt(std::max<FCL_REAL>(radsqr - dz * dz, 0));
351  dz = P[maxindex][2] - cz;
352  maxx = P[maxindex][0] - std::sqrt(std::max<FCL_REAL>(radsqr - dz * dz, 0));
353 
354  // grow minx/maxx
355 
356  for (unsigned int i = 0; i < size_P; ++i) {
357  if (P[i][0] < minx) {
358  dz = P[i][2] - cz;
359  x = P[i][0] + std::sqrt(std::max<FCL_REAL>(radsqr - dz * dz, 0));
360  if (x < minx) minx = x;
361  } else if (P[i][0] > maxx) {
362  dz = P[i][2] - cz;
363  x = P[i][0] - std::sqrt(std::max<FCL_REAL>(radsqr - dz * dz, 0));
364  if (x > maxx) maxx = x;
365  }
366  }
367 
368  // compute an initial norm of rectangle along y direction
369 
370  // find miny and maxy as starting points
371 
372  minindex = maxindex = 0;
373  mintmp = maxtmp = P[0][1];
374  for (unsigned int i = 1; i < size_P; ++i) {
375  FCL_REAL y_value = P[i][1];
376  if (y_value < mintmp) {
377  minindex = i;
378  mintmp = y_value;
379  } else if (y_value > maxtmp) {
380  maxindex = i;
381  maxtmp = y_value;
382  }
383  }
384 
385  FCL_REAL y;
386  dz = P[minindex][2] - cz;
387  miny = P[minindex][1] + std::sqrt(std::max<FCL_REAL>(radsqr - dz * dz, 0));
388  dz = P[maxindex][2] - cz;
389  maxy = P[maxindex][1] - std::sqrt(std::max<FCL_REAL>(radsqr - dz * dz, 0));
390 
391  // grow miny/maxy
392 
393  for (unsigned int i = 0; i < size_P; ++i) {
394  if (P[i][1] < miny) {
395  dz = P[i][2] - cz;
396  y = P[i][1] + std::sqrt(std::max<FCL_REAL>(radsqr - dz * dz, 0));
397  if (y < miny) miny = y;
398  } else if (P[i][1] > maxy) {
399  dz = P[i][2] - cz;
400  y = P[i][1] - std::sqrt(std::max<FCL_REAL>(radsqr - dz * dz, 0));
401  if (y > maxy) maxy = y;
402  }
403  }
404 
405  // corners may have some points which are not covered - grow lengths if
406  // necessary quite conservative (can be improved)
407  FCL_REAL dx, dy, u, t;
408  FCL_REAL a = std::sqrt((FCL_REAL)0.5);
409  for (unsigned int i = 0; i < size_P; ++i) {
410  if (P[i][0] > maxx) {
411  if (P[i][1] > maxy) {
412  dx = P[i][0] - maxx;
413  dy = P[i][1] - maxy;
414  u = dx * a + dy * a;
415  t = (a * u - dx) * (a * u - dx) + (a * u - dy) * (a * u - dy) +
416  (cz - P[i][2]) * (cz - P[i][2]);
417  u = u - std::sqrt(std::max<FCL_REAL>(radsqr - t, 0));
418  if (u > 0) {
419  maxx += u * a;
420  maxy += u * a;
421  }
422  } else if (P[i][1] < miny) {
423  dx = P[i][0] - maxx;
424  dy = P[i][1] - miny;
425  u = dx * a - dy * a;
426  t = (a * u - dx) * (a * u - dx) + (-a * u - dy) * (-a * u - dy) +
427  (cz - P[i][2]) * (cz - P[i][2]);
428  u = u - std::sqrt(std::max<FCL_REAL>(radsqr - t, 0));
429  if (u > 0) {
430  maxx += u * a;
431  miny -= u * a;
432  }
433  }
434  } else if (P[i][0] < minx) {
435  if (P[i][1] > maxy) {
436  dx = P[i][0] - minx;
437  dy = P[i][1] - maxy;
438  u = dy * a - dx * a;
439  t = (-a * u - dx) * (-a * u - dx) + (a * u - dy) * (a * u - dy) +
440  (cz - P[i][2]) * (cz - P[i][2]);
441  u = u - std::sqrt(std::max<FCL_REAL>(radsqr - t, 0));
442  if (u > 0) {
443  minx -= u * a;
444  maxy += u * a;
445  }
446  } else if (P[i][1] < miny) {
447  dx = P[i][0] - minx;
448  dy = P[i][1] - miny;
449  u = -dx * a - dy * a;
450  t = (-a * u - dx) * (-a * u - dx) + (-a * u - dy) * (-a * u - dy) +
451  (cz - P[i][2]) * (cz - P[i][2]);
452  u = u - std::sqrt(std::max<FCL_REAL>(radsqr - t, 0));
453  if (u > 0) {
454  minx -= u * a;
455  miny -= u * a;
456  }
457  }
458  }
459  }
460 
461  origin.noalias() = axes * Vec3f(minx, miny, cz);
462 
463  l[0] = std::max<FCL_REAL>(maxx - minx, 0);
464  l[1] = std::max<FCL_REAL>(maxy - miny, 0);
465 
466  delete[] P;
467 }
468 
472 static inline void getExtentAndCenter_pointcloud(Vec3f* ps, Vec3f* ps2,
473  unsigned int* indices,
474  unsigned int n, Matrix3f& axes,
475  Vec3f& center, Vec3f& extent) {
476  bool indirect_index = true;
477  if (!indices) indirect_index = false;
478 
479  FCL_REAL real_max = (std::numeric_limits<FCL_REAL>::max)();
480 
481  Vec3f min_coord(real_max, real_max, real_max);
482  Vec3f max_coord(-real_max, -real_max, -real_max);
483 
484  for (unsigned int i = 0; i < n; ++i) {
485  unsigned int index = indirect_index ? indices[i] : i;
486 
487  const Vec3f& p = ps[index];
488  Vec3f proj(axes.transpose() * p);
489 
490  for (int j = 0; j < 3; ++j) {
491  if (proj[j] > max_coord[j]) max_coord[j] = proj[j];
492  if (proj[j] < min_coord[j]) min_coord[j] = proj[j];
493  }
494 
495  if (ps2) {
496  const Vec3f& v = ps2[index];
497  proj.noalias() = axes.transpose() * v;
498 
499  for (int j = 0; j < 3; ++j) {
500  if (proj[j] > max_coord[j]) max_coord[j] = proj[j];
501  if (proj[j] < min_coord[j]) min_coord[j] = proj[j];
502  }
503  }
504  }
505 
506  center.noalias() = axes * (max_coord + min_coord) / 2;
507 
508  extent.noalias() = (max_coord - min_coord) / 2;
509 }
510 
514 static inline void getExtentAndCenter_mesh(Vec3f* ps, Vec3f* ps2, Triangle* ts,
515  unsigned int* indices,
516  unsigned int n, Matrix3f& axes,
517  Vec3f& center, Vec3f& extent) {
518  bool indirect_index = true;
519  if (!indices) indirect_index = false;
520 
521  FCL_REAL real_max = (std::numeric_limits<FCL_REAL>::max)();
522 
523  Vec3f min_coord(real_max, real_max, real_max);
524  Vec3f max_coord(-real_max, -real_max, -real_max);
525 
526  for (unsigned int i = 0; i < n; ++i) {
527  unsigned int index = indirect_index ? indices[i] : i;
528  const Triangle& t = ts[index];
529 
530  for (Triangle::index_type j = 0; j < 3; ++j) {
531  Triangle::index_type point_id = t[j];
532  const Vec3f& p = ps[point_id];
533  Vec3f proj(axes.transpose() * p);
534 
535  for (int k = 0; k < 3; ++k) {
536  if (proj[k] > max_coord[k]) max_coord[k] = proj[k];
537  if (proj[k] < min_coord[k]) min_coord[k] = proj[k];
538  }
539  }
540 
541  if (ps2) {
542  for (Triangle::index_type j = 0; j < 3; ++j) {
543  Triangle::index_type point_id = t[j];
544  const Vec3f& p = ps2[point_id];
545  Vec3f proj(axes.transpose() * p);
546 
547  for (int k = 0; k < 3; ++k) {
548  if (proj[k] > max_coord[k]) max_coord[k] = proj[k];
549  if (proj[k] < min_coord[k]) min_coord[k] = proj[k];
550  }
551  }
552  }
553  }
554 
555  Vec3f o((max_coord + min_coord) / 2);
556 
557  center.noalias() = axes * o;
558 
559  extent.noalias() = (max_coord - min_coord) / 2;
560 }
561 
563  unsigned int* indices, unsigned int n, Matrix3f& axes,
564  Vec3f& center, Vec3f& extent) {
565  if (ts)
566  getExtentAndCenter_mesh(ps, ps2, ts, indices, n, axes, center, extent);
567  else
568  getExtentAndCenter_pointcloud(ps, ps2, indices, n, axes, center, extent);
569 }
570 
571 void circumCircleComputation(const Vec3f& a, const Vec3f& b, const Vec3f& c,
572  Vec3f& center, FCL_REAL& radius) {
573  Vec3f e1 = a - c;
574  Vec3f e2 = b - c;
575  FCL_REAL e1_len2 = e1.squaredNorm();
576  FCL_REAL e2_len2 = e2.squaredNorm();
577  Vec3f e3 = e1.cross(e2);
578  FCL_REAL e3_len2 = e3.squaredNorm();
579  radius = e1_len2 * e2_len2 * (e1 - e2).squaredNorm() / e3_len2;
580  radius = std::sqrt(radius) * 0.5;
581 
582  center = (e2 * e1_len2 - e1 * e2_len2).cross(e3) * (0.5 * 1 / e3_len2) + c;
583 }
584 
585 static inline FCL_REAL maximumDistance_mesh(Vec3f* ps, Vec3f* ps2, Triangle* ts,
586  unsigned int* indices,
587  unsigned int n,
588  const Vec3f& query) {
589  bool indirect_index = true;
590  if (!indices) indirect_index = false;
591 
592  FCL_REAL maxD = 0;
593  for (unsigned int i = 0; i < n; ++i) {
594  unsigned int index = indirect_index ? indices[i] : i;
595  const Triangle& t = ts[index];
596 
597  for (Triangle::index_type j = 0; j < 3; ++j) {
598  Triangle::index_type point_id = t[j];
599  const Vec3f& p = ps[point_id];
600 
601  FCL_REAL d = (p - query).squaredNorm();
602  if (d > maxD) maxD = d;
603  }
604 
605  if (ps2) {
606  for (Triangle::index_type j = 0; j < 3; ++j) {
607  Triangle::index_type point_id = t[j];
608  const Vec3f& p = ps2[point_id];
609 
610  FCL_REAL d = (p - query).squaredNorm();
611  if (d > maxD) maxD = d;
612  }
613  }
614  }
615 
616  return std::sqrt(maxD);
617 }
618 
620  unsigned int* indices,
621  unsigned int n,
622  const Vec3f& query) {
623  bool indirect_index = true;
624  if (!indices) indirect_index = false;
625 
626  FCL_REAL maxD = 0;
627  for (unsigned int i = 0; i < n; ++i) {
628  unsigned int index = indirect_index ? indices[i] : i;
629 
630  const Vec3f& p = ps[index];
631  FCL_REAL d = (p - query).squaredNorm();
632  if (d > maxD) maxD = d;
633 
634  if (ps2) {
635  const Vec3f& v = ps2[index];
636  FCL_REAL d = (v - query).squaredNorm();
637  if (d > maxD) maxD = d;
638  }
639  }
640 
641  return std::sqrt(maxD);
642 }
643 
645  unsigned int* indices, unsigned int n,
646  const Vec3f& query) {
647  if (ts)
648  return maximumDistance_mesh(ps, ps2, ts, indices, n, query);
649  else
650  return maximumDistance_pointcloud(ps, ps2, indices, n, query);
651 }
652 
653 } // namespace fcl
654 
655 } // namespace hpp
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
q
KDOP class describes the KDOP collision structures. K is set as the template parameter, which should be 16, 18, or 24 The KDOP structure is defined by some pairs of parallel planes defined by some axes. For K = 16, the planes are 6 AABB planes and 10 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 8 (0,-1,0) and (0,1,0) -> indices 1 and 9 (0,0,-1) and (0,0,1) -> indices 2 and 10 (-1,-1,0) and (1,1,0) -> indices 3 and 11 (-1,0,-1) and (1,0,1) -> indices 4 and 12 (0,-1,-1) and (0,1,1) -> indices 5 and 13 (-1,1,0) and (1,-1,0) -> indices 6 and 14 (-1,0,1) and (1,0,-1) -> indices 7 and 15 For K = 18, the planes are 6 AABB planes and 12 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 9 (0,-1,0) and (0,1,0) -> indices 1 and 10 (0,0,-1) and (0,0,1) -> indices 2 and 11 (-1,-1,0) and (1,1,0) -> indices 3 and 12 (-1,0,-1) and (1,0,1) -> indices 4 and 13 (0,-1,-1) and (0,1,1) -> indices 5 and 14 (-1,1,0) and (1,-1,0) -> indices 6 and 15 (-1,0,1) and (1,0,-1) -> indices 7 and 16 (0,-1,1) and (0,1,-1) -> indices 8 and 17 For K = 18, the planes are 6 AABB planes and 18 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 12 (0,-1,0) and (0,1,0) -> indices 1 and 13 (0,0,-1) and (0,0,1) -> indices 2 and 14 (-1,-1,0) and (1,1,0) -> indices 3 and 15 (-1,0,-1) and (1,0,1) -> indices 4 and 16 (0,-1,-1) and (0,1,1) -> indices 5 and 17 (-1,1,0) and (1,-1,0) -> indices 6 and 18 (-1,0,1) and (1,0,-1) -> indices 7 and 19 (0,-1,1) and (0,1,-1) -> indices 8 and 20 (-1, -1, 1) and (1, 1, -1) –> indices 9 and 21 (-1, 1, -1) and (1, -1, 1) –> indices 10 and 22 (1, -1, -1) and (-1, 1, 1) –> indices 11 and 23.
Definition: kDOP.h:92
y
tuple p1
Definition: octree.py:55
Main namespace.
t
static FCL_REAL maximumDistance_pointcloud(Vec3f *ps, Vec3f *ps2, unsigned int *indices, unsigned int n, const Vec3f &query)
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
Definition: data_types.h:68
HPP_FCL_DLLAPI FCL_REAL maximumDistance(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Vec3f &query)
Compute the maximum distance from a given center point to a point cloud.
static FCL_REAL maximumDistance_mesh(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Vec3f &query)
HPP_FCL_DLLAPI void circumCircleComputation(const Vec3f &a, const Vec3f &b, const Vec3f &c, Vec3f &center, FCL_REAL &radius)
Compute the center and radius for a triangle&#39;s circumcircle.
HPP_FCL_DLLAPI void getRadiusAndOriginAndRectangleSize(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Matrix3f &axes, Vec3f &origin, FCL_REAL l[2], FCL_REAL &r)
Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises.
unsigned int num_vertices
Number of points.
Definition: BVH/BVH_model.h:78
P
list v
Definition: obb.py:45
unknown model type
Definition: BVH_internal.h:82
std::size_t index_type
Definition: data_types.h:98
static void getExtentAndCenter_pointcloud(Vec3f *ps, Vec3f *ps2, unsigned int *indices, unsigned int n, Matrix3f &axes, Vec3f &center, Vec3f &extent)
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes...
HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:181
HPP_FCL_DLLAPI void getCovariance(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3f &M)
Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to poin...
HPP_FCL_DLLAPI void getExtentAndCenter(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3f &axes, Vec3f &center, Vec3f &extent)
Compute the bounding volume extent and center for a set or subset of points, given the BV axises...
Triangle * tri_indices
Geometry triangle index data, will be NULL for point clouds.
Definition: BVH/BVH_model.h:69
Vec3f * vertices
Geometry point data.
Definition: BVH/BVH_model.h:66
unsigned int num_tris
Number of triangles.
Definition: BVH/BVH_model.h:75
double FCL_REAL
Definition: data_types.h:65
int beginModel(unsigned int num_tris=0, unsigned int num_vertices=0)
Begin a new BVH model.
Definition: BVH_model.cpp:170
x
Center at zero point, axis aligned box.
BVHModelType getModelType() const
Model type described by the instance.
Definition: BVH/BVH_model.h:87
const Vec3f & getTranslation() const
get translation
Definition: transform.h:100
BVHModel< BV > * BVHExtract(const BVHModel< BV > &model, const Transform3f &pose, const AABB &_aabb)
Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is con...
Definition: BVH_utility.cpp:47
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: BV/AABB.h:54
static AABB translate(const AABB &aabb, const Vec3f &t)
translate the center of AABB by t
Definition: BV/AABB.h:226
Transform3f inverseTimes(const Transform3f &other) const
inverse the transform and multiply with another
Definition: transform.h:170
Triangle with 3 indices for points.
Definition: data_types.h:96
Definition: doc/gjk.py:1
bool shapeTriangleInteraction(const S &s, const Transform3f &tf1, const Vec3f &P1, const Vec3f &P2, const Vec3f &P3, const Transform3f &tf2, FCL_REAL &distance, Vec3f &p1, Vec3f &p2, Vec3f &normal) const
intersection checking between one shape and a triangle with transformation
Definition: narrowphase.h:178
bool contain(const Vec3f &p) const
Check whether the AABB contains a point.
Definition: BV/AABB.h:101
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Definition: narrowphase.h:54
c2
list a
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
static void getExtentAndCenter_mesh(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3f &axes, Vec3f &center, Vec3f &extent)
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes...
HPP_FCL_DLLAPI void constructBox(const AABB &bv, Box &box, Transform3f &tf)
construct a box shape (with a configuration) from a given bounding volume
const Matrix3f & getRotation() const
get rotation
Definition: transform.h:109
int endModel()
End BVH model construction, will build the bounding volume hierarchy.
Definition: BVH_model.cpp:473


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