traversal_recurse-inl.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-2016, 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 FCL_TRAVERSAL_RECURSE_INL_H
39 #define FCL_TRAVERSAL_RECURSE_INL_H
40 
42 
43 #include <queue>
44 
45 #include "fcl/common/unused.h"
46 
47 namespace fcl
48 {
49 
50 namespace detail
51 {
52 
53 //==============================================================================
54 extern template
55 void collisionRecurse(CollisionTraversalNodeBase<double>* node, int b1, int b2, BVHFrontList* front_list);
56 
57 //==============================================================================
58 extern template
59 void collisionRecurse(MeshCollisionTraversalNodeOBB<double>* node, int b1, int b2, const Matrix3<double>& R, const Vector3<double>& T, BVHFrontList* front_list);
60 
61 //==============================================================================
62 extern template
63 void collisionRecurse(MeshCollisionTraversalNodeRSS<double>* node, int b1, int b2, const Matrix3<double>& R, const Vector3<double>& T, BVHFrontList* front_list);
64 
65 //==============================================================================
66 extern template
68 
69 //==============================================================================
70 extern template
71 void distanceRecurse(DistanceTraversalNodeBase<double>* node, int b1, int b2, BVHFrontList* front_list);
72 
73 //==============================================================================
74 extern template
75 void distanceQueueRecurse(DistanceTraversalNodeBase<double>* node, int b1, int b2, BVHFrontList* front_list, int qsize);
76 
77 //==============================================================================
78 extern template
80 
81 //==============================================================================
82 template <typename S>
83 FCL_EXPORT
84 void collisionRecurse(CollisionTraversalNodeBase<S>* node, int b1, int b2, BVHFrontList* front_list)
85 {
86  bool l1 = node->isFirstNodeLeaf(b1);
87  bool l2 = node->isSecondNodeLeaf(b2);
88 
89  if(l1 && l2)
90  {
91  updateFrontList(front_list, b1, b2);
92 
93  if(node->BVTesting(b1, b2)) return;
94 
95  node->leafTesting(b1, b2);
96  return;
97  }
98 
99  if(node->BVTesting(b1, b2))
100  {
101  updateFrontList(front_list, b1, b2);
102  return;
103  }
104 
105  if(node->firstOverSecond(b1, b2))
106  {
107  int c1 = node->getFirstLeftChild(b1);
108  int c2 = node->getFirstRightChild(b1);
109 
110  collisionRecurse(node, c1, b2, front_list);
111 
112  // early stop is disabled is front_list is used
113  if(node->canStop() && !front_list) return;
114 
115  collisionRecurse(node, c2, b2, front_list);
116  }
117  else
118  {
119  int c1 = node->getSecondLeftChild(b2);
120  int c2 = node->getSecondRightChild(b2);
121 
122  collisionRecurse(node, b1, c1, front_list);
123 
124  // early stop is disabled is front_list is used
125  if(node->canStop() && !front_list) return;
126 
127  collisionRecurse(node, b1, c2, front_list);
128  }
129 }
130 
131 //==============================================================================
132 template <typename S>
133 FCL_EXPORT
134 void collisionRecurse(MeshCollisionTraversalNodeOBB<S>* node, int b1, int b2, const Matrix3<S>& R, const Vector3<S>& T, BVHFrontList* front_list)
135 {
136  bool l1 = node->isFirstNodeLeaf(b1);
137  bool l2 = node->isSecondNodeLeaf(b2);
138 
139  if(l1 && l2)
140  {
141  updateFrontList(front_list, b1, b2);
142 
143  if(node->BVTesting(b1, b2, R, T)) return;
144 
145  node->leafTesting(b1, b2, R, T);
146  return;
147  }
148 
149  if(node->BVTesting(b1, b2, R, T))
150  {
151  updateFrontList(front_list, b1, b2);
152  return;
153  }
154 
155  Vector3<S> temp;
156 
157  if(node->firstOverSecond(b1, b2))
158  {
159  int c1 = node->getFirstLeftChild(b1);
160  int c2 = node->getFirstRightChild(b1);
161 
162  const OBB<S>& bv1 = node->model1->getBV(c1).bv;
163 
164  Matrix3<S> Rc = R.transpose() * bv1.axis;
165  temp = T - bv1.To;
166  Vector3<S> Tc = temp.transpose() * bv1.axis;
167 
168  collisionRecurse(node, c1, b2, Rc, Tc, front_list);
169 
170  // early stop is disabled is front_list is used
171  if(node->canStop() && !front_list) return;
172 
173  const OBB<S>& bv2 = node->model1->getBV(c2).bv;
174 
175  Rc.noalias() = R.transpose() * bv2.axis;
176  temp = T - bv2.To;
177  Tc[0] = bv2.axis.col(0).dot(temp);
178  Tc[1] = bv2.axis.col(1).dot(temp);
179  Tc[2] = bv2.axis.col(2).dot(temp);
180 
181  collisionRecurse(node, c2, b2, Rc, Tc, front_list);
182  }
183  else
184  {
185  int c1 = node->getSecondLeftChild(b2);
186  int c2 = node->getSecondRightChild(b2);
187 
188  const OBB<S>& bv1 = node->model2->getBV(c1).bv;
189  Matrix3<S> Rc;
190  temp.noalias() = R * bv1.axis.col(0);
191  Rc(0, 0) = temp[0]; Rc(1, 0) = temp[1]; Rc(2, 0) = temp[2];
192  temp.noalias() = R * bv1.axis.col(1);
193  Rc(0, 1) = temp[0]; Rc(1, 1) = temp[1]; Rc(2, 1) = temp[2];
194  temp.noalias() = R * bv1.axis.col(2);
195  Rc(0, 2) = temp[0]; Rc(1, 2) = temp[1]; Rc(2, 2) = temp[2];
196  Vector3<S> Tc = R * bv1.To + T;
197 
198  collisionRecurse(node, b1, c1, Rc, Tc, front_list);
199 
200  // early stop is disabled is front_list is used
201  if(node->canStop() && !front_list) return;
202 
203  const OBB<S>& bv2 = node->model2->getBV(c2).bv;
204  temp.noalias() = R * bv2.axis.col(0);
205  Rc(0, 0) = temp[0]; Rc(1, 0) = temp[1]; Rc(2, 0) = temp[2];
206  temp.noalias() = R * bv2.axis.col(1);
207  Rc(0, 1) = temp[0]; Rc(1, 1) = temp[1]; Rc(2, 1) = temp[2];
208  temp.noalias() = R * bv2.axis.col(2);
209  Rc(0, 2) = temp[0]; Rc(1, 2) = temp[1]; Rc(2, 2) = temp[2];
210  Tc = T;
211  Tc.noalias() += R * bv2.To;
212 
213  collisionRecurse(node, b1, c2, Rc, Tc, front_list);
214  }
215 }
216 
217 //==============================================================================
218 template <typename S>
219 FCL_EXPORT
220 void collisionRecurse(MeshCollisionTraversalNodeRSS<S>* node, int b1, int b2, const Matrix3<S>& R, const Vector3<S>& T, BVHFrontList* front_list)
221 {
222  FCL_UNUSED(node);
223  FCL_UNUSED(b1);
224  FCL_UNUSED(b2);
225  FCL_UNUSED(R);
226  FCL_UNUSED(T);
227  FCL_UNUSED(front_list);
228 
229  // Do nothing
230 }
231 
232 //==============================================================================
236 template <typename S>
237 FCL_EXPORT
239 {
240  bool l = node->isFirstNodeLeaf(b);
241 
242  if(l) return;
243 
244  int c1 = node->getFirstLeftChild(b);
245  int c2 = node->getFirstRightChild(b);
246 
247  selfCollisionRecurse(node, c1, front_list);
248  if(node->canStop() && !front_list) return;
249 
250  selfCollisionRecurse(node, c2, front_list);
251  if(node->canStop() && !front_list) return;
252 
253  collisionRecurse(node, c1, c2, front_list);
254 }
255 
256 //==============================================================================
257 template <typename S>
258 FCL_EXPORT
259 void distanceRecurse(DistanceTraversalNodeBase<S>* node, int b1, int b2, BVHFrontList* front_list)
260 {
261  bool l1 = node->isFirstNodeLeaf(b1);
262  bool l2 = node->isSecondNodeLeaf(b2);
263 
264  if(l1 && l2)
265  {
266  updateFrontList(front_list, b1, b2);
267 
268  node->leafTesting(b1, b2);
269  return;
270  }
271 
272  int a1, a2, c1, c2;
273 
274  if(node->firstOverSecond(b1, b2))
275  {
276  a1 = node->getFirstLeftChild(b1);
277  a2 = b2;
278  c1 = node->getFirstRightChild(b1);
279  c2 = b2;
280  }
281  else
282  {
283  a1 = b1;
284  a2 = node->getSecondLeftChild(b2);
285  c1 = b1;
286  c2 = node->getSecondRightChild(b2);
287  }
288 
289  S d1 = node->BVTesting(a1, a2);
290  S d2 = node->BVTesting(c1, c2);
291 
292  if(d2 < d1)
293  {
294  if(!node->canStop(d2))
295  distanceRecurse(node, c1, c2, front_list);
296  else
297  updateFrontList(front_list, c1, c2);
298 
299  if(!node->canStop(d1))
300  distanceRecurse(node, a1, a2, front_list);
301  else
302  updateFrontList(front_list, a1, a2);
303  }
304  else
305  {
306  if(!node->canStop(d1))
307  distanceRecurse(node, a1, a2, front_list);
308  else
309  updateFrontList(front_list, a1, a2);
310 
311  if(!node->canStop(d2))
312  distanceRecurse(node, c1, c2, front_list);
313  else
314  updateFrontList(front_list, c1, c2);
315  }
316 }
317 
318 //==============================================================================
320 template <typename S>
321 struct FCL_EXPORT BVT
322 {
324  S d;
325 
327  int b1, b2;
328 };
329 
330 //==============================================================================
332 template <typename S>
333 struct FCL_EXPORT BVT_Comparer
334 {
335  bool operator() (const BVT<S>& lhs, const BVT<S>& rhs) const
336  {
337  return lhs.d > rhs.d;
338  }
339 };
340 
341 //==============================================================================
342 template <typename S>
343 struct FCL_EXPORT BVTQ
344 {
345  BVTQ() : qsize(2) {}
346 
347  bool empty() const
348  {
349  return pq.empty();
350  }
351 
352  size_t size() const
353  {
354  return pq.size();
355  }
356 
357  const BVT<S>& top() const
358  {
359  return pq.top();
360  }
361 
362  void push(const BVT<S>& x)
363  {
364  pq.push(x);
365  }
366 
367  void pop()
368  {
369  pq.pop();
370  }
371 
372  bool full() const
373  {
374  return (pq.size() + 1 >= qsize);
375  }
376 
377  std::priority_queue<BVT<S>, std::vector<BVT<S>>, BVT_Comparer<S>> pq;
378 
380  unsigned int qsize;
381 };
382 
383 //==============================================================================
384 template <typename S>
385 FCL_EXPORT
386 void distanceQueueRecurse(DistanceTraversalNodeBase<S>* node, int b1, int b2, BVHFrontList* front_list, int qsize)
387 {
388  BVTQ<S> bvtq;
389  bvtq.qsize = qsize;
390 
391  BVT<S> min_test;
392  min_test.b1 = b1;
393  min_test.b2 = b2;
394 
395  while(1)
396  {
397  bool l1 = node->isFirstNodeLeaf(min_test.b1);
398  bool l2 = node->isSecondNodeLeaf(min_test.b2);
399 
400  if(l1 && l2)
401  {
402  updateFrontList(front_list, min_test.b1, min_test.b2);
403 
404  node->leafTesting(min_test.b1, min_test.b2);
405  }
406  else if(bvtq.full())
407  {
408  // queue should not get two more tests, recur
409 
410  distanceQueueRecurse(node, min_test.b1, min_test.b2, front_list, qsize);
411  }
412  else
413  {
414  // queue capacity is not full yet
415  BVT<S> bvt1, bvt2;
416 
417  if(node->firstOverSecond(min_test.b1, min_test.b2))
418  {
419  int c1 = node->getFirstLeftChild(min_test.b1);
420  int c2 = node->getFirstRightChild(min_test.b1);
421  bvt1.b1 = c1;
422  bvt1.b2 = min_test.b2;
423  bvt1.d = node->BVTesting(bvt1.b1, bvt1.b2);
424 
425  bvt2.b1 = c2;
426  bvt2.b2 = min_test.b2;
427  bvt2.d = node->BVTesting(bvt2.b1, bvt2.b2);
428  }
429  else
430  {
431  int c1 = node->getSecondLeftChild(min_test.b2);
432  int c2 = node->getSecondRightChild(min_test.b2);
433  bvt1.b1 = min_test.b1;
434  bvt1.b2 = c1;
435  bvt1.d = node->BVTesting(bvt1.b1, bvt1.b2);
436 
437  bvt2.b1 = min_test.b1;
438  bvt2.b2 = c2;
439  bvt2.d = node->BVTesting(bvt2.b1, bvt2.b2);
440  }
441 
442  bvtq.push(bvt1);
443  bvtq.push(bvt2);
444  }
445 
446  if(bvtq.empty())
447  break;
448  else
449  {
450  min_test = bvtq.top();
451  bvtq.pop();
452 
453  if(node->canStop(min_test.d))
454  {
455  updateFrontList(front_list, min_test.b1, min_test.b2);
456  break;
457  }
458  }
459  }
460 }
461 
462 //==============================================================================
463 template <typename S>
464 FCL_EXPORT
466 {
467  BVHFrontList::iterator front_iter;
468  BVHFrontList append;
469  for(front_iter = front_list->begin(); front_iter != front_list->end(); ++front_iter)
470  {
471  int b1 = front_iter->left;
472  int b2 = front_iter->right;
473  bool l1 = node->isFirstNodeLeaf(b1);
474  bool l2 = node->isSecondNodeLeaf(b2);
475 
476  if(l1 & l2)
477  {
478  front_iter->valid = false; // the front node is no longer valid, in collideRecurse will add again.
479  collisionRecurse(node, b1, b2, &append);
480  }
481  else
482  {
483  if(!node->BVTesting(b1, b2))
484  {
485  front_iter->valid = false;
486 
487  if(node->firstOverSecond(b1, b2))
488  {
489  int c1 = node->getFirstLeftChild(b1);
490  int c2 = node->getFirstRightChild(b1);
491 
492  collisionRecurse(node, c1, b2, front_list);
493  collisionRecurse(node, c2, b2, front_list);
494  }
495  else
496  {
497  int c1 = node->getSecondLeftChild(b2);
498  int c2 = node->getSecondRightChild(b2);
499 
500  collisionRecurse(node, b1, c1, front_list);
501  collisionRecurse(node, b1, c2, front_list);
502  }
503  }
504  }
505  }
506 
507 
508  // clean the old front list (remove invalid node)
509  for(front_iter = front_list->begin(); front_iter != front_list->end();)
510  {
511  if(!front_iter->valid)
512  front_iter = front_list->erase(front_iter);
513  else
514  ++front_iter;
515  }
516 
517  for(front_iter = append.begin(); front_iter != append.end(); ++front_iter)
518  {
519  front_list->push_back(*front_iter);
520  }
521 }
522 
523 } // namespace detail
524 } // namespace fcl
525 
526 #endif
int b1
bv indices for a pair of bvs in two models
std::priority_queue< BVT< S >, std::vector< BVT< S > >, BVT_Comparer< S > > pq
const BVT< S > & top() const
virtual bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
Main namespace.
int getSecondLeftChild(int b) const
Obtain the left child of BV node in the second BVH.
template class FCL_EXPORT DistanceTraversalNodeBase< double >
void push(const BVT< S > &x)
virtual bool isSecondNodeLeaf(int b) const
Whether b is a leaf node in the second BVH tree.
Bounding volume test structure.
Eigen::Matrix< S, 3, 3 > Matrix3
Definition: types.h:85
template class FCL_EXPORT MeshCollisionTraversalNodeOBB< double >
template class FCL_EXPORT MeshCollisionTraversalNodeRSS< double >
virtual bool isFirstNodeLeaf(int b) const
Whether b is a leaf node in the first BVH tree.
int getFirstLeftChild(int b) const
Obtain the left child of BV node in the first BVH.
S d
distance between bvs
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
bool canStop() const
Whether the traversal process can stop early.
const BVHModel< OBB< S > > * model1
The first BVH model.
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
virtual bool canStop() const
Check whether the traversal can stop.
Comparer between two BVT.
Node structure encoding the information required for collision traversal.
Node structure encoding the information required for distance traversal.
template void selfCollisionRecurse(CollisionTraversalNodeBase< double > *node, int b, BVHFrontList *front_list)
virtual void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
bool isSecondNodeLeaf(int b) const
Whether the BV node in the second BVH tree is leaf.
template void propagateBVHFrontListCollisionRecurse(CollisionTraversalNodeBase< double > *node, BVHFrontList *front_list)
FCL_EXPORT void updateFrontList(BVHFrontList *front_list, int b1, int b2)
Add new front node into the front list.
Definition: BVH_front.cpp:54
virtual int getFirstRightChild(int b) const
Get the right child of the node b in the first tree.
int getSecondRightChild(int b) const
Obtain the right child of BV node in the second BVH.
#define FCL_UNUSED(x)
Definition: unused.h:39
template class FCL_EXPORT CollisionTraversalNodeBase< double >
template void distanceRecurse(DistanceTraversalNodeBase< double > *node, int b1, int b2, BVHFrontList *front_list)
BV bv
bounding volume storing the geometry
Definition: BV_node.h:57
virtual int getSecondLeftChild(int b) const
Get the left child of the node b in the second tree.
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
Matrix3< S > axis
Orientation of OBB. The axes of the rotation matrix are the principle directions of the box...
Definition: OBB.h:62
virtual void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
virtual S BVTesting(int b1, int b2) const
BV test between b1 and b2.
template void distanceQueueRecurse(DistanceTraversalNodeBase< double > *node, int b1, int b2, BVHFrontList *front_list, int qsize)
bool firstOverSecond(int b1, int b2) const
Determine the traversal order, is the first BVTT subtree better.
bool isFirstNodeLeaf(int b) const
Whether the BV node in the first BVH tree is leaf.
int getFirstRightChild(int b) const
Obtain the right child of BV node in the first BVH.
const BVHModel< OBB< S > > * model2
The second BVH model.
Vector3< S > To
Center of OBB.
Definition: OBB.h:65
virtual bool firstOverSecond(int b1, int b2) const
Traverse the subtree of the node in the first tree first.
std::list< BVHFrontNode > BVHFrontList
BVH front list is a list of front nodes.
Definition: BVH_front.h:69
unsigned int qsize
Queue size.
virtual int getSecondRightChild(int b) const
Get the right child of the node b in the second tree.
Traversal node for collision between two meshes if their underlying BVH node is oriented node (OBB...
virtual bool canStop(S c) const
Check whether the traversal can stop.
virtual int getFirstLeftChild(int b) const
Get the left child of the node b in the first tree.
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
template void collisionRecurse(CollisionTraversalNodeBase< double > *node, int b1, int b2, BVHFrontList *front_list)


fcl_catkin
Author(s):
autogenerated on Thu Mar 23 2023 03:00:19