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


hpp-fcl
Author(s):
autogenerated on Fri Aug 2 2024 02:45:14