coal/internal/traversal_node_bvhs.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-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 #ifndef COAL_TRAVERSAL_NODE_MESHES_H
39 #define COAL_TRAVERSAL_NODE_MESHES_H
40 
42 
43 #include "coal/collision_data.h"
45 #include "coal/BV/BV_node.h"
46 #include "coal/BV/BV.h"
47 #include "coal/BVH/BVH_model.h"
53 
54 #include <cassert>
55 
56 namespace coal {
57 
60 
62 template <typename BV>
63 class BVHCollisionTraversalNode : public CollisionTraversalNodeBase {
64  public:
65  BVHCollisionTraversalNode(const CollisionRequest& request)
66  : CollisionTraversalNodeBase(request) {
67  model1 = NULL;
68  model2 = NULL;
69 
70  num_bv_tests = 0;
71  num_leaf_tests = 0;
72  query_time_seconds = 0.0;
73  }
74 
76  bool isFirstNodeLeaf(unsigned int b) const {
77  assert(model1 != NULL && "model1 is NULL");
78  return model1->getBV(b).isLeaf();
79  }
80 
82  bool isSecondNodeLeaf(unsigned int b) const {
83  assert(model2 != NULL && "model2 is NULL");
84  return model2->getBV(b).isLeaf();
85  }
86 
88  bool firstOverSecond(unsigned int b1, unsigned int b2) const {
89  CoalScalar sz1 = model1->getBV(b1).bv.size();
90  CoalScalar sz2 = model2->getBV(b2).bv.size();
91 
92  bool l1 = model1->getBV(b1).isLeaf();
93  bool l2 = model2->getBV(b2).isLeaf();
94 
95  if (l2 || (!l1 && (sz1 > sz2))) return true;
96  return false;
97  }
98 
100  int getFirstLeftChild(unsigned int b) const {
101  return model1->getBV(b).leftChild();
102  }
103 
105  int getFirstRightChild(unsigned int b) const {
106  return model1->getBV(b).rightChild();
107  }
108 
110  int getSecondLeftChild(unsigned int b) const {
111  return model2->getBV(b).leftChild();
112  }
113 
115  int getSecondRightChild(unsigned int b) const {
116  return model2->getBV(b).rightChild();
117  }
118 
120  const BVHModel<BV>* model1;
122  const BVHModel<BV>* model2;
123 
125  mutable int num_bv_tests;
126  mutable int num_leaf_tests;
127  mutable CoalScalar query_time_seconds;
128 };
129 
131 template <typename BV, int _Options = RelativeTransformationIsIdentity>
132 class MeshCollisionTraversalNode : public BVHCollisionTraversalNode<BV> {
133  public:
134  enum {
135  Options = _Options,
136  RTIsIdentity = _Options & RelativeTransformationIsIdentity
137  };
138 
139  MeshCollisionTraversalNode(const CollisionRequest& request)
140  : BVHCollisionTraversalNode<BV>(request) {
141  vertices1 = NULL;
142  vertices2 = NULL;
143  tri_indices1 = NULL;
144  tri_indices2 = NULL;
145  }
146 
151  bool BVDisjoints(unsigned int b1, unsigned int b2,
152  CoalScalar& sqrDistLowerBound) const {
153  if (this->enable_statistics) this->num_bv_tests++;
154  bool disjoint;
155  if (RTIsIdentity)
156  disjoint = !this->model1->getBV(b1).overlap(
157  this->model2->getBV(b2), this->request, sqrDistLowerBound);
158  else {
159  disjoint = !overlap(RT._R(), RT._T(), this->model2->getBV(b2).bv,
160  this->model1->getBV(b1).bv, this->request,
161  sqrDistLowerBound);
162  }
163  if (disjoint)
164  internal::updateDistanceLowerBoundFromBV(this->request, *this->result,
165  sqrDistLowerBound);
166  return disjoint;
167  }
168 
183  void leafCollides(unsigned int b1, unsigned int b2,
184  CoalScalar& sqrDistLowerBound) const {
185  if (this->enable_statistics) this->num_leaf_tests++;
186 
187  const BVNode<BV>& node1 = this->model1->getBV(b1);
188  const BVNode<BV>& node2 = this->model2->getBV(b2);
189 
190  int primitive_id1 = node1.primitiveId();
191  int primitive_id2 = node2.primitiveId();
192 
193  const Triangle& tri_id1 = tri_indices1[primitive_id1];
194  const Triangle& tri_id2 = tri_indices2[primitive_id2];
195 
196  const Vec3s& P1 = vertices1[tri_id1[0]];
197  const Vec3s& P2 = vertices1[tri_id1[1]];
198  const Vec3s& P3 = vertices1[tri_id1[2]];
199  const Vec3s& Q1 = vertices2[tri_id2[0]];
200  const Vec3s& Q2 = vertices2[tri_id2[1]];
201  const Vec3s& Q3 = vertices2[tri_id2[2]];
202 
203  TriangleP tri1(P1, P2, P3);
204  TriangleP tri2(Q1, Q2, Q3);
205 
206  // TODO(louis): MeshCollisionTraversalNode should have its own GJKSolver.
207  GJKSolver solver(this->request);
208 
209  const bool compute_penetration =
210  this->request.enable_contact || (this->request.security_margin < 0);
211  Vec3s p1, p2, normal;
212  DistanceResult distanceResult;
214  &tri1, this->tf1, &tri2, this->tf2, &solver, compute_penetration, p1,
215  p2, normal);
216 
217  const CoalScalar distToCollision = distance - this->request.security_margin;
218 
219  internal::updateDistanceLowerBoundFromLeaf(this->request, *(this->result),
220  distToCollision, p1, p2, normal);
221 
222  if (distToCollision <=
223  this->request.collision_distance_threshold) { // collision
224  sqrDistLowerBound = 0;
225  if (this->result->numContacts() < this->request.num_max_contacts) {
226  this->result->addContact(Contact(this->model1, this->model2,
227  primitive_id1, primitive_id2, p1, p2,
228  normal, distance));
229  }
230  } else
231  sqrDistLowerBound = distToCollision * distToCollision;
232  }
233 
234  Vec3s* vertices1;
235  Vec3s* vertices2;
236 
237  Triangle* tri_indices1;
238  Triangle* tri_indices2;
239 
240  details::RelativeTransformation<!bool(RTIsIdentity)> RT;
241 };
242 
245 typedef MeshCollisionTraversalNode<OBB, 0> MeshCollisionTraversalNodeOBB;
246 typedef MeshCollisionTraversalNode<RSS, 0> MeshCollisionTraversalNodeRSS;
247 typedef MeshCollisionTraversalNode<kIOS, 0> MeshCollisionTraversalNodekIOS;
248 typedef MeshCollisionTraversalNode<OBBRSS, 0> MeshCollisionTraversalNodeOBBRSS;
249 
251 
252 namespace details {
253 template <typename BV>
254 struct DistanceTraversalBVDistanceLowerBound_impl {
255  static CoalScalar run(const BVNode<BV>& b1, const BVNode<BV>& b2) {
256  return b1.distance(b2);
257  }
258  static CoalScalar run(const Matrix3s& R, const Vec3s& T, const BVNode<BV>& b1,
259  const BVNode<BV>& b2) {
260  return distance(R, T, b1.bv, b2.bv);
261  }
262 };
263 
264 template <>
265 struct DistanceTraversalBVDistanceLowerBound_impl<OBB> {
266  static CoalScalar run(const BVNode<OBB>& b1, const BVNode<OBB>& b2) {
267  CoalScalar sqrDistLowerBound;
268  CollisionRequest request(DISTANCE_LOWER_BOUND, 0);
269  // request.break_distance = ?
270  if (b1.overlap(b2, request, sqrDistLowerBound)) {
271  // TODO A penetration upper bound should be computed.
272  return -1;
273  }
274  return sqrt(sqrDistLowerBound);
275  }
276  static CoalScalar run(const Matrix3s& R, const Vec3s& T,
277  const BVNode<OBB>& b1, const BVNode<OBB>& b2) {
278  CoalScalar sqrDistLowerBound;
279  CollisionRequest request(DISTANCE_LOWER_BOUND, 0);
280  // request.break_distance = ?
281  if (overlap(R, T, b1.bv, b2.bv, request, sqrDistLowerBound)) {
282  // TODO A penetration upper bound should be computed.
283  return -1;
284  }
285  return sqrt(sqrDistLowerBound);
286  }
287 };
288 
289 template <>
290 struct DistanceTraversalBVDistanceLowerBound_impl<AABB> {
291  static CoalScalar run(const BVNode<AABB>& b1, const BVNode<AABB>& b2) {
292  CoalScalar sqrDistLowerBound;
293  CollisionRequest request(DISTANCE_LOWER_BOUND, 0);
294  // request.break_distance = ?
295  if (b1.overlap(b2, request, sqrDistLowerBound)) {
296  // TODO A penetration upper bound should be computed.
297  return -1;
298  }
299  return sqrt(sqrDistLowerBound);
300  }
301  static CoalScalar run(const Matrix3s& R, const Vec3s& T,
302  const BVNode<AABB>& b1, const BVNode<AABB>& b2) {
303  CoalScalar sqrDistLowerBound;
304  CollisionRequest request(DISTANCE_LOWER_BOUND, 0);
305  // request.break_distance = ?
306  if (overlap(R, T, b1.bv, b2.bv, request, sqrDistLowerBound)) {
307  // TODO A penetration upper bound should be computed.
308  return -1;
309  }
310  return sqrt(sqrDistLowerBound);
311  }
312 };
313 } // namespace details
314 
317 
319 template <typename BV>
320 class BVHDistanceTraversalNode : public DistanceTraversalNodeBase {
321  public:
322  BVHDistanceTraversalNode() : DistanceTraversalNodeBase() {
323  model1 = NULL;
324  model2 = NULL;
325 
326  num_bv_tests = 0;
327  num_leaf_tests = 0;
328  query_time_seconds = 0.0;
329  }
330 
332  bool isFirstNodeLeaf(unsigned int b) const {
333  return model1->getBV(b).isLeaf();
334  }
335 
337  bool isSecondNodeLeaf(unsigned int b) const {
338  return model2->getBV(b).isLeaf();
339  }
340 
342  bool firstOverSecond(unsigned int b1, unsigned int b2) const {
343  CoalScalar sz1 = model1->getBV(b1).bv.size();
344  CoalScalar sz2 = model2->getBV(b2).bv.size();
345 
346  bool l1 = model1->getBV(b1).isLeaf();
347  bool l2 = model2->getBV(b2).isLeaf();
348 
349  if (l2 || (!l1 && (sz1 > sz2))) return true;
350  return false;
351  }
352 
354  int getFirstLeftChild(unsigned int b) const {
355  return model1->getBV(b).leftChild();
356  }
357 
359  int getFirstRightChild(unsigned int b) const {
360  return model1->getBV(b).rightChild();
361  }
362 
364  int getSecondLeftChild(unsigned int b) const {
365  return model2->getBV(b).leftChild();
366  }
367 
369  int getSecondRightChild(unsigned int b) const {
370  return model2->getBV(b).rightChild();
371  }
372 
374  const BVHModel<BV>* model1;
376  const BVHModel<BV>* model2;
377 
379  mutable int num_bv_tests;
380  mutable int num_leaf_tests;
381  mutable CoalScalar query_time_seconds;
382 };
383 
385 template <typename BV, int _Options = RelativeTransformationIsIdentity>
386 class MeshDistanceTraversalNode : public BVHDistanceTraversalNode<BV> {
387  public:
388  enum {
389  Options = _Options,
390  RTIsIdentity = _Options & RelativeTransformationIsIdentity
391  };
392 
393  using BVHDistanceTraversalNode<BV>::enable_statistics;
394  using BVHDistanceTraversalNode<BV>::request;
395  using BVHDistanceTraversalNode<BV>::result;
397  using BVHDistanceTraversalNode<BV>::model1;
398  using BVHDistanceTraversalNode<BV>::model2;
399  using BVHDistanceTraversalNode<BV>::num_bv_tests;
400  using BVHDistanceTraversalNode<BV>::num_leaf_tests;
401 
402  MeshDistanceTraversalNode() : BVHDistanceTraversalNode<BV>() {
403  vertices1 = NULL;
404  vertices2 = NULL;
405  tri_indices1 = NULL;
406  tri_indices2 = NULL;
407 
408  rel_err = this->request.rel_err;
409  abs_err = this->request.abs_err;
410  }
411 
412  void preprocess() {
413  if (!RTIsIdentity) preprocessOrientedNode();
414  }
415 
416  void postprocess() {
417  if (!RTIsIdentity) postprocessOrientedNode();
418  }
419 
421  CoalScalar BVDistanceLowerBound(unsigned int b1, unsigned int b2) const {
422  if (enable_statistics) num_bv_tests++;
423  if (RTIsIdentity)
425  model1->getBV(b1), model2->getBV(b2));
426  else
428  RT._R(), RT._T(), model1->getBV(b1), model2->getBV(b2));
429  }
430 
432  void leafComputeDistance(unsigned int b1, unsigned int b2) const {
433  if (this->enable_statistics) this->num_leaf_tests++;
434 
435  const BVNode<BV>& node1 = this->model1->getBV(b1);
436  const BVNode<BV>& node2 = this->model2->getBV(b2);
437 
438  int primitive_id1 = node1.primitiveId();
439  int primitive_id2 = node2.primitiveId();
440 
441  const Triangle& tri_id1 = tri_indices1[primitive_id1];
442  const Triangle& tri_id2 = tri_indices2[primitive_id2];
443 
444  const Vec3s& t11 = vertices1[tri_id1[0]];
445  const Vec3s& t12 = vertices1[tri_id1[1]];
446  const Vec3s& t13 = vertices1[tri_id1[2]];
447 
448  const Vec3s& t21 = vertices2[tri_id2[0]];
449  const Vec3s& t22 = vertices2[tri_id2[1]];
450  const Vec3s& t23 = vertices2[tri_id2[2]];
451 
452  // nearest point pair
453  Vec3s P1, P2, normal;
454 
455  CoalScalar d2;
456  if (RTIsIdentity)
457  d2 = TriangleDistance::sqrTriDistance(t11, t12, t13, t21, t22, t23, P1,
458  P2);
459  else
460  d2 = TriangleDistance::sqrTriDistance(t11, t12, t13, t21, t22, t23,
461  RT._R(), RT._T(), P1, P2);
462  CoalScalar d = sqrt(d2);
463 
464  this->result->update(d, this->model1, this->model2, primitive_id1,
465  primitive_id2, P1, P2, normal);
466  }
467 
469  bool canStop(CoalScalar c) const {
470  if ((c >= this->result->min_distance - abs_err) &&
471  (c * (1 + rel_err) >= this->result->min_distance))
472  return true;
473  return false;
474  }
475 
476  Vec3s* vertices1;
477  Vec3s* vertices2;
478 
479  Triangle* tri_indices1;
480  Triangle* tri_indices2;
481 
483  CoalScalar rel_err;
484  CoalScalar abs_err;
485 
486  details::RelativeTransformation<!bool(RTIsIdentity)> RT;
487 
488  private:
489  void preprocessOrientedNode() {
490  const int init_tri_id1 = 0, init_tri_id2 = 0;
491  const Triangle& init_tri1 = tri_indices1[init_tri_id1];
492  const Triangle& init_tri2 = tri_indices2[init_tri_id2];
493 
494  Vec3s init_tri1_points[3];
495  Vec3s init_tri2_points[3];
496 
497  init_tri1_points[0] = vertices1[init_tri1[0]];
498  init_tri1_points[1] = vertices1[init_tri1[1]];
499  init_tri1_points[2] = vertices1[init_tri1[2]];
500 
501  init_tri2_points[0] = vertices2[init_tri2[0]];
502  init_tri2_points[1] = vertices2[init_tri2[1]];
503  init_tri2_points[2] = vertices2[init_tri2[2]];
504 
505  Vec3s p1, p2, normal;
506  CoalScalar distance = sqrt(TriangleDistance::sqrTriDistance(
507  init_tri1_points[0], init_tri1_points[1], init_tri1_points[2],
508  init_tri2_points[0], init_tri2_points[1], init_tri2_points[2], RT._R(),
509  RT._T(), p1, p2));
510 
511  result->update(distance, model1, model2, init_tri_id1, init_tri_id2, p1, p2,
512  normal);
513  }
514  void postprocessOrientedNode() {
518  if (request.enable_nearest_points && (result->o1 == model1) &&
519  (result->o2 == model2)) {
520  result->nearest_points[0] = tf1.transform(result->nearest_points[0]);
521  result->nearest_points[1] = tf1.transform(result->nearest_points[1]);
522  }
523  }
524 };
525 
528 typedef MeshDistanceTraversalNode<RSS, 0> MeshDistanceTraversalNodeRSS;
529 typedef MeshDistanceTraversalNode<kIOS, 0> MeshDistanceTraversalNodekIOS;
530 typedef MeshDistanceTraversalNode<OBBRSS, 0> MeshDistanceTraversalNodeOBBRSS;
531 
533 
536 namespace details {
537 
538 template <typename BV>
539 inline const Matrix3s& getBVAxes(const BV& bv) {
540  return bv.axes;
541 }
542 
543 template <>
544 inline const Matrix3s& getBVAxes<OBBRSS>(const OBBRSS& bv) {
545  return bv.obb.axes;
546 }
547 
548 } // namespace details
549 
550 } // namespace coal
551 
553 
554 #endif
traversal.h
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
intersect.h
traversal_node_base.h
coal::internal::updateDistanceLowerBoundFromLeaf
void updateDistanceLowerBoundFromLeaf(const CollisionRequest &, CollisionResult &res, const CoalScalar &distance, const Vec3s &p0, const Vec3s &p1, const Vec3s &normal)
Definition: coal/collision_data.h:1184
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
collision_data.h
gjk.P2
tuple P2
Definition: test/scripts/gjk.py:22
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
narrowphase.h
coal::distance
COAL_DLLAPI CoalScalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:180
BV.h
coal::DISTANCE_LOWER_BOUND
@ DISTANCE_LOWER_BOUND
Definition: coal/collision_data.h:306
shape_shape_func.h
BVH_model.h
d
d
gjk.Q1
tuple Q1
Definition: test/scripts/gjk.py:24
gjk.P1
tuple P1
Definition: test/scripts/gjk.py:21
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
l1
list l1
omniidl_be_python_with_docstring.run
def run(tree, args)
Definition: omniidl_be_python_with_docstring.py:140
octree.p1
tuple p1
Definition: octree.py:54
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
coal::internal::ShapeShapeDistance< TriangleP, TriangleP >
CoalScalar ShapeShapeDistance< TriangleP, TriangleP >(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const GJKSolver *solver, const bool, Vec3s &p1, Vec3s &p2, Vec3s &normal)
Definition: triangle_triangle.cpp:46
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::internal::updateDistanceLowerBoundFromBV
void updateDistanceLowerBoundFromBV(const CollisionRequest &, CollisionResult &res, const CoalScalar sqrDistLowerBound)
Definition: coal/collision_data.h:1175
gjk.Q3
tuple Q3
Definition: test/scripts/gjk.py:26
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
geometric_shapes.h
gjk.P3
tuple P3
Definition: test/scripts/gjk.py:23
l2
l2
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
gjk.Q2
tuple Q2
Definition: test/scripts/gjk.py:25
BV_node.h


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