traversal_node_bvh_hfield.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, INRIA
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Open Source Robotics Foundation nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #ifndef COAL_TRAVERSAL_NODE_BVH_HFIELD_H
38 #define COAL_TRAVERSAL_NODE_BVH_HFIELD_H
39 
41 
42 #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"
48 #include "coal/hfield.h"
53 
54 #include <limits>
55 #include <vector>
56 #include <cassert>
57 
58 namespace coal {
59 
62 
65 template <typename BV1, typename BV2,
66  int _Options = RelativeTransformationIsIdentity>
67 class MeshHeightFieldCollisionTraversalNode
68  : public CollisionTraversalNodeBase {
69  public:
70  enum {
71  Options = _Options,
72  RTIsIdentity = _Options & RelativeTransformationIsIdentity
73  };
74 
75  MeshHeightFieldCollisionTraversalNode(const CollisionRequest& request)
76  : CollisionTraversalNodeBase(request) {
77  model1 = NULL;
78  model2 = NULL;
79 
80  num_bv_tests = 0;
81  num_leaf_tests = 0;
82  query_time_seconds = 0.0;
83 
84  vertices1 = NULL;
85  tri_indices1 = NULL;
86  }
87 
89  bool isFirstNodeLeaf(unsigned int b) const {
90  assert(model1 != NULL && "model1 is NULL");
91  return model1->getBV(b).isLeaf();
92  }
93 
95  bool isSecondNodeLeaf(unsigned int b) const {
96  assert(model2 != NULL && "model2 is NULL");
97  return model2->getBV(b).isLeaf();
98  }
99 
101  bool firstOverSecond(unsigned int b1, unsigned int b2) const {
102  CoalScalar sz1 = model1->getBV(b1).bv.size();
103  CoalScalar sz2 = model2->getBV(b2).bv.size();
104 
105  bool l1 = model1->getBV(b1).isLeaf();
106  bool l2 = model2->getBV(b2).isLeaf();
107 
108  if (l2 || (!l1 && (sz1 > sz2))) return true;
109  return false;
110  }
111 
113  int getFirstLeftChild(unsigned int b) const {
114  return model1->getBV(b).leftChild();
115  }
116 
118  int getFirstRightChild(unsigned int b) const {
119  return model1->getBV(b).rightChild();
120  }
121 
123  int getSecondLeftChild(unsigned int b) const {
124  return model2->getBV(b).leftChild();
125  }
126 
128  int getSecondRightChild(unsigned int b) const {
129  return model2->getBV(b).rightChild();
130  }
131 
133  bool BVDisjoints(unsigned int b1, unsigned int b2) const {
134  if (this->enable_statistics) this->num_bv_tests++;
135  if (RTIsIdentity)
136  return !this->model1->getBV(b1).overlap(this->model2->getBV(b2));
137  else
138  return !overlap(RT._R(), RT._T(), this->model1->getBV(b1).bv,
139  this->model2->getBV(b2).bv);
140  }
141 
146  bool BVDisjoints(unsigned int b1, unsigned int b2,
147  CoalScalar& sqrDistLowerBound) const {
148  if (this->enable_statistics) this->num_bv_tests++;
149  if (RTIsIdentity)
150  return !this->model1->getBV(b1).overlap(this->model2->getBV(b2),
151  this->request, sqrDistLowerBound);
152  else {
153  bool res = !overlap(RT._R(), RT._T(), this->model1->getBV(b1).bv,
154  this->model2->getBV(b2).bv, this->request,
155  sqrDistLowerBound);
156  assert(!res || sqrDistLowerBound > 0);
157  return res;
158  }
159  }
160 
175  void leafCollides(unsigned int b1, unsigned int b2,
176  CoalScalar& sqrDistLowerBound) const {
177  if (this->enable_statistics) this->num_leaf_tests++;
178 
179  const BVNode<BV1>& node1 = this->model1->getBV(b1);
180  const HeightFieldNode<BV2>& node2 = this->model2->getBV(b2);
181 
182  int primitive_id1 = node1.primitiveId();
183  const Triangle& tri_id1 = tri_indices1[primitive_id1];
184 
185  const Vec3s& P1 = vertices1[tri_id1[0]];
186  const Vec3s& P2 = vertices1[tri_id1[1]];
187  const Vec3s& P3 = vertices1[tri_id1[2]];
188 
189  TriangleP tri1(P1, P2, P3);
190 
191  typedef Convex<Triangle> ConvexTriangle;
192  ConvexTriangle convex1, convex2;
193  details::buildConvexTriangles(node2, *this->model2, convex2, convex2);
194 
195  GJKSolver solver;
196  Vec3s p1,
197  p2; // closest points if no collision contact points if collision.
198  Vec3s normal;
200  solver.shapeDistance(tri1, this->tf1, tri2, this->tf2, distance, p1, p2,
201  normal);
202  CoalScalar distToCollision = distance - this->request.security_margin;
203  sqrDistLowerBound = distance * distance;
204  if (distToCollision <= 0) { // collision
205  Vec3s p(p1); // contact point
206  CoalScalar penetrationDepth(0);
207  if (this->result->numContacts() < this->request.num_max_contacts) {
208  // How much (Q1, Q2, Q3) should be moved so that all vertices are
209  // above (P1, P2, P3).
210  penetrationDepth = -distance;
211  if (distance > 0) {
212  normal = (p2 - p1).normalized();
213  p = .5 * (p1 + p2);
214  }
215  this->result->addContact(Contact(this->model1, this->model2,
216  primitive_id1, primitive_id2, p,
217  normal, penetrationDepth));
218  }
219  }
220  }
221 
223  const BVHModel<BV1>* model1;
225  const HeightField<BV2>* model2;
226 
228  mutable int num_bv_tests;
229  mutable int num_leaf_tests;
230  mutable CoalScalar query_time_seconds;
231 
232  Vec3s* vertices1 Triangle* tri_indices1;
233 
234  details::RelativeTransformation<!bool(RTIsIdentity)> RT;
235 };
236 
239 typedef MeshHeightFieldCollisionTraversalNode<OBB, 0>
240  MeshHeightFieldCollisionTraversalNodeOBB;
241 typedef MeshHeightFieldCollisionTraversalNode<RSS, 0>
242  MeshHeightFieldCollisionTraversalNodeRSS;
243 typedef MeshHeightFieldCollisionTraversalNode<kIOS, 0>
244  MeshHeightFieldCollisionTraversalNodekIOS;
245 typedef MeshHeightFieldCollisionTraversalNode<OBBRSS, 0>
246  MeshHeightFieldCollisionTraversalNodeOBBRSS;
247 
249 
250 namespace details {
251 template <typename BV>
252 struct DistanceTraversalBVDistanceLowerBound_impl {
253  static CoalScalar run(const BVNode<BV>& b1, const BVNode<BV>& b2) {
254  return b1.distance(b2);
255  }
256  static CoalScalar run(const Matrix3s& R, const Vec3s& T, const BVNode<BV>& b1,
257  const BVNode<BV>& b2) {
258  return distance(R, T, b1.bv, b2.bv);
259  }
260 };
261 
262 template <>
263 struct DistanceTraversalBVDistanceLowerBound_impl<OBB> {
264  static CoalScalar run(const BVNode<OBB>& b1, const BVNode<OBB>& b2) {
265  CoalScalar sqrDistLowerBound;
266  CollisionRequest request(DISTANCE_LOWER_BOUND, 0);
267  // request.break_distance = ?
268  if (b1.overlap(b2, request, sqrDistLowerBound)) {
269  // TODO A penetration upper bound should be computed.
270  return -1;
271  }
272  return sqrt(sqrDistLowerBound);
273  }
274  static CoalScalar run(const Matrix3s& R, const Vec3s& T,
275  const BVNode<OBB>& b1, const BVNode<OBB>& b2) {
276  CoalScalar sqrDistLowerBound;
277  CollisionRequest request(DISTANCE_LOWER_BOUND, 0);
278  // request.break_distance = ?
279  if (overlap(R, T, b1.bv, b2.bv, request, sqrDistLowerBound)) {
280  // TODO A penetration upper bound should be computed.
281  return -1;
282  }
283  return sqrt(sqrDistLowerBound);
284  }
285 };
286 
287 template <>
288 struct DistanceTraversalBVDistanceLowerBound_impl<AABB> {
289  static CoalScalar run(const BVNode<AABB>& b1, const BVNode<AABB>& b2) {
290  CoalScalar sqrDistLowerBound;
291  CollisionRequest request(DISTANCE_LOWER_BOUND, 0);
292  // request.break_distance = ?
293  if (b1.overlap(b2, request, sqrDistLowerBound)) {
294  // TODO A penetration upper bound should be computed.
295  return -1;
296  }
297  return sqrt(sqrDistLowerBound);
298  }
299  static CoalScalar run(const Matrix3s& R, const Vec3s& T,
300  const BVNode<AABB>& b1, const BVNode<AABB>& b2) {
301  CoalScalar sqrDistLowerBound;
302  CollisionRequest request(DISTANCE_LOWER_BOUND, 0);
303  // request.break_distance = ?
304  if (overlap(R, T, b1.bv, b2.bv, request, sqrDistLowerBound)) {
305  // TODO A penetration upper bound should be computed.
306  return -1;
307  }
308  return sqrt(sqrDistLowerBound);
309  }
310 };
311 } // namespace details
312 
315 
317 template <typename BV>
318 class BVHDistanceTraversalNode : public DistanceTraversalNodeBase {
319  public:
320  BVHDistanceTraversalNode() : DistanceTraversalNodeBase() {
321  model1 = NULL;
322  model2 = NULL;
323 
324  num_bv_tests = 0;
325  num_leaf_tests = 0;
326  query_time_seconds = 0.0;
327  }
328 
330  bool isFirstNodeLeaf(unsigned int b) const {
331  return model1->getBV(b).isLeaf();
332  }
333 
335  bool isSecondNodeLeaf(unsigned int b) const {
336  return model2->getBV(b).isLeaf();
337  }
338 
340  bool firstOverSecond(unsigned int b1, unsigned int b2) const {
341  CoalScalar sz1 = model1->getBV(b1).bv.size();
342  CoalScalar sz2 = model2->getBV(b2).bv.size();
343 
344  bool l1 = model1->getBV(b1).isLeaf();
345  bool l2 = model2->getBV(b2).isLeaf();
346 
347  if (l2 || (!l1 && (sz1 > sz2))) return true;
348  return false;
349  }
350 
352  int getFirstLeftChild(unsigned int b) const {
353  return model1->getBV(b).leftChild();
354  }
355 
357  int getFirstRightChild(unsigned int b) const {
358  return model1->getBV(b).rightChild();
359  }
360 
362  int getSecondLeftChild(unsigned int b) const {
363  return model2->getBV(b).leftChild();
364  }
365 
367  int getSecondRightChild(unsigned int b) const {
368  return model2->getBV(b).rightChild();
369  }
370 
372  const BVHModel<BV>* model1;
374  const BVHModel<BV>* model2;
375 
377  mutable int num_bv_tests;
378  mutable int num_leaf_tests;
379  mutable CoalScalar query_time_seconds;
380 };
381 
383 template <typename BV, int _Options = RelativeTransformationIsIdentity>
384 class MeshDistanceTraversalNode : public BVHDistanceTraversalNode<BV> {
385  public:
386  enum {
387  Options = _Options,
388  RTIsIdentity = _Options & RelativeTransformationIsIdentity
389  };
390 
391  using BVHDistanceTraversalNode<BV>::enable_statistics;
392  using BVHDistanceTraversalNode<BV>::request;
393  using BVHDistanceTraversalNode<BV>::result;
395  using BVHDistanceTraversalNode<BV>::model1;
396  using BVHDistanceTraversalNode<BV>::model2;
397  using BVHDistanceTraversalNode<BV>::num_bv_tests;
398  using BVHDistanceTraversalNode<BV>::num_leaf_tests;
399 
400  MeshDistanceTraversalNode() : BVHDistanceTraversalNode<BV>() {
401  vertices1 = NULL;
402  vertices2 = NULL;
403  tri_indices1 = NULL;
404  tri_indices2 = NULL;
405 
406  rel_err = this->request.rel_err;
407  abs_err = this->request.abs_err;
408  }
409 
410  void preprocess() {
411  if (!RTIsIdentity) preprocessOrientedNode();
412  }
413 
414  void postprocess() {
415  if (!RTIsIdentity) postprocessOrientedNode();
416  }
417 
419  CoalScalar BVDistanceLowerBound(unsigned int b1, unsigned int b2) const {
420  if (enable_statistics) num_bv_tests++;
421  if (RTIsIdentity)
423  model1->getBV(b1), model2->getBV(b2));
424  else
426  RT._R(), RT._T(), model1->getBV(b1), model2->getBV(b2));
427  }
428 
430  void leafComputeDistance(unsigned int b1, unsigned int b2) const {
431  if (this->enable_statistics) this->num_leaf_tests++;
432 
433  const BVNode<BV>& node1 = this->model1->getBV(b1);
434  const BVNode<BV>& node2 = this->model2->getBV(b2);
435 
436  int primitive_id1 = node1.primitiveId();
437  int primitive_id2 = node2.primitiveId();
438 
439  const Triangle& tri_id1 = tri_indices1[primitive_id1];
440  const Triangle& tri_id2 = tri_indices2[primitive_id2];
441 
442  const Vec3s& t11 = vertices1[tri_id1[0]];
443  const Vec3s& t12 = vertices1[tri_id1[1]];
444  const Vec3s& t13 = vertices1[tri_id1[2]];
445 
446  const Vec3s& t21 = vertices2[tri_id2[0]];
447  const Vec3s& t22 = vertices2[tri_id2[1]];
448  const Vec3s& t23 = vertices2[tri_id2[2]];
449 
450  // nearest point pair
451  Vec3s P1, P2, normal;
452 
453  CoalScalar d2;
454  if (RTIsIdentity)
455  d2 = TriangleDistance::sqrTriDistance(t11, t12, t13, t21, t22, t23, P1,
456  P2);
457  else
458  d2 = TriangleDistance::sqrTriDistance(t11, t12, t13, t21, t22, t23,
459  RT._R(), RT._T(), P1, P2);
460  CoalScalar d = sqrt(d2);
461 
462  this->result->update(d, this->model1, this->model2, primitive_id1,
463  primitive_id2, P1, P2, normal);
464  }
465 
467  bool canStop(CoalScalar c) const {
468  if ((c >= this->result->min_distance - abs_err) &&
469  (c * (1 + rel_err) >= this->result->min_distance))
470  return true;
471  return false;
472  }
473 
474  Vec3s* vertices1;
475  Vec3s* vertices2;
476 
477  Triangle* tri_indices1;
478  Triangle* tri_indices2;
479 
481  CoalScalar rel_err;
482  CoalScalar abs_err;
483 
484  details::RelativeTransformation<!bool(RTIsIdentity)> RT;
485 
486  private:
487  void preprocessOrientedNode() {
488  const int init_tri_id1 = 0, init_tri_id2 = 0;
489  const Triangle& init_tri1 = tri_indices1[init_tri_id1];
490  const Triangle& init_tri2 = tri_indices2[init_tri_id2];
491 
492  Vec3s init_tri1_points[3];
493  Vec3s init_tri2_points[3];
494 
495  init_tri1_points[0] = vertices1[init_tri1[0]];
496  init_tri1_points[1] = vertices1[init_tri1[1]];
497  init_tri1_points[2] = vertices1[init_tri1[2]];
498 
499  init_tri2_points[0] = vertices2[init_tri2[0]];
500  init_tri2_points[1] = vertices2[init_tri2[1]];
501  init_tri2_points[2] = vertices2[init_tri2[2]];
502 
503  Vec3s p1, p2, normal;
504  CoalScalar distance = sqrt(TriangleDistance::sqrTriDistance(
505  init_tri1_points[0], init_tri1_points[1], init_tri1_points[2],
506  init_tri2_points[0], init_tri2_points[1], init_tri2_points[2], RT._R(),
507  RT._T(), p1, p2));
508 
509  result->update(distance, model1, model2, init_tri_id1, init_tri_id2, p1, p2,
510  normal);
511  }
512  void postprocessOrientedNode() {
516  if (request.enable_nearest_points && (result->o1 == model1) &&
517  (result->o2 == model2)) {
518  result->nearest_points[0] = tf1.transform(result->nearest_points[0]);
519  result->nearest_points[1] = tf1.transform(result->nearest_points[1]);
520  }
521  }
522 };
523 
526 typedef MeshDistanceTraversalNode<RSS, 0> MeshDistanceTraversalNodeRSS;
527 typedef MeshDistanceTraversalNode<kIOS, 0> MeshDistanceTraversalNodekIOS;
528 typedef MeshDistanceTraversalNode<OBBRSS, 0> MeshDistanceTraversalNodeOBBRSS;
529 
531 
534 namespace details {
535 
536 template <typename BV>
537 inline const Matrix3s& getBVAxes(const BV& bv) {
538  return bv.axes;
539 }
540 
541 template <>
542 inline const Matrix3s& getBVAxes<OBBRSS>(const OBBRSS& bv) {
543  return bv.obb.axes;
544 }
545 
546 } // namespace details
547 
548 } // namespace coal
549 
551 
552 #endif
traversal.h
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
intersect.h
traversal_node_base.h
traversal_node_hfield_shape.h
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
res
res
BVH_model.h
d
d
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
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
hfield.h
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
BV_node.h


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