38 #ifndef FCL_BROAD_PHASE_DYNAMIC_AABB_TREE_ARRAY_INL_H 
   39 #define FCL_BROAD_PHASE_DYNAMIC_AABB_TREE_ARRAY_INL_H 
   57 namespace dynamic_AABB_tree_array
 
   65 bool collisionRecurse_(
 
   68     const OcTree<S>* tree2,
 
   69     const typename OcTree<S>::OcTreeNode* root2,
 
  103       if(collisionRecurse_<S>(nodes1, root1->
children[0], tree2, 
nullptr, root2_bv, tf2, cdata, callback))
 
  105       if(collisionRecurse_<S>(nodes1, root1->
children[1], tree2, 
nullptr, root2_bv, tf2, cdata, callback))
 
  111   else if(root1->
isLeaf() && !tree2->nodeHasChildren(root2))
 
  114     if(!tree2->isNodeFree(root2) && !
obj1->isFree())
 
  130         return callback(
obj1, &
obj2, cdata);
 
  141   if(tree2->isNodeFree(root2) || !obb1.
overlap(obb2)) 
return false;
 
  143   if(!tree2->nodeHasChildren(root2) || (!root1->
isLeaf() && (root1->
bv.size() > root2_bv.
size())))
 
  145     if(collisionRecurse_(nodes1, root1->
children[0], tree2, root2, root2_bv, tf2, cdata, callback))
 
  147     if(collisionRecurse_(nodes1, root1->
children[1], tree2, root2, root2_bv, tf2, cdata, callback))
 
  152     for(
unsigned int i = 0; i < 8; ++i)
 
  154       if(tree2->nodeChildExists(root2, i))
 
  156         const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
 
  158         computeChildBV(root2_bv, i, child_bv);
 
  160         if(collisionRecurse_(nodes1, root1_id, tree2, child, child_bv, tf2, cdata, callback))
 
  166         computeChildBV(root2_bv, i, child_bv);
 
  167         if(collisionRecurse_<S>(nodes1, root1_id, tree2, 
nullptr, child_bv, tf2, cdata, callback))
 
  177 template <
typename S, 
typename Derived>
 
  179 bool collisionRecurse_(
 
  182     const OcTree<S>* tree2,
 
  183     const typename OcTree<S>::OcTreeNode* root2,
 
  185     const Eigen::MatrixBase<Derived>& translation2,
 
  199         if(root1->
bv.overlap(root_bv_t))
 
  204           tf2.translation() = translation2;
 
  210           return callback(
obj1, &
obj2, cdata);
 
  216       if(collisionRecurse_<S>(nodes1, root1->
children[0], tree2, 
nullptr, root2_bv, translation2, cdata, callback))
 
  218       if(collisionRecurse_<S>(nodes1, root1->
children[1], tree2, 
nullptr, root2_bv, translation2, cdata, callback))
 
  224   else if(root1->
isLeaf() && !tree2->nodeHasChildren(root2))
 
  227     if(!tree2->isNodeFree(root2) && !
obj1->isFree())
 
  230       if(root1->
bv.overlap(root_bv_t))
 
  235         tf2.translation() = translation2;
 
  242         return callback(
obj1, &
obj2, cdata);
 
  250   if(tree2->isNodeFree(root2) || !root1->
bv.overlap(root_bv_t)) 
return false;
 
  252   if(!tree2->nodeHasChildren(root2) || (!root1->
isLeaf() && (root1->
bv.size() > root2_bv.
size())))
 
  254     if(collisionRecurse_(nodes1, root1->
children[0], tree2, root2, root2_bv, translation2, cdata, callback))
 
  256     if(collisionRecurse_(nodes1, root1->
children[1], tree2, root2, root2_bv, translation2, cdata, callback))
 
  261     for(
unsigned int i = 0; i < 8; ++i)
 
  263       if(tree2->nodeChildExists(root2, i))
 
  265         const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
 
  267         computeChildBV(root2_bv, i, child_bv);
 
  269         if(collisionRecurse_(nodes1, root1_id, tree2, child, child_bv, translation2, cdata, callback))
 
  275         computeChildBV(root2_bv, i, child_bv);
 
  276         if(collisionRecurse_<S>(nodes1, root1_id, tree2, 
nullptr, child_bv, translation2, cdata, callback))
 
  286 template <
typename S>
 
  291   if(root1->
isLeaf() && !tree2->nodeHasChildren(root2))
 
  293     if(tree2->isNodeOccupied(root2))
 
  304   if(!tree2->isNodeOccupied(root2)) 
return false;
 
  306   if(!tree2->nodeHasChildren(root2) || (!root1->
isLeaf() && (root1->
bv.size() > root2_bv.
size())))
 
  318         if(distanceRecurse_(nodes1, root1->
children[1], tree2, root2, root2_bv, tf2, cdata, callback, min_dist))
 
  324         if(distanceRecurse_(nodes1, root1->
children[0], tree2, root2, root2_bv, tf2, cdata, callback, min_dist))
 
  332         if(distanceRecurse_(nodes1, root1->
children[0], tree2, root2, root2_bv, tf2, cdata, callback, min_dist))
 
  338         if(distanceRecurse_(nodes1, root1->
children[1], tree2, root2, root2_bv, tf2, cdata, callback, min_dist))
 
  345     for(
unsigned int i = 0; i < 8; ++i)
 
  347       if(tree2->nodeChildExists(root2, i))
 
  349         const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
 
  351         computeChildBV(root2_bv, i, child_bv);
 
  355         S d = root1->
bv.distance(aabb2);
 
  359           if(distanceRecurse_(nodes1, root1_id, tree2, child, child_bv, tf2, cdata, callback, min_dist))
 
  370 template <
typename S, 
typename Derived>
 
  372 bool distanceRecurse_(
 
  375     const OcTree<S>* tree2,
 
  376     const typename OcTree<S>::OcTreeNode* root2,
 
  378     const Eigen::MatrixBase<Derived>& translation2,
 
  384   if(root1->
isLeaf() && !tree2->nodeHasChildren(root2))
 
  386     if(tree2->isNodeOccupied(root2))
 
  391       tf2.translation() = translation2;
 
  399   if(!tree2->isNodeOccupied(root2)) 
return false;
 
  401   if(!tree2->nodeHasChildren(root2) || (!root1->
isLeaf() && (root1->
bv.size() > root2_bv.
size())))
 
  412         if(distanceRecurse_(nodes1, root1->
children[1], tree2, root2, root2_bv, translation2, cdata, callback, min_dist))
 
  418         if(distanceRecurse_(nodes1, root1->
children[0], tree2, root2, root2_bv, translation2, cdata, callback, min_dist))
 
  426         if(distanceRecurse_(nodes1, root1->
children[0], tree2, root2, root2_bv, translation2, cdata, callback, min_dist))
 
  432         if(distanceRecurse_(nodes1, root1->
children[1], tree2, root2, root2_bv, translation2, cdata, callback, min_dist))
 
  439     for(
unsigned int i = 0; i < 8; ++i)
 
  441       if(tree2->nodeChildExists(root2, i))
 
  443         const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
 
  445         computeChildBV(root2_bv, i, child_bv);
 
  448         S d = root1->
bv.distance(aabb2);
 
  452           if(distanceRecurse_(nodes1, root1_id, tree2, child, child_bv, translation2, cdata, callback, min_dist))
 
  466 template <
typename S>
 
  476     if(!root1->
bv.overlap(root2->
bv)) 
return false;
 
  480   if(!root1->
bv.overlap(root2->
bv)) 
return false;
 
  482   if(root2->
isLeaf() || (!root1->
isLeaf() && (root1->
bv.size() > root2->
bv.size())))
 
  500 template <
typename S>
 
  507     if(!root->
bv.overlap(query->
getAABB())) 
return false;
 
  511   if(!root->
bv.overlap(query->
getAABB())) 
return false;
 
  525 template <
typename S>
 
  530   if(root->
isLeaf()) 
return false;
 
  545 template <
typename S>
 
  557     return callback(root1_obj, root2_obj, cdata, min_dist);
 
  560   if(root2->
isLeaf() || (!root1->
isLeaf() && (root1->
bv.size() > root2->
bv.size())))
 
  562     S d1 = root2->
bv.distance((nodes1 + root1->
children[0])->bv);
 
  563     S d2 = root2->
bv.distance((nodes1 + root1->
children[1])->bv);
 
  596     S d1 = root1->
bv.distance((nodes2 + root2->
children[0])->bv);
 
  597     S d2 = root1->
bv.distance((nodes2 + root2->
children[1])->bv);
 
  633 template <
typename S>
 
  641     return callback(root_obj, query, cdata, min_dist);
 
  680 template <
typename S>
 
  685   if(root->
isLeaf()) 
return false;
 
  703 template <
typename S>
 
  707   if(tf2.linear().isIdentity())
 
  708     return collisionRecurse_(nodes1, root1_id, tree2, root2, root2_bv, tf2.translation(), cdata, callback);
 
  710     return collisionRecurse_(nodes1, root1_id, tree2, root2, root2_bv, tf2, cdata, callback);
 
  714 template <
typename S>
 
  718   if(tf2.linear().isIdentity())
 
  719     return distanceRecurse_(nodes1, root1_id, tree2, root2, root2_bv, tf2.translation(), cdata, callback, min_dist);
 
  721     return distanceRecurse_(nodes1, root1_id, tree2, root2, root2_bv, tf2, cdata, callback, min_dist);
 
  731 template <
typename S>
 
  734   : tree_topdown_balance_threshold(dtree.bu_threshold),
 
  735     tree_topdown_level(dtree.topdown_level)
 
  750 template <
typename S>
 
  755   if(other_objs.empty()) 
return;
 
  764     table.rehash(other_objs.size());
 
  765     for(
size_t i = 0, size = other_objs.size(); i < size; ++i)
 
  767       leaves[i].
bv = other_objs[i]->getAABB();
 
  768       leaves[i].
parent = dtree.NULL_NODE;
 
  769       leaves[i].
children[1] = dtree.NULL_NODE;
 
  770       leaves[i].
data = other_objs[i];
 
  771       table[other_objs[i]] = i;
 
  774     int n_leaves = other_objs.size();
 
  776     dtree.init(leaves, n_leaves, tree_init_level);
 
  783 template <
typename S>
 
  787   size_t node = dtree.insert(
obj->getAABB(), 
obj);
 
  792 template <
typename S>
 
  796   size_t node = table[
obj];
 
  802 template <
typename S>
 
  808     int num = dtree.size();
 
  815     int height = dtree.getMaxHeight();
 
  818     if(height - std::log((S)num) / std::log(2.0) < max_tree_nonbalanced_level)
 
  819       dtree.balanceIncremental(tree_incremental_balance_pass);
 
  821       dtree.balanceTopdown();
 
  828 template <
typename S>
 
  832   for(
auto it = table.cbegin(), end = table.cend(); it != end; ++it)
 
  835     size_t node = it->second;
 
  836     dtree.getNodes()[node].bv = 
obj->getAABB();
 
  846 template <
typename S>
 
  850   const auto it = table.find(updated_obj);
 
  851   if(it != table.end())
 
  853     size_t node = it->second;
 
  854     if(!dtree.getNodes()[node].bv.equal(updated_obj->
getAABB()))
 
  855       dtree.update(node, updated_obj->
getAABB());
 
  861 template <
typename S>
 
  865   update_(updated_obj);
 
  870 template <
typename S>
 
  874   for(
size_t i = 0, size = updated_objs.size(); i < size; ++i)
 
  875     update_(updated_objs[i]);
 
  880 template <
typename S>
 
  889 template <
typename S>
 
  893   objs.resize(this->size());
 
  894   std::transform(table.begin(), table.end(), objs.begin(), std::bind(&DynamicAABBTable::value_type::first, std::placeholders::_1));
 
  898 template <
typename S>
 
  902   if(size() == 0) 
return;
 
  903   switch(
obj->collisionGeometry()->getNodeType())
 
  908       if(!octree_as_geometry_collide)
 
  910         const OcTree<S>* octree = 
static_cast<const OcTree<S>*
>(
obj->collisionGeometry().get());
 
  924 template <
typename S>
 
  928   if(size() == 0) 
return;
 
  930   switch(
obj->collisionGeometry()->getNodeType())
 
  935       if(!octree_as_geometry_distance)
 
  937         const OcTree<S>* octree = 
static_cast<const OcTree<S>*
>(
obj->collisionGeometry().get());
 
  951 template <
typename S>
 
  955   if(size() == 0) 
return;
 
  960 template <
typename S>
 
  964   if(size() == 0) 
return;
 
  970 template <
typename S>
 
  975   if((size() == 0) || (other_manager->
size() == 0)) 
return;
 
  980 template <
typename S>
 
  985   if((size() == 0) || (other_manager->
size() == 0)) 
return;
 
  991 template <
typename S>
 
  995   return dtree.empty();
 
  999 template <
typename S>
 
 1003   return dtree.size();
 
 1007 template <
typename S>