OBB.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 
38 #include "coal/BV/OBB.h"
39 #include "coal/BVH/BVH_utility.h"
40 #include "coal/math/transform.h"
41 #include "coal/collision_data.h"
42 #include "coal/internal/tools.h"
43 
44 #include <iostream>
45 #include <limits>
46 
47 namespace coal {
48 
50 inline void computeVertices(const OBB& b, Vec3s vertices[8]) {
51  Matrix3s extAxes(b.axes * b.extent.asDiagonal());
52  vertices[0].noalias() = b.To + extAxes * Vec3s(-1, -1, -1);
53  vertices[1].noalias() = b.To + extAxes * Vec3s(1, -1, -1);
54  vertices[2].noalias() = b.To + extAxes * Vec3s(1, 1, -1);
55  vertices[3].noalias() = b.To + extAxes * Vec3s(-1, 1, -1);
56  vertices[4].noalias() = b.To + extAxes * Vec3s(-1, -1, 1);
57  vertices[5].noalias() = b.To + extAxes * Vec3s(1, -1, 1);
58  vertices[6].noalias() = b.To + extAxes * Vec3s(1, 1, 1);
59  vertices[7].noalias() = b.To + extAxes * Vec3s(-1, 1, 1);
60 }
61 
63 inline OBB merge_largedist(const OBB& b1, const OBB& b2) {
64  OBB b;
65  Vec3s vertex[16];
66  computeVertices(b1, vertex);
67  computeVertices(b2, vertex + 8);
68  Matrix3s M;
69  Vec3s E[3];
70  CoalScalar s[3] = {0, 0, 0};
71 
72  // obb axes
73  b.axes.col(0).noalias() = (b1.To - b2.To).normalized();
74 
75  Vec3s vertex_proj[16];
76  for (int i = 0; i < 16; ++i)
77  vertex_proj[i].noalias() =
78  vertex[i] - b.axes.col(0) * vertex[i].dot(b.axes.col(0));
79 
80  getCovariance(vertex_proj, NULL, NULL, NULL, 16, M);
81  eigen(M, s, E);
82 
83  int min, mid, max;
84  if (s[0] > s[1]) {
85  max = 0;
86  min = 1;
87  } else {
88  min = 0;
89  max = 1;
90  }
91  if (s[2] < s[min]) {
92  mid = min;
93  min = 2;
94  } else if (s[2] > s[max]) {
95  mid = max;
96  max = 2;
97  } else {
98  mid = 2;
99  }
100 
101  b.axes.col(1) << E[0][max], E[1][max], E[2][max];
102  b.axes.col(2) << E[0][mid], E[1][mid], E[2][mid];
103 
104  // set obb centers and extensions
105  Vec3s center, extent;
106  getExtentAndCenter(vertex, NULL, NULL, NULL, 16, b.axes, center, extent);
107 
108  b.To.noalias() = center;
109  b.extent.noalias() = extent;
110 
111  return b;
112 }
113 
115 inline OBB merge_smalldist(const OBB& b1, const OBB& b2) {
116  OBB b;
117  b.To = (b1.To + b2.To) * 0.5;
118  Quatf q0(b1.axes), q1(b2.axes);
119  if (q0.dot(q1) < 0) q1.coeffs() *= -1;
120 
121  Quatf q((q0.coeffs() + q1.coeffs()).normalized());
122  b.axes = q.toRotationMatrix();
123 
124  Vec3s vertex[8], diff;
125  CoalScalar real_max = (std::numeric_limits<CoalScalar>::max)();
126  Vec3s pmin(real_max, real_max, real_max);
127  Vec3s pmax(-real_max, -real_max, -real_max);
128 
129  computeVertices(b1, vertex);
130  for (int i = 0; i < 8; ++i) {
131  diff = vertex[i] - b.To;
132  for (int j = 0; j < 3; ++j) {
133  CoalScalar dot = diff.dot(b.axes.col(j));
134  if (dot > pmax[j])
135  pmax[j] = dot;
136  else if (dot < pmin[j])
137  pmin[j] = dot;
138  }
139  }
140 
141  computeVertices(b2, vertex);
142  for (int i = 0; i < 8; ++i) {
143  diff = vertex[i] - b.To;
144  for (int j = 0; j < 3; ++j) {
145  CoalScalar dot = diff.dot(b.axes.col(j));
146  if (dot > pmax[j])
147  pmax[j] = dot;
148  else if (dot < pmin[j])
149  pmin[j] = dot;
150  }
151  }
152 
153  for (int j = 0; j < 3; ++j) {
154  b.To.noalias() += (b.axes.col(j) * (0.5 * (pmax[j] + pmin[j])));
155  b.extent[j] = 0.5 * (pmax[j] - pmin[j]);
156  }
157 
158  return b;
159 }
160 
161 bool obbDisjoint(const Matrix3s& B, const Vec3s& T, const Vec3s& a,
162  const Vec3s& b) {
163  CoalScalar t, s;
164  const CoalScalar reps = 1e-6;
165 
166  Matrix3s Bf(B.array().abs() + reps);
167  // Bf += reps;
168 
169  // if any of these tests are one-sided, then the polyhedra are disjoint
170 
171  // A1 x A2 = A0
172  t = ((T[0] < 0.0) ? -T[0] : T[0]);
173 
174  // if(t > (a[0] + Bf.dotX(b)))
175  if (t > (a[0] + Bf.row(0).dot(b))) return true;
176 
177  // B1 x B2 = B0
178  // s = B.transposeDotX(T);
179  s = B.col(0).dot(T);
180  t = ((s < 0.0) ? -s : s);
181 
182  // if(t > (b[0] + Bf.transposeDotX(a)))
183  if (t > (b[0] + Bf.col(0).dot(a))) return true;
184 
185  // A2 x A0 = A1
186  t = ((T[1] < 0.0) ? -T[1] : T[1]);
187 
188  // if(t > (a[1] + Bf.dotY(b)))
189  if (t > (a[1] + Bf.row(1).dot(b))) return true;
190 
191  // A0 x A1 = A2
192  t = ((T[2] < 0.0) ? -T[2] : T[2]);
193 
194  // if(t > (a[2] + Bf.dotZ(b)))
195  if (t > (a[2] + Bf.row(2).dot(b))) return true;
196 
197  // B2 x B0 = B1
198  // s = B.transposeDotY(T);
199  s = B.col(1).dot(T);
200  t = ((s < 0.0) ? -s : s);
201 
202  // if(t > (b[1] + Bf.transposeDotY(a)))
203  if (t > (b[1] + Bf.col(1).dot(a))) return true;
204 
205  // B0 x B1 = B2
206  // s = B.transposeDotZ(T);
207  s = B.col(2).dot(T);
208  t = ((s < 0.0) ? -s : s);
209 
210  // if(t > (b[2] + Bf.transposeDotZ(a)))
211  if (t > (b[2] + Bf.col(2).dot(a))) return true;
212 
213  // A0 x B0
214  s = T[2] * B(1, 0) - T[1] * B(2, 0);
215  t = ((s < 0.0) ? -s : s);
216 
217  if (t >
218  (a[1] * Bf(2, 0) + a[2] * Bf(1, 0) + b[1] * Bf(0, 2) + b[2] * Bf(0, 1)))
219  return true;
220 
221  // A0 x B1
222  s = T[2] * B(1, 1) - T[1] * B(2, 1);
223  t = ((s < 0.0) ? -s : s);
224 
225  if (t >
226  (a[1] * Bf(2, 1) + a[2] * Bf(1, 1) + b[0] * Bf(0, 2) + b[2] * Bf(0, 0)))
227  return true;
228 
229  // A0 x B2
230  s = T[2] * B(1, 2) - T[1] * B(2, 2);
231  t = ((s < 0.0) ? -s : s);
232 
233  if (t >
234  (a[1] * Bf(2, 2) + a[2] * Bf(1, 2) + b[0] * Bf(0, 1) + b[1] * Bf(0, 0)))
235  return true;
236 
237  // A1 x B0
238  s = T[0] * B(2, 0) - T[2] * B(0, 0);
239  t = ((s < 0.0) ? -s : s);
240 
241  if (t >
242  (a[0] * Bf(2, 0) + a[2] * Bf(0, 0) + b[1] * Bf(1, 2) + b[2] * Bf(1, 1)))
243  return true;
244 
245  // A1 x B1
246  s = T[0] * B(2, 1) - T[2] * B(0, 1);
247  t = ((s < 0.0) ? -s : s);
248 
249  if (t >
250  (a[0] * Bf(2, 1) + a[2] * Bf(0, 1) + b[0] * Bf(1, 2) + b[2] * Bf(1, 0)))
251  return true;
252 
253  // A1 x B2
254  s = T[0] * B(2, 2) - T[2] * B(0, 2);
255  t = ((s < 0.0) ? -s : s);
256 
257  if (t >
258  (a[0] * Bf(2, 2) + a[2] * Bf(0, 2) + b[0] * Bf(1, 1) + b[1] * Bf(1, 0)))
259  return true;
260 
261  // A2 x B0
262  s = T[1] * B(0, 0) - T[0] * B(1, 0);
263  t = ((s < 0.0) ? -s : s);
264 
265  if (t >
266  (a[0] * Bf(1, 0) + a[1] * Bf(0, 0) + b[1] * Bf(2, 2) + b[2] * Bf(2, 1)))
267  return true;
268 
269  // A2 x B1
270  s = T[1] * B(0, 1) - T[0] * B(1, 1);
271  t = ((s < 0.0) ? -s : s);
272 
273  if (t >
274  (a[0] * Bf(1, 1) + a[1] * Bf(0, 1) + b[0] * Bf(2, 2) + b[2] * Bf(2, 0)))
275  return true;
276 
277  // A2 x B2
278  s = T[1] * B(0, 2) - T[0] * B(1, 2);
279  t = ((s < 0.0) ? -s : s);
280 
281  if (t >
282  (a[0] * Bf(1, 2) + a[1] * Bf(0, 2) + b[0] * Bf(2, 1) + b[1] * Bf(2, 0)))
283  return true;
284 
285  return false;
286 }
287 
288 namespace internal {
289 inline CoalScalar obbDisjoint_check_A_axis(const Vec3s& T, const Vec3s& a,
290  const Vec3s& b, const Matrix3s& Bf) {
291  // |T| - |B| * b - a
292  Vec3s AABB_corner(T.cwiseAbs() - a);
293  AABB_corner.noalias() -= Bf * b;
294  return AABB_corner.array().max(CoalScalar(0)).matrix().squaredNorm();
295 }
296 
298  const Vec3s& a, const Vec3s& b,
299  const Matrix3s& Bf) {
300  // Bf = |B|
301  // | B^T T| - Bf^T * a - b
302  CoalScalar s, t = 0;
303  s = std::abs(B.col(0).dot(T)) - Bf.col(0).dot(a) - b[0];
304  if (s > 0) t += s * s;
305  s = std::abs(B.col(1).dot(T)) - Bf.col(1).dot(a) - b[1];
306  if (s > 0) t += s * s;
307  s = std::abs(B.col(2).dot(T)) - Bf.col(2).dot(a) - b[2];
308  if (s > 0) t += s * s;
309  return t;
310 }
311 
312 template <int ib, int jb = (ib + 1) % 3, int kb = (ib + 2) % 3>
313 struct COAL_LOCAL obbDisjoint_check_Ai_cross_Bi{static inline bool run(
314  int ia, int ja, int ka, const Matrix3s& B, const Vec3s& T, const Vec3s& a,
315  const Vec3s& b, const Matrix3s& Bf, const CoalScalar& breakDistance2,
316  CoalScalar& squaredLowerBoundDistance){CoalScalar sinus2 =
317  1 - Bf(ia, ib) * Bf(ia, ib);
318 if (sinus2 < 1e-6) return false;
319 
320 const CoalScalar s = T[ka] * B(ja, ib) - T[ja] * B(ka, ib);
321 
322 const CoalScalar diff = fabs(s) - (a[ja] * Bf(ka, ib) + a[ka] * Bf(ja, ib) +
323  b[jb] * Bf(ia, kb) + b[kb] * Bf(ia, jb));
324 // We need to divide by the norm || Aia x Bib ||
325 // As ||Aia|| = ||Bib|| = 1, (Aia | Bib)^2 = cosine^2
326 if (diff > 0) {
327  squaredLowerBoundDistance = diff * diff / sinus2;
328  if (squaredLowerBoundDistance > breakDistance2) {
329  return true;
330  }
331 }
332 return false;
333 } // namespace internal
334 }; // namespace coal
335 } // namespace internal
336 
337 // B, T orientation and position of 2nd OBB in frame of 1st OBB,
338 // a extent of 1st OBB,
339 // b extent of 2nd OBB.
340 //
341 // This function tests whether bounding boxes should be broken down.
342 //
344  const Vec3s& a_, const Vec3s& b_,
345  const CollisionRequest& request,
346  CoalScalar& squaredLowerBoundDistance) {
347  assert(request.security_margin >
348  -2 * (std::min)(a_.minCoeff(), b_.minCoeff()) -
350  "A negative security margin could not be lower than the OBB extent.");
351  // const CoalScalar breakDistance(request.break_distance +
352  // request.security_margin);
353  const CoalScalar breakDistance2 =
354  request.break_distance * request.break_distance;
355 
356  Matrix3s Bf(B.cwiseAbs());
357  const Vec3s a((a_ + Vec3s::Constant(request.security_margin / 2))
358  .array()
359  .max(CoalScalar(0)));
360  const Vec3s b((b_ + Vec3s::Constant(request.security_margin / 2))
361  .array()
362  .max(CoalScalar(0)));
363 
364  // Corner of b axis aligned bounding box the closest to the origin
365  squaredLowerBoundDistance = internal::obbDisjoint_check_A_axis(T, a, b, Bf);
366  if (squaredLowerBoundDistance > breakDistance2) return true;
367 
368  squaredLowerBoundDistance =
370  if (squaredLowerBoundDistance > breakDistance2) return true;
371 
372  // Ai x Bj
373  int ja = 1, ka = 2;
374  for (int ia = 0; ia < 3; ++ia) {
376  ia, ja, ka, B, T, a, b, Bf, breakDistance2,
377  squaredLowerBoundDistance))
378  return true;
380  ia, ja, ka, B, T, a, b, Bf, breakDistance2,
381  squaredLowerBoundDistance))
382  return true;
384  ia, ja, ka, B, T, a, b, Bf, breakDistance2,
385  squaredLowerBoundDistance))
386  return true;
387  ja = ka;
388  ka = ia;
389  }
390 
391  return false;
392 }
393 
394 bool OBB::overlap(const OBB& other) const {
398  Vec3s T(axes.transpose() * (other.To - To));
399  Matrix3s R(axes.transpose() * other.axes);
400 
401  return !obbDisjoint(R, T, extent, other.extent);
402 }
403 
404 bool OBB::overlap(const OBB& other, const CollisionRequest& request,
405  CoalScalar& sqrDistLowerBound) const {
409  // Vec3s t = other.To - To; // T2 - T1
410  // Vec3s T(t.dot(axis[0]), t.dot(axis[1]), t.dot(axis[2])); // R1'(T2-T1)
411  // Matrix3s R(axis[0].dot(other.axis[0]), axis[0].dot(other.axis[1]),
412  // axis[0].dot(other.axis[2]),
413  // axis[1].dot(other.axis[0]), axis[1].dot(other.axis[1]),
414  // axis[1].dot(other.axis[2]),
415  // axis[2].dot(other.axis[0]), axis[2].dot(other.axis[1]),
416  // axis[2].dot(other.axis[2]));
417  Vec3s T(axes.transpose() * (other.To - To));
418  Matrix3s R(axes.transpose() * other.axes);
419 
420  return !obbDisjointAndLowerBoundDistance(R, T, extent, other.extent, request,
421  sqrDistLowerBound);
422 }
423 
424 bool OBB::contain(const Vec3s& p) const {
425  Vec3s local_p(p - To);
426  CoalScalar proj = local_p.dot(axes.col(0));
427  if ((proj > extent[0]) || (proj < -extent[0])) return false;
428 
429  proj = local_p.dot(axes.col(1));
430  if ((proj > extent[1]) || (proj < -extent[1])) return false;
431 
432  proj = local_p.dot(axes.col(2));
433  if ((proj > extent[2]) || (proj < -extent[2])) return false;
434 
435  return true;
436 }
437 
439  OBB bvp;
440  bvp.To = p;
441  bvp.axes.noalias() = axes;
442  bvp.extent.setZero();
443 
444  *this += bvp;
445  return *this;
446 }
447 
448 OBB OBB::operator+(const OBB& other) const {
449  Vec3s center_diff = To - other.To;
450  CoalScalar max_extent = std::max(std::max(extent[0], extent[1]), extent[2]);
451  CoalScalar max_extent2 =
452  std::max(std::max(other.extent[0], other.extent[1]), other.extent[2]);
453  if (center_diff.norm() > 2 * (max_extent + max_extent2)) {
454  return merge_largedist(*this, other);
455  } else {
456  return merge_smalldist(*this, other);
457  }
458 }
459 
460 CoalScalar OBB::distance(const OBB& /*other*/, Vec3s* /*P*/,
461  Vec3s* /*Q*/) const {
462  std::cerr << "OBB distance not implemented!" << std::endl;
463  return 0.0;
464 }
465 
466 bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1,
467  const OBB& b2) {
468  Vec3s Ttemp(R0.transpose() * (b2.To - T0) - b1.To);
469  Vec3s T(b1.axes.transpose() * Ttemp);
470  Matrix3s R(b1.axes.transpose() * R0.transpose() * b2.axes);
471 
472  return !obbDisjoint(R, T, b1.extent, b2.extent);
473 }
474 
475 bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,
476  const CollisionRequest& request, CoalScalar& sqrDistLowerBound) {
477  Vec3s Ttemp(R0.transpose() * (b2.To - T0) - b1.To);
478  Vec3s T(b1.axes.transpose() * Ttemp);
479  Matrix3s R(b1.axes.transpose() * R0.transpose() * b2.axes);
480 
481  return !obbDisjointAndLowerBoundDistance(R, T, b1.extent, b2.extent, request,
482  sqrDistLowerBound);
483 }
484 
485 OBB translate(const OBB& bv, const Vec3s& t) {
486  OBB res(bv);
487  res.To += t;
488  return res;
489 }
490 
491 } // namespace coal
coal::computeVertices
void computeVertices(const OBB &b, Vec3s vertices[8])
Compute the 8 vertices of a OBB.
Definition: OBB.cpp:50
coal::OBB::operator+=
OBB & operator+=(const Vec3s &p)
A simple way to merge the OBB and a point (the result is not compact).
Definition: OBB.cpp:438
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::obbDisjointAndLowerBoundDistance
bool obbDisjointAndLowerBoundDistance(const Matrix3s &B, const Vec3s &T, const Vec3s &a_, const Vec3s &b_, const CollisionRequest &request, CoalScalar &squaredLowerBoundDistance)
Definition: OBB.cpp:343
coal::internal::obbDisjoint_check_B_axis
CoalScalar obbDisjoint_check_B_axis(const Matrix3s &B, const Vec3s &T, const Vec3s &a, const Vec3s &b, const Matrix3s &Bf)
Definition: OBB.cpp:297
B
B
coal::OBB::contain
bool contain(const Vec3s &p) const
Check whether the OBB contains a point.
Definition: OBB.cpp:424
coal::OBB::extent
Vec3s extent
Half dimensions of OBB.
Definition: include/coal/BV/OBB.h:65
coal::internal::obbDisjoint_check_A_axis
CoalScalar obbDisjoint_check_A_axis(const Vec3s &T, const Vec3s &a, const Vec3s &b, const Matrix3s &Bf)
Definition: OBB.cpp:289
coal::CollisionRequest::security_margin
CoalScalar security_margin
Distance below which objects are considered in collision. See Collision.
Definition: coal/collision_data.h:328
collision_data.h
OBB.h
coal::OBB::axes
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Matrix3s axes
Orientation of OBB. axis[i] is the ith column of the orientation matrix for the box; it is also the i...
Definition: include/coal/BV/OBB.h:59
coal::OBB::To
Vec3s To
Center of OBB.
Definition: include/coal/BV/OBB.h:62
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
collision.q1
tuple q1
Definition: scripts/collision.py:32
coal::Quatf
Eigen::Quaternion< CoalScalar > Quatf
Definition: coal/math/transform.h:47
coal::obbDisjoint
COAL_DLLAPI bool obbDisjoint(const Matrix3s &B, const Vec3s &T, const Vec3s &a, const Vec3s &b)
Definition: OBB.cpp:161
R
R
coal::getExtentAndCenter
COAL_DLLAPI void getExtentAndCenter(Vec3s *ps, Vec3s *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3s &axes, Vec3s &center, Vec3s &extent)
Compute the bounding volume extent and center for a set or subset of points, given the BV axises.
Definition: BVH_utility.cpp:576
coal::eigen
void eigen(const Eigen::MatrixBase< Derived > &m, typename Derived::Scalar dout[3], Vector *vout)
compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen ve...
Definition: coal/internal/tools.h:103
coal::OBB::overlap
bool overlap(const OBB &other) const
Definition: OBB.cpp:394
a
list a
coal::internal::obbDisjoint_check_Ai_cross_Bi::run
static bool run(int ia, int ja, int ka, const Matrix3s &B, const Vec3s &T, const Vec3s &a, const Vec3s &b, const Matrix3s &Bf, const CoalScalar &breakDistance2, CoalScalar &squaredLowerBoundDistance)
Definition: OBB.cpp:313
res
res
transform.h
coal::merge_smalldist
OBB merge_smalldist(const OBB &b1, const OBB &b2)
OBB merge method when the centers of two smaller OBB are close.
Definition: OBB.cpp:115
coal::OBB::operator+
OBB operator+(const OBB &other) const
Return the merged OBB of current OBB and the other one (the result is not compact).
Definition: OBB.cpp:448
coal::CollisionRequest
request to the collision algorithm
Definition: coal/collision_data.h:311
M
M
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::OBB::distance
CoalScalar distance(const OBB &other, Vec3s *P=NULL, Vec3s *Q=NULL) const
Distance between two OBBs, not implemented.
Definition: OBB.cpp:460
q
q
tools.h
coal::overlap
COAL_DLLAPI bool overlap(const Matrix3s &R0, const Vec3s &T0, const AABB &b1, const AABB &b2)
Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity.
Definition: AABB.cpp:134
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
epsilon
static CoalScalar epsilon
Definition: simple.cpp:12
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
coal::getCovariance
COAL_DLLAPI void getCovariance(Vec3s *ps, Vec3s *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3s &M)
Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to poin...
Definition: BVH_utility.cpp:182
BVH_utility.h
coal::merge_largedist
OBB merge_largedist(const OBB &b1, const OBB &b2)
OBB merge method when the centers of two smaller OBB are far away.
Definition: OBB.cpp:63
coal::OBB
Oriented bounding box class.
Definition: include/coal/BV/OBB.h:51
coal::internal::obbDisjoint_check_Ai_cross_Bi
Definition: OBB.cpp:313
t
dictionary t
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::CollisionRequest::break_distance
CoalScalar break_distance
Distance below which bounding volumes are broken down. See Collision.
Definition: coal/collision_data.h:332


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