broadphase_dynamic_AABB_tree_array.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-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 
39 
40 #ifdef COAL_HAVE_OCTOMAP
41 #include "coal/octree.h"
42 #endif
43 namespace coal {
44 namespace detail {
45 namespace dynamic_AABB_tree_array {
46 
47 #if COAL_HAVE_OCTOMAP
48 
49 //==============================================================================
50 bool collisionRecurse_(
52  size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2,
53  const AABB& root2_bv, const Transform3s& tf2,
54  CollisionCallBackBase* callback) {
56  nodes1 + root1_id;
57  if (!root2) {
58  if (root1->isLeaf()) {
59  CollisionObject* obj1 = static_cast<CollisionObject*>(root1->data);
60 
61  if (!obj1->collisionGeometry()->isFree()) {
62  OBB obb1, obb2;
63  convertBV(root1->bv, Transform3s::Identity(), obb1);
64  convertBV(root2_bv, tf2, obb2);
65 
66  if (obb1.overlap(obb2)) {
67  Box* box = new Box();
68  Transform3s box_tf;
69  constructBox(root2_bv, tf2, *box, box_tf);
70 
71  box->cost_density = tree2->getDefaultOccupancy();
72 
73  CollisionObject obj2(shared_ptr<CollisionGeometry>(box), box_tf);
74  return (*callback)(obj1, &obj2);
75  }
76  }
77  } else {
78  if (collisionRecurse_(nodes1, root1->children[0], tree2, nullptr,
79  root2_bv, tf2, callback))
80  return true;
81  if (collisionRecurse_(nodes1, root1->children[1], tree2, nullptr,
82  root2_bv, tf2, callback))
83  return true;
84  }
85 
86  return false;
87  } else if (root1->isLeaf() && !tree2->nodeHasChildren(root2)) {
88  CollisionObject* obj1 = static_cast<CollisionObject*>(root1->data);
89  if (!tree2->isNodeFree(root2) && !obj1->collisionGeometry()->isFree()) {
90  OBB obb1, obb2;
91  convertBV(root1->bv, Transform3s::Identity(), obb1);
92  convertBV(root2_bv, tf2, obb2);
93 
94  if (obb1.overlap(obb2)) {
95  Box* box = new Box();
96  Transform3s box_tf;
97  constructBox(root2_bv, tf2, *box, box_tf);
98 
99  box->cost_density = root2->getOccupancy();
100  box->threshold_occupied = tree2->getOccupancyThres();
101 
102  CollisionObject obj2(shared_ptr<CollisionGeometry>(box), box_tf);
103  return (*callback)(obj1, &obj2);
104  } else
105  return false;
106  } else
107  return false;
108  }
109 
110  OBB obb1, obb2;
111  convertBV(root1->bv, Transform3s::Identity(), obb1);
112  convertBV(root2_bv, tf2, obb2);
113 
114  if (tree2->isNodeFree(root2) || !obb1.overlap(obb2)) return false;
115 
116  if (!tree2->nodeHasChildren(root2) ||
117  (!root1->isLeaf() && (root1->bv.size() > root2_bv.size()))) {
118  if (collisionRecurse_(nodes1, root1->children[0], tree2, root2, root2_bv,
119  tf2, callback))
120  return true;
121  if (collisionRecurse_(nodes1, root1->children[1], tree2, root2, root2_bv,
122  tf2, callback))
123  return true;
124  } else {
125  for (unsigned int i = 0; i < 8; ++i) {
126  if (tree2->nodeChildExists(root2, i)) {
127  const OcTree::OcTreeNode* child = tree2->getNodeChild(root2, i);
128  AABB child_bv;
129  computeChildBV(root2_bv, i, child_bv);
130 
131  if (collisionRecurse_(nodes1, root1_id, tree2, child, child_bv, tf2,
132  callback))
133  return true;
134  } else {
135  AABB child_bv;
136  computeChildBV(root2_bv, i, child_bv);
137  if (collisionRecurse_(nodes1, root1_id, tree2, nullptr, child_bv, tf2,
138  callback))
139  return true;
140  }
141  }
142  }
143 
144  return false;
145 }
146 
147 //==============================================================================
148 bool distanceRecurse_(
150  size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2,
151  const AABB& root2_bv, const Transform3s& tf2,
152  DistanceCallBackBase* callback, CoalScalar& min_dist) {
154  nodes1 + root1_id;
155  if (root1->isLeaf() && !tree2->nodeHasChildren(root2)) {
156  if (tree2->isNodeOccupied(root2)) {
157  Box* box = new Box();
158  Transform3s box_tf;
159  constructBox(root2_bv, tf2, *box, box_tf);
160  CollisionObject obj(shared_ptr<CollisionGeometry>(box), box_tf);
161  return (*callback)(static_cast<CollisionObject*>(root1->data), &obj,
162  min_dist);
163  } else
164  return false;
165  }
166 
167  if (!tree2->isNodeOccupied(root2)) return false;
168 
169  if (!tree2->nodeHasChildren(root2) ||
170  (!root1->isLeaf() && (root1->bv.size() > root2_bv.size()))) {
171  AABB aabb2;
172  convertBV(root2_bv, tf2, aabb2);
173 
174  CoalScalar d1 = aabb2.distance((nodes1 + root1->children[0])->bv);
175  CoalScalar d2 = aabb2.distance((nodes1 + root1->children[1])->bv);
176 
177  if (d2 < d1) {
178  if (d2 < min_dist) {
179  if (distanceRecurse_(nodes1, root1->children[1], tree2, root2, root2_bv,
180  tf2, callback, min_dist))
181  return true;
182  }
183 
184  if (d1 < min_dist) {
185  if (distanceRecurse_(nodes1, root1->children[0], tree2, root2, root2_bv,
186  tf2, callback, min_dist))
187  return true;
188  }
189  } else {
190  if (d1 < min_dist) {
191  if (distanceRecurse_(nodes1, root1->children[0], tree2, root2, root2_bv,
192  tf2, callback, min_dist))
193  return true;
194  }
195 
196  if (d2 < min_dist) {
197  if (distanceRecurse_(nodes1, root1->children[1], tree2, root2, root2_bv,
198  tf2, callback, min_dist))
199  return true;
200  }
201  }
202  } else {
203  for (unsigned int i = 0; i < 8; ++i) {
204  if (tree2->nodeChildExists(root2, i)) {
205  const OcTree::OcTreeNode* child = tree2->getNodeChild(root2, i);
206  AABB child_bv;
207  computeChildBV(root2_bv, i, child_bv);
208 
209  AABB aabb2;
210  convertBV(child_bv, tf2, aabb2);
211  CoalScalar d = root1->bv.distance(aabb2);
212 
213  if (d < min_dist) {
214  if (distanceRecurse_(nodes1, root1_id, tree2, child, child_bv, tf2,
215  callback, min_dist))
216  return true;
217  }
218  }
219  }
220  }
221 
222  return false;
223 }
224 
225 #endif
226 
227 //==============================================================================
230  size_t root1_id,
232  size_t root2_id, CollisionCallBackBase* callback) {
234  nodes1 + root1_id;
236  nodes2 + root2_id;
237  if (root1->isLeaf() && root2->isLeaf()) {
238  if (!root1->bv.overlap(root2->bv)) return false;
239  return (*callback)(static_cast<CollisionObject*>(root1->data),
240  static_cast<CollisionObject*>(root2->data));
241  }
242 
243  if (!root1->bv.overlap(root2->bv)) return false;
244 
245  if (root2->isLeaf() ||
246  (!root1->isLeaf() && (root1->bv.size() > root2->bv.size()))) {
247  if (collisionRecurse(nodes1, root1->children[0], nodes2, root2_id,
248  callback))
249  return true;
250  if (collisionRecurse(nodes1, root1->children[1], nodes2, root2_id,
251  callback))
252  return true;
253  } else {
254  if (collisionRecurse(nodes1, root1_id, nodes2, root2->children[0],
255  callback))
256  return true;
257  if (collisionRecurse(nodes1, root1_id, nodes2, root2->children[1],
258  callback))
259  return true;
260  }
261  return false;
262 }
263 
264 //==============================================================================
265 inline COAL_DLLAPI bool collisionRecurse(
267  size_t root_id, CollisionObject* query, CollisionCallBackBase* callback) {
269  if (!root->bv.overlap(query->getAABB())) return false;
270 
271  if (root->isLeaf()) {
272  return (*callback)(static_cast<CollisionObject*>(root->data), query);
273  }
274 
275  size_t select_res = implementation_array::select(
276  query->getAABB(), root->children[0], root->children[1], nodes);
277 
278  if (collisionRecurse(nodes, root->children[select_res], query, callback))
279  return true;
280 
281  if (collisionRecurse(nodes, root->children[1 - select_res], query, callback))
282  return true;
283 
284  return false;
285 }
286 
287 //==============================================================================
290  size_t root_id, CollisionCallBackBase* callback) {
292  if (root->isLeaf()) return false;
293 
294  if (selfCollisionRecurse(nodes, root->children[0], callback)) return true;
295 
296  if (selfCollisionRecurse(nodes, root->children[1], callback)) return true;
297 
298  if (collisionRecurse(nodes, root->children[0], nodes, root->children[1],
299  callback))
300  return true;
301 
302  return false;
303 }
304 
305 //==============================================================================
308  size_t root1_id,
310  size_t root2_id, DistanceCallBackBase* callback, CoalScalar& min_dist) {
312  nodes1 + root1_id;
314  nodes2 + root2_id;
315  if (root1->isLeaf() && root2->isLeaf()) {
316  CollisionObject* root1_obj = static_cast<CollisionObject*>(root1->data);
317  CollisionObject* root2_obj = static_cast<CollisionObject*>(root2->data);
318  return (*callback)(root1_obj, root2_obj, min_dist);
319  }
320 
321  if (root2->isLeaf() ||
322  (!root1->isLeaf() && (root1->bv.size() > root2->bv.size()))) {
323  CoalScalar d1 = root2->bv.distance((nodes1 + root1->children[0])->bv);
324  CoalScalar d2 = root2->bv.distance((nodes1 + root1->children[1])->bv);
325 
326  if (d2 < d1) {
327  if (d2 < min_dist) {
328  if (distanceRecurse(nodes1, root1->children[1], nodes2, root2_id,
329  callback, min_dist))
330  return true;
331  }
332 
333  if (d1 < min_dist) {
334  if (distanceRecurse(nodes1, root1->children[0], nodes2, root2_id,
335  callback, min_dist))
336  return true;
337  }
338  } else {
339  if (d1 < min_dist) {
340  if (distanceRecurse(nodes1, root1->children[0], nodes2, root2_id,
341  callback, min_dist))
342  return true;
343  }
344 
345  if (d2 < min_dist) {
346  if (distanceRecurse(nodes1, root1->children[1], nodes2, root2_id,
347  callback, min_dist))
348  return true;
349  }
350  }
351  } else {
352  CoalScalar d1 = root1->bv.distance((nodes2 + root2->children[0])->bv);
353  CoalScalar d2 = root1->bv.distance((nodes2 + root2->children[1])->bv);
354 
355  if (d2 < d1) {
356  if (d2 < min_dist) {
357  if (distanceRecurse(nodes1, root1_id, nodes2, root2->children[1],
358  callback, min_dist))
359  return true;
360  }
361 
362  if (d1 < min_dist) {
363  if (distanceRecurse(nodes1, root1_id, nodes2, root2->children[0],
364  callback, min_dist))
365  return true;
366  }
367  } else {
368  if (d1 < min_dist) {
369  if (distanceRecurse(nodes1, root1_id, nodes2, root2->children[0],
370  callback, min_dist))
371  return true;
372  }
373 
374  if (d2 < min_dist) {
375  if (distanceRecurse(nodes1, root1_id, nodes2, root2->children[1],
376  callback, min_dist))
377  return true;
378  }
379  }
380  }
381 
382  return false;
383 }
384 
385 //==============================================================================
388  size_t root_id, CollisionObject* query, DistanceCallBackBase* callback,
389  CoalScalar& min_dist) {
391  if (root->isLeaf()) {
392  CollisionObject* root_obj = static_cast<CollisionObject*>(root->data);
393  return (*callback)(root_obj, query, min_dist);
394  }
395 
396  CoalScalar d1 = query->getAABB().distance((nodes + root->children[0])->bv);
397  CoalScalar d2 = query->getAABB().distance((nodes + root->children[1])->bv);
398 
399  if (d2 < d1) {
400  if (d2 < min_dist) {
401  if (distanceRecurse(nodes, root->children[1], query, callback, min_dist))
402  return true;
403  }
404 
405  if (d1 < min_dist) {
406  if (distanceRecurse(nodes, root->children[0], query, callback, min_dist))
407  return true;
408  }
409  } else {
410  if (d1 < min_dist) {
411  if (distanceRecurse(nodes, root->children[0], query, callback, min_dist))
412  return true;
413  }
414 
415  if (d2 < min_dist) {
416  if (distanceRecurse(nodes, root->children[1], query, callback, min_dist))
417  return true;
418  }
419  }
420 
421  return false;
422 }
423 
424 //==============================================================================
427  size_t root_id, DistanceCallBackBase* callback, CoalScalar& min_dist) {
429  if (root->isLeaf()) return false;
430 
431  if (selfDistanceRecurse(nodes, root->children[0], callback, min_dist))
432  return true;
433 
434  if (selfDistanceRecurse(nodes, root->children[1], callback, min_dist))
435  return true;
436 
437  if (distanceRecurse(nodes, root->children[0], nodes, root->children[1],
438  callback, min_dist))
439  return true;
440 
441  return false;
442 }
443 
444 #if COAL_HAVE_OCTOMAP
445 
446 //==============================================================================
447 bool collisionRecurse(
449  size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2,
450  const AABB& root2_bv, const Transform3s& tf2,
452  if (tf2.rotation().isIdentity())
453  return collisionRecurse_(nodes1, root1_id, tree2, root2, root2_bv,
454  tf2.translation(), callback);
455  else
456  return collisionRecurse_(nodes1, root1_id, tree2, root2, root2_bv, tf2,
457  callback);
458 }
459 
460 //==============================================================================
461 bool distanceRecurse(
463  size_t root1_id, const OcTree* tree2, const OcTree::OcTreeNode* root2,
464  const AABB& root2_bv, const Transform3s& tf2,
466  if (tf2.rotation().isIdentity())
467  return distanceRecurse_(nodes1, root1_id, tree2, root2, root2_bv,
468  tf2.translation(), callback, min_dist);
469  else
470  return distanceRecurse_(nodes1, root1_id, tree2, root2, root2_bv, tf2,
471  callback, min_dist);
472 }
473 
474 #endif
475 
476 } // namespace dynamic_AABB_tree_array
477 
478 } // namespace detail
479 
480 //==============================================================================
482  tree_topdown_balance_threshold = &dtree.bu_threshold;
483  tree_topdown_level = &dtree.topdown_level;
487  *tree_topdown_level = 0;
488  tree_init_level = 0;
489  setup_ = false;
490 
491  // from experiment, this is the optimal setting
494 }
495 
496 //==============================================================================
498  const std::vector<CollisionObject*>& other_objs) {
499  if (other_objs.empty()) return;
500 
501  if (size() > 0) {
503  } else {
504  DynamicAABBNode* leaves = new DynamicAABBNode[other_objs.size()];
505  table.rehash(other_objs.size());
506  for (size_t i = 0, size = other_objs.size(); i < size; ++i) {
507  leaves[i].bv = other_objs[i]->getAABB();
508  leaves[i].parent = dtree.NULL_NODE;
509  leaves[i].children[1] = dtree.NULL_NODE;
510  leaves[i].data = other_objs[i];
511  table[other_objs[i]] = i;
512  }
513 
514  int n_leaves = (int)other_objs.size();
515 
516  dtree.init(leaves, n_leaves, tree_init_level);
517 
518  setup_ = true;
519  }
520 }
521 
522 //==============================================================================
524  CollisionObject* obj) {
525  size_t node = dtree.insert(obj->getAABB(), obj);
526  table[obj] = node;
527 }
528 
529 //==============================================================================
531  CollisionObject* obj) {
532  size_t node = table[obj];
533  table.erase(obj);
534  dtree.remove(node);
535 }
536 
537 //==============================================================================
539  if (!setup_) {
540  int num = (int)dtree.size();
541  if (num == 0) {
542  setup_ = true;
543  return;
544  }
545 
546  int height = (int)dtree.getMaxHeight();
547 
548  if ((CoalScalar)height - std::log((CoalScalar)num) / std::log(2.0) <
550  dtree.balanceIncremental(tree_incremental_balance_pass);
551  else
552  dtree.balanceTopdown();
553 
554  setup_ = true;
555  }
556 }
557 
558 //==============================================================================
560  for (auto it = table.cbegin(), end = table.cend(); it != end; ++it) {
561  const CollisionObject* obj = it->first;
562  size_t node = it->second;
563  dtree.getNodes()[node].bv = obj->getAABB();
564  }
565 
566  dtree.refit();
567  setup_ = false;
568 
569  setup();
570 }
571 
572 //==============================================================================
574  CollisionObject* updated_obj) {
575  const auto it = table.find(updated_obj);
576  if (it != table.end()) {
577  size_t node = it->second;
578  if (!(dtree.getNodes()[node].bv == updated_obj->getAABB()))
579  dtree.update(node, updated_obj->getAABB());
580  }
581  setup_ = false;
582 }
583 
584 //==============================================================================
586  CollisionObject* updated_obj) {
587  update_(updated_obj);
588  setup();
589 }
590 
591 //==============================================================================
593  const std::vector<CollisionObject*>& updated_objs) {
594  for (size_t i = 0, size = updated_objs.size(); i < size; ++i)
595  update_(updated_objs[i]);
596  setup();
597 }
598 
599 //==============================================================================
601  dtree.clear();
602  table.clear();
603 }
604 
605 //==============================================================================
607  std::vector<CollisionObject*>& objs) const {
608  objs.resize(this->size());
610  table.begin(), table.end(), objs.begin(),
611  std::bind(&DynamicAABBTable::value_type::first, std::placeholders::_1));
612 }
613 
614 //==============================================================================
617  callback->init();
618  if (size() == 0) return;
619  switch (obj->collisionGeometry()->getNodeType()) {
620 #if COAL_HAVE_OCTOMAP
621  case GEOM_OCTREE: {
623  const OcTree* octree =
624  static_cast<const OcTree*>(obj->collisionGeometryPtr());
626  dtree.getNodes(), dtree.getRoot(), octree, octree->getRoot(),
627  octree->getRootBV(), obj->getTransform(), callback);
628  } else
630  dtree.getNodes(), dtree.getRoot(), obj, callback);
631  } break;
632 #endif
633  default:
635  dtree.getNodes(), dtree.getRoot(), obj, callback);
636  }
637 }
638 
639 //==============================================================================
642  callback->init();
643  if (size() == 0) return;
644  CoalScalar min_dist = (std::numeric_limits<CoalScalar>::max)();
645  switch (obj->collisionGeometry()->getNodeType()) {
646 #if COAL_HAVE_OCTOMAP
647  case GEOM_OCTREE: {
649  const OcTree* octree =
650  static_cast<const OcTree*>(obj->collisionGeometryPtr());
652  dtree.getNodes(), dtree.getRoot(), octree, octree->getRoot(),
653  octree->getRootBV(), obj->getTransform(), callback, min_dist);
654  } else
656  dtree.getNodes(), dtree.getRoot(), obj, callback, min_dist);
657  } break;
658 #endif
659  default:
661  dtree.getNodes(), dtree.getRoot(), obj, callback, min_dist);
662  }
663 }
664 
665 //==============================================================================
668  callback->init();
669  if (size() == 0) return;
671  dtree.getNodes(), dtree.getRoot(), callback);
672 }
673 
674 //==============================================================================
677  callback->init();
678  if (size() == 0) return;
679  CoalScalar min_dist = (std::numeric_limits<CoalScalar>::max)();
681  dtree.getNodes(), dtree.getRoot(), callback, min_dist);
682 }
683 
684 //==============================================================================
686  BroadPhaseCollisionManager* other_manager_,
688  callback->init();
689  DynamicAABBTreeArrayCollisionManager* other_manager =
690  static_cast<DynamicAABBTreeArrayCollisionManager*>(other_manager_);
691  if ((size() == 0) || (other_manager->size() == 0)) return;
693  dtree.getNodes(), dtree.getRoot(), other_manager->dtree.getNodes(),
694  other_manager->dtree.getRoot(), callback);
695 }
696 
697 //==============================================================================
699  BroadPhaseCollisionManager* other_manager_,
701  callback->init();
702  DynamicAABBTreeArrayCollisionManager* other_manager =
703  static_cast<DynamicAABBTreeArrayCollisionManager*>(other_manager_);
704  if ((size() == 0) || (other_manager->size() == 0)) return;
705  CoalScalar min_dist = (std::numeric_limits<CoalScalar>::max)();
707  dtree.getNodes(), dtree.getRoot(), other_manager->dtree.getNodes(),
708  other_manager->dtree.getRoot(), callback, min_dist);
709 }
710 
711 //==============================================================================
713  return dtree.empty();
714 }
715 
716 //==============================================================================
718  return dtree.size();
719 }
720 
721 //==============================================================================
724  return dtree;
725 }
726 
727 } // namespace coal
coal::detail::implementation_array::NodeBase::data
void * data
Definition: coal/broadphase/detail/node_base_array.h:60
coal::DynamicAABBTreeArrayCollisionManager::table
std::unordered_map< CollisionObject *, size_t > table
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:135
octree.h
coal::DynamicAABBTreeArrayCollisionManager::registerObject
void registerObject(CollisionObject *obj)
add one object to the manager
Definition: broadphase_dynamic_AABB_tree_array.cpp:523
geometric_shapes.d1
float d1
Definition: scripts/geometric_shapes.py:31
coal::DynamicAABBTreeArrayCollisionManager::octree_as_geometry_distance
bool octree_as_geometry_distance
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:70
collision_manager.callback
callback
Definition: collision_manager.py:27
coal::detail::dynamic_AABB_tree_array::collisionRecurse
bool collisionRecurse(DynamicAABBTreeArrayCollisionManager::DynamicAABBNode *nodes1, size_t root1_id, DynamicAABBTreeArrayCollisionManager::DynamicAABBNode *nodes2, size_t root2_id, CollisionCallBackBase *callback)
Definition: broadphase_dynamic_AABB_tree_array.cpp:228
collision_manager.box
box
Definition: collision_manager.py:11
coal::detail::implementation_array::select
size_t select(size_t query, size_t node1, size_t node2, NodeBase< BV > *nodes)
select the node from node1 and node2 which is close to the query-th node in the nodes....
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:933
coal::DynamicAABBTreeArrayCollisionManager::size
size_t size() const
the number of objects managed by the manager
Definition: broadphase_dynamic_AABB_tree_array.cpp:717
coal::AABB::distance
CoalScalar distance(const AABB &other) const
Distance between two AABBs.
Definition: AABB.cpp:114
coal::CollisionObject::collisionGeometryPtr
const CollisionGeometry * collisionGeometryPtr() const
get raw pointer to collision geometry of the object instance
Definition: coal/collision_object.h:319
coal::CollisionObject::getTransform
const Transform3s & getTransform() const
get object's transform
Definition: coal/collision_object.h:290
coal::BroadPhaseCollisionManager
Base class for broad phase collision. It helps to accelerate the collision/distance between N objects...
Definition: coal/broadphase/broadphase_collision_manager.h:53
coal::DynamicAABBTreeArrayCollisionManager::tree_incremental_balance_pass
int tree_incremental_balance_pass
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:64
coal::detail::implementation_array::NodeBase::bv
BV bv
Definition: coal/broadphase/detail/node_base_array.h:51
coal::detail::implementation_array::NodeBase
Definition: coal/broadphase/detail/node_base_array.h:50
coal::DynamicAABBTreeArrayCollisionManager::octree_as_geometry_collide
bool octree_as_geometry_collide
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:69
coal::detail::dynamic_AABB_tree_array::selfDistanceRecurse
bool selfDistanceRecurse(DynamicAABBTreeArrayCollisionManager::DynamicAABBNode *nodes, size_t root_id, DistanceCallBackBase *callback, CoalScalar &min_dist)
Definition: broadphase_dynamic_AABB_tree_array.cpp:425
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::BroadPhaseCollisionManager::getObjects
virtual std::vector< CollisionObject * > getObjects() const
return the objects managed by the manager
Definition: coal/broadphase/broadphase_collision_manager.h:87
coal::DynamicAABBTreeArrayCollisionManager::distance
void distance(CollisionObject *obj, DistanceCallBackBase *callback) const
perform distance computation between one object and all the objects belonging to the manager
Definition: broadphase_dynamic_AABB_tree_array.cpp:640
coal::detail::dynamic_AABB_tree_array::distanceRecurse
bool distanceRecurse(DynamicAABBTreeArrayCollisionManager::DynamicAABBNode *nodes1, size_t root1_id, DynamicAABBTreeArrayCollisionManager::DynamicAABBNode *nodes2, size_t root2_id, DistanceCallBackBase *callback, CoalScalar &min_dist)
Definition: broadphase_dynamic_AABB_tree_array.cpp:306
coal::DynamicAABBTreeArrayCollisionManager::empty
bool empty() const
whether the manager is empty
Definition: broadphase_dynamic_AABB_tree_array.cpp:712
octree
Definition: octree.py:1
coal::DynamicAABBTreeArrayCollisionManager::update_
void update_(CollisionObject *updated_obj)
Definition: broadphase_dynamic_AABB_tree_array.cpp:573
coal::BroadPhaseCollisionManager::registerObjects
virtual void registerObjects(const std::vector< CollisionObject * > &other_objs)
add objects to the manager
Definition: broadphase_collision_manager.cpp:54
coal::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: coal/BV/AABB.h:55
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::DynamicAABBTreeArrayCollisionManager::tree_topdown_level
int * tree_topdown_level
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:66
coal::constructBox
COAL_DLLAPI void constructBox(const AABB &bv, Box &box, Transform3s &tf)
construct a box shape (with a configuration) from a given bounding volume
Definition: geometric_shapes_utility.cpp:1011
coal::DynamicAABBTreeArrayCollisionManager::collide
void collide(CollisionObject *obj, CollisionCallBackBase *callback) const
perform collision test between one object and all the objects belonging to the manager
Definition: broadphase_dynamic_AABB_tree_array.cpp:615
coal::DynamicAABBTreeArrayCollisionManager
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:54
d
d
coal::DynamicAABBTreeArrayCollisionManager::DynamicAABBTreeArrayCollisionManager
DynamicAABBTreeArrayCollisionManager()
Definition: broadphase_dynamic_AABB_tree_array.cpp:481
coal::transform
COAL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3s &tf)
Definition: geometric_shapes_utility.cpp:248
coal::detail::implementation_array::NodeBase::isLeaf
bool isLeaf() const
Definition: coal/broadphase/detail/node_base_array-inl.h:51
coal::computeChildBV
static void computeChildBV(const AABB &root_bv, unsigned int i, AABB &child_bv)
compute the bounding volume of an octree node's i-th child
Definition: coal/octree.h:299
coal::detail::dynamic_AABB_tree_array::selfCollisionRecurse
bool selfCollisionRecurse(DynamicAABBTreeArrayCollisionManager::DynamicAABBNode *nodes, size_t root_id, CollisionCallBackBase *callback)
Definition: broadphase_dynamic_AABB_tree_array.cpp:288
coal::DynamicAABBTreeArrayCollisionManager::DynamicAABBNode
detail::implementation_array::NodeBase< AABB > DynamicAABBNode
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:60
coal::Transform3s::Identity
static Transform3s Identity()
Definition: coal/math/transform.h:68
coal::DynamicAABBTreeArrayCollisionManager::tree_init_level
int tree_init_level
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:67
coal::DistanceCallBackBase
Base callback class for distance queries. This class can be supersed by child classes to provide desi...
Definition: coal/broadphase/broadphase_callbacks.h:72
coal::DynamicAABBTreeArrayCollisionManager::max_tree_nonbalanced_level
int max_tree_nonbalanced_level
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:63
coal::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: coal/collision_object.h:214
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
coal::DynamicAABBTreeArrayCollisionManager::clear
void clear()
clear the manager
Definition: broadphase_dynamic_AABB_tree_array.cpp:600
coal::CollisionObject::getAABB
const AABB & getAABB() const
get the AABB in world space
Definition: coal/collision_object.h:252
coal::DynamicAABBTreeArrayCollisionManager::setup
void setup()
initialize the manager, related with the specific type of manager
Definition: broadphase_dynamic_AABB_tree_array.cpp:538
broadphase_dynamic_AABB_tree_array.h
coal::GEOM_OCTREE
@ GEOM_OCTREE
Definition: coal/collision_object.h:83
coal::OcTree::OcTreeNode
octomap::OcTreeNode OcTreeNode
Definition: coal/octree.h:63
coal::OcTree
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: coal/octree.h:53
coal::DynamicAABBTreeArrayCollisionManager::dtree
detail::implementation_array::HierarchyTree< AABB > dtree
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:134
coal::detail::implementation_array::NodeBase::parent
size_t parent
Definition: coal/broadphase/detail/node_base_array.h:54
coal::DynamicAABBTreeArrayCollisionManager::update
virtual void update()
update the condition of manager
Definition: broadphase_dynamic_AABB_tree_array.cpp:559
coal::DynamicAABBTreeArrayCollisionManager::registerObjects
void registerObjects(const std::vector< CollisionObject * > &other_objs)
add objects to the manager
Definition: broadphase_dynamic_AABB_tree_array.cpp:497
coal::DynamicAABBTreeArrayCollisionManager::unregisterObject
void unregisterObject(CollisionObject *obj)
remove one object from the manager
Definition: broadphase_dynamic_AABB_tree_array.cpp:530
coal::convertBV
static void convertBV(const BV1 &bv1, const Transform3s &tf1, BV2 &bv2)
Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity...
Definition: coal/BV/BV.h:276
coal::DynamicAABBTreeArrayCollisionManager::tree_topdown_balance_threshold
int * tree_topdown_balance_threshold
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:65
coal::detail::implementation_array::HierarchyTree
Class for hierarchy tree structure.
Definition: coal/broadphase/detail/hierarchy_tree_array.h:58
coal::CollisionCallBackBase
Base callback class for collision queries. This class can be supersed by child classes to provide des...
Definition: coal/broadphase/broadphase_callbacks.h:49
coal::DynamicAABBTreeArrayCollisionManager::getTree
const detail::implementation_array::HierarchyTree< AABB > & getTree() const
Definition: broadphase_dynamic_AABB_tree_array.cpp:723
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::DynamicAABBTreeArrayCollisionManager::setup_
bool setup_
Definition: coal/broadphase/broadphase_dynamic_AABB_tree_array.h:137
coal::CollisionObject::collisionGeometry
const shared_ptr< const CollisionGeometry > collisionGeometry() const
get shared pointer to collision geometry of the object instance
Definition: coal/collision_object.h:311
coal::detail::implementation_array::NodeBase::children
size_t children[2]
Definition: coal/broadphase/detail/node_base_array.h:59


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