38 #ifndef FCL_BROAD_PHASE_DYNAMIC_AABB_TREE_INL_H
39 #define FCL_BROAD_PHASE_DYNAMIC_AABB_TREE_INL_H
57 namespace dynamic_AABB_tree {
63 bool collisionRecurse_(
65 const OcTree<S>* tree2,
66 const typename OcTree<S>::OcTreeNode* root2,
99 if(collisionRecurse_<S>(root1->
children[0], tree2,
nullptr, root2_bv, tf2, cdata, callback))
101 if(collisionRecurse_<S>(root1->
children[1], tree2,
nullptr, root2_bv, tf2, cdata, callback))
107 else if(root1->
isLeaf() && !tree2->nodeHasChildren(root2))
111 if(!tree2->isNodeFree(root2) && !
obj1->isFree())
127 return callback(
obj1, &
obj2, cdata);
138 if(tree2->isNodeFree(root2) || !obb1.
overlap(obb2))
return false;
140 if(!tree2->nodeHasChildren(root2) || (!root1->
isLeaf() && (root1->
bv.size() > root2_bv.
size())))
142 if(collisionRecurse_(root1->
children[0], tree2, root2, root2_bv, tf2, cdata, callback))
144 if(collisionRecurse_(root1->
children[1], tree2, root2, root2_bv, tf2, cdata, callback))
149 for(
unsigned int i = 0; i < 8; ++i)
151 if(tree2->nodeChildExists(root2, i))
153 const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
155 computeChildBV(root2_bv, i, child_bv);
157 if(collisionRecurse_(root1, tree2, child, child_bv, tf2, cdata, callback))
163 computeChildBV(root2_bv, i, child_bv);
164 if(collisionRecurse_<S>(root1, tree2,
nullptr, child_bv, tf2, cdata, callback))
173 template <
typename S,
typename Derived>
175 bool collisionRecurse_(
177 const OcTree<S>* tree2,
178 const typename OcTree<S>::OcTreeNode* root2,
180 const Eigen::MatrixBase<Derived>& translation2,
193 if(root1->
bv.overlap(root2_bv_t))
198 tf2.translation() = translation2;
204 return callback(
obj1, &
obj2, cdata);
210 if(collisionRecurse_<S>(root1->
children[0], tree2,
nullptr, root2_bv, translation2, cdata, callback))
212 if(collisionRecurse_<S>(root1->
children[1], tree2,
nullptr, root2_bv, translation2, cdata, callback))
218 else if(root1->
isLeaf() && !tree2->nodeHasChildren(root2))
222 if(!tree2->isNodeFree(root2) && !
obj1->isFree())
225 if(root1->
bv.overlap(root2_bv_t))
230 tf2.translation() = translation2;
237 return callback(
obj1, &
obj2, cdata);
245 if(tree2->isNodeFree(root2) || !root1->
bv.overlap(root2_bv_t))
return false;
247 if(!tree2->nodeHasChildren(root2) || (!root1->
isLeaf() && (root1->
bv.size() > root2_bv.
size())))
249 if(collisionRecurse_(root1->
children[0], tree2, root2, root2_bv, translation2, cdata, callback))
251 if(collisionRecurse_(root1->
children[1], tree2, root2, root2_bv, translation2, cdata, callback))
256 for(
unsigned int i = 0; i < 8; ++i)
258 if(tree2->nodeChildExists(root2, i))
260 const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
262 computeChildBV(root2_bv, i, child_bv);
264 if(collisionRecurse_(root1, tree2, child, child_bv, translation2, cdata, callback))
270 computeChildBV(root2_bv, i, child_bv);
271 if(collisionRecurse_<S>(root1, tree2,
nullptr, child_bv, translation2, cdata, callback))
280 template <
typename S>
282 bool distanceRecurse_(
284 const OcTree<S>* tree2,
285 const typename OcTree<S>::OcTreeNode* root2,
292 if(root1->
isLeaf() && !tree2->nodeHasChildren(root2))
294 if(tree2->isNodeOccupied(root2))
305 if(!tree2->isNodeOccupied(root2))
return false;
307 if(!tree2->nodeHasChildren(root2) || (!root1->
isLeaf() && (root1->
bv.size() > root2_bv.
size())))
319 if(distanceRecurse_(root1->
children[1], tree2, root2, root2_bv, tf2, cdata, callback, min_dist))
325 if(distanceRecurse_(root1->
children[0], tree2, root2, root2_bv, tf2, cdata, callback, min_dist))
333 if(distanceRecurse_(root1->
children[0], tree2, root2, root2_bv, tf2, cdata, callback, min_dist))
339 if(distanceRecurse_(root1->
children[1], tree2, root2, root2_bv, tf2, cdata, callback, min_dist))
346 for(
unsigned int i = 0; i < 8; ++i)
348 if(tree2->nodeChildExists(root2, i))
350 const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
352 computeChildBV(root2_bv, i, child_bv);
356 S d = root1->
bv.distance(aabb2);
360 if(distanceRecurse_(root1, tree2, child, child_bv, tf2, cdata, callback, min_dist))
371 template <
typename S>
375 const OcTree<S>* tree2,
376 const typename OcTree<S>::OcTreeNode* root2,
382 if(tf2.linear().isIdentity())
383 return collisionRecurse_(root1, tree2, root2, root2_bv, tf2.translation(), cdata, callback);
385 return collisionRecurse_(root1, tree2, root2, root2_bv, tf2, cdata, callback);
389 template <
typename S,
typename Derived>
391 bool distanceRecurse_(
393 const OcTree<S>* tree2,
394 const typename OcTree<S>::OcTreeNode* root2,
396 const Eigen::MatrixBase<Derived>& translation2,
401 if(root1->
isLeaf() && !tree2->nodeHasChildren(root2))
403 if(tree2->isNodeOccupied(root2))
408 tf2.translation() = translation2;
416 if(!tree2->isNodeOccupied(root2))
return false;
418 if(!tree2->nodeHasChildren(root2) || (!root1->
isLeaf() && (root1->
bv.size() > root2_bv.
size())))
428 if(distanceRecurse_(root1->
children[1], tree2, root2, root2_bv, translation2, cdata, callback, min_dist))
434 if(distanceRecurse_(root1->
children[0], tree2, root2, root2_bv, translation2, cdata, callback, min_dist))
442 if(distanceRecurse_(root1->
children[0], tree2, root2, root2_bv, translation2, cdata, callback, min_dist))
448 if(distanceRecurse_(root1->
children[1], tree2, root2, root2_bv, translation2, cdata, callback, min_dist))
455 for(
unsigned int i = 0; i < 8; ++i)
457 if(tree2->nodeChildExists(root2, i))
459 const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
461 computeChildBV(root2_bv, i, child_bv);
464 S d = root1->
bv.distance(aabb2);
468 if(distanceRecurse_(root1, tree2, child, child_bv, translation2, cdata, callback, min_dist))
479 template <
typename S>
483 if(tf2.linear().isIdentity())
484 return distanceRecurse_(root1, tree2, root2, root2_bv, tf2.translation(), cdata, callback, min_dist);
486 return distanceRecurse_(root1, tree2, root2, root2_bv, tf2, cdata, callback, min_dist);
492 template <
typename S>
502 if(!root1->
bv.overlap(root2->
bv))
return false;
506 if(!root1->
bv.overlap(root2->
bv))
return false;
508 if(root2->
isLeaf() || (!root1->
isLeaf() && (root1->
bv.size() > root2->
bv.size())))
526 template <
typename S>
532 if(!root->
bv.overlap(query->
getAABB()))
return false;
536 if(!root->
bv.overlap(query->
getAABB()))
return false;
550 template <
typename S>
554 if(root->
isLeaf())
return false;
569 template <
typename S>
582 return callback(root1_obj, root2_obj, cdata, min_dist);
585 if(root2->
isLeaf() || (!root1->
isLeaf() && (root1->
bv.size() > root2->
bv.size())))
587 S d1 = root2->
bv.distance(root1->
children[0]->bv);
588 S d2 = root2->
bv.distance(root1->
children[1]->bv);
621 S d1 = root1->
bv.distance(root2->
children[0]->bv);
622 S d2 = root1->
bv.distance(root2->
children[1]->bv);
658 template <
typename S>
665 return callback(root_obj, query, cdata, min_dist);
704 template <
typename S>
708 if(root->
isLeaf())
return false;
727 template <
typename S>
730 : tree_topdown_balance_threshold(dtree.bu_threshold),
731 tree_topdown_level(dtree.topdown_level)
746 template <
typename S>
751 if(other_objs.empty())
return;
759 std::vector<DynamicAABBNode*> leaves(other_objs.size());
760 table.rehash(other_objs.size());
761 for(
size_t i = 0, size = other_objs.size(); i < size; ++i)
764 node->
bv = other_objs[i]->getAABB();
767 node->
data = other_objs[i];
768 table[other_objs[i]] = node;
772 dtree.init(leaves, tree_init_level);
779 template <
typename S>
788 template <
typename S>
798 template <
typename S>
804 int num = dtree.size();
811 int height = dtree.getMaxHeight();
814 if(height - std::log((S)num) / std::log(2.0) < max_tree_nonbalanced_level)
815 dtree.balanceIncremental(tree_incremental_balance_pass);
817 dtree.balanceTopdown();
824 template <
typename S>
828 for(
auto it = table.cbegin(); it != table.cend(); ++it)
832 node->
bv =
obj->getAABB();
842 template <
typename S>
846 const auto it = table.find(updated_obj);
847 if(it != table.end())
850 if(!node->
bv.equal(updated_obj->
getAABB()))
851 dtree.update(node, updated_obj->
getAABB());
857 template <
typename S>
861 update_(updated_obj);
866 template <
typename S>
870 for(
size_t i = 0, size = updated_objs.size(); i < size; ++i)
871 update_(updated_objs[i]);
876 template <
typename S>
885 template <
typename S>
889 objs.resize(this->size());
890 std::transform(table.begin(), table.end(), objs.begin(), std::bind(&DynamicAABBTable::value_type::first, std::placeholders::_1));
894 template <
typename S>
898 if(size() == 0)
return;
899 switch(
obj->collisionGeometry()->getNodeType())
904 if(!octree_as_geometry_collide)
906 const OcTree<S>* octree =
static_cast<const OcTree<S>*
>(
obj->collisionGeometry().get());
920 template <
typename S>
924 if(size() == 0)
return;
926 switch(
obj->collisionGeometry()->getNodeType())
931 if(!octree_as_geometry_distance)
933 const OcTree<S>* octree =
static_cast<const OcTree<S>*
>(
obj->collisionGeometry().get());
947 template <
typename S>
951 if(size() == 0)
return;
956 template <
typename S>
960 if(size() == 0)
return;
966 template <
typename S>
971 if((size() == 0) || (other_manager->
size() == 0))
return;
976 template <
typename S>
981 if((size() == 0) || (other_manager->
size() == 0))
return;
987 template <
typename S>
991 return dtree.empty();
995 template <
typename S>
1003 template <
typename S>