broadphase_interval_tree.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00037 #include "fcl/broadphase/broadphase_interval_tree.h"
00038 #include <algorithm>
00039 #include <limits>
00040 #include <boost/bind.hpp>
00041 
00042 namespace fcl
00043 {
00044 
00045 void IntervalTreeCollisionManager::unregisterObject(CollisionObject* obj)
00046 {
00047   // must sorted before
00048   setup();
00049 
00050   EndPoint p;
00051   p.value = obj->getAABB().min_[0];
00052   std::vector<EndPoint>::iterator start1 = std::lower_bound(endpoints[0].begin(), endpoints[0].end(), p, boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00053   p.value = obj->getAABB().max_[0];
00054   std::vector<EndPoint>::iterator end1 = std::upper_bound(start1, endpoints[0].end(), p, boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00055 
00056   if(start1 < end1)
00057   {
00058     unsigned int start_id = start1 - endpoints[0].begin();
00059     unsigned int end_id = end1 - endpoints[0].begin();
00060     unsigned int cur_id = start_id;
00061     for(unsigned int i = start_id; i < end_id; ++i)
00062     {
00063       if(endpoints[0][i].obj != obj)
00064       {
00065         if(i == cur_id) cur_id++;
00066         else
00067         {
00068           endpoints[0][cur_id] = endpoints[0][i];
00069           cur_id++;
00070         }
00071       }
00072     }
00073     if(cur_id < end_id)
00074       endpoints[0].resize(endpoints[0].size() - 2);
00075   }
00076 
00077   p.value = obj->getAABB().min_[1];
00078   std::vector<EndPoint>::iterator start2 = std::lower_bound(endpoints[1].begin(), endpoints[1].end(), p, boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00079   p.value = obj->getAABB().max_[1];
00080   std::vector<EndPoint>::iterator end2 = std::upper_bound(start2, endpoints[1].end(), p, boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00081 
00082   if(start2 < end2)
00083   {
00084     unsigned int start_id = start2 - endpoints[1].begin();
00085     unsigned int end_id = end2 - endpoints[1].begin();
00086     unsigned int cur_id = start_id;
00087     for(unsigned int i = start_id; i < end_id; ++i)
00088     {
00089       if(endpoints[1][i].obj != obj)
00090       {
00091         if(i == cur_id) cur_id++;
00092         else
00093         {
00094           endpoints[1][cur_id] = endpoints[1][i];
00095           cur_id++;
00096         }
00097       }
00098     }
00099     if(cur_id < end_id)
00100       endpoints[1].resize(endpoints[1].size() - 2);
00101   }
00102 
00103 
00104   p.value = obj->getAABB().min_[2];
00105   std::vector<EndPoint>::iterator start3 = std::lower_bound(endpoints[2].begin(), endpoints[2].end(), p, boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00106   p.value = obj->getAABB().max_[2];
00107   std::vector<EndPoint>::iterator end3 = std::upper_bound(start3, endpoints[2].end(), p, boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00108 
00109   if(start3 < end3)
00110   {
00111     unsigned int start_id = start3 - endpoints[2].begin();
00112     unsigned int end_id = end3 - endpoints[2].begin();
00113     unsigned int cur_id = start_id;
00114     for(unsigned int i = start_id; i < end_id; ++i)
00115     {
00116       if(endpoints[2][i].obj != obj)
00117       {
00118         if(i == cur_id) cur_id++;
00119         else
00120         {
00121           endpoints[2][cur_id] = endpoints[2][i];
00122           cur_id++;
00123         }
00124       }
00125     }
00126     if(cur_id < end_id)
00127       endpoints[2].resize(endpoints[2].size() - 2);
00128   }
00129 
00130   // update the interval tree
00131   if(obj_interval_maps[0].find(obj) != obj_interval_maps[0].end())
00132   {
00133     SAPInterval* ivl1 = obj_interval_maps[0][obj];
00134     SAPInterval* ivl2 = obj_interval_maps[1][obj];
00135     SAPInterval* ivl3 = obj_interval_maps[2][obj];
00136 
00137     interval_trees[0]->deleteNode(ivl1);
00138     interval_trees[1]->deleteNode(ivl2);
00139     interval_trees[2]->deleteNode(ivl3);
00140 
00141     delete ivl1;
00142     delete ivl2;
00143     delete ivl3;
00144 
00145     obj_interval_maps[0].erase(obj);
00146     obj_interval_maps[1].erase(obj);             
00147     obj_interval_maps[2].erase(obj);
00148   }
00149 }
00150 
00151 void IntervalTreeCollisionManager::registerObject(CollisionObject* obj)
00152 {
00153   EndPoint p, q;
00154 
00155   p.obj = obj;
00156   q.obj = obj;
00157   p.minmax = 0;
00158   q.minmax = 1;
00159   p.value = obj->getAABB().min_[0];
00160   q.value = obj->getAABB().max_[0];
00161   endpoints[0].push_back(p);
00162   endpoints[0].push_back(q);
00163 
00164   p.value = obj->getAABB().min_[1];
00165   q.value = obj->getAABB().max_[1];
00166   endpoints[1].push_back(p);
00167   endpoints[1].push_back(q);
00168 
00169   p.value = obj->getAABB().min_[2];
00170   q.value = obj->getAABB().max_[2];
00171   endpoints[2].push_back(p);
00172   endpoints[2].push_back(q);
00173   setup_ = false;
00174 }
00175 
00176 void IntervalTreeCollisionManager::setup()
00177 {
00178   if(!setup_)
00179   {
00180     std::sort(endpoints[0].begin(), endpoints[0].end(), boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00181     std::sort(endpoints[1].begin(), endpoints[1].end(), boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00182     std::sort(endpoints[2].begin(), endpoints[2].end(), boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00183 
00184     for(int i = 0; i < 3; ++i)
00185       delete interval_trees[i];
00186 
00187     for(int i = 0; i < 3; ++i)
00188       interval_trees[i] = new IntervalTree;
00189 
00190     for(unsigned int i = 0, size = endpoints[0].size(); i < size; ++i)
00191     {
00192       EndPoint p = endpoints[0][i];
00193       CollisionObject* obj = p.obj;
00194       if(p.minmax == 0)
00195       {
00196         SAPInterval* ivl1 = new SAPInterval(obj->getAABB().min_[0], obj->getAABB().max_[0], obj);
00197         SAPInterval* ivl2 = new SAPInterval(obj->getAABB().min_[1], obj->getAABB().max_[1], obj);
00198         SAPInterval* ivl3 = new SAPInterval(obj->getAABB().min_[2], obj->getAABB().max_[2], obj);
00199 
00200         interval_trees[0]->insert(ivl1);
00201         interval_trees[1]->insert(ivl2);
00202         interval_trees[2]->insert(ivl3);
00203 
00204         obj_interval_maps[0][obj] = ivl1;
00205         obj_interval_maps[1][obj] = ivl2;
00206         obj_interval_maps[2][obj] = ivl3;
00207       }
00208     }
00209 
00210     setup_ = true;
00211   }
00212 }
00213 
00214 void IntervalTreeCollisionManager::update()
00215 {
00216   setup_ = false;
00217 
00218   for(unsigned int i = 0, size = endpoints[0].size(); i < size; ++i)
00219   {
00220     if(endpoints[0][i].minmax == 0)
00221       endpoints[0][i].value = endpoints[0][i].obj->getAABB().min_[0];
00222     else
00223       endpoints[0][i].value = endpoints[0][i].obj->getAABB().max_[0];
00224   }
00225 
00226   for(unsigned int i = 0, size = endpoints[1].size(); i < size; ++i)
00227   {
00228     if(endpoints[1][i].minmax == 0)
00229       endpoints[1][i].value = endpoints[1][i].obj->getAABB().min_[1];
00230     else
00231       endpoints[1][i].value = endpoints[1][i].obj->getAABB().max_[1];
00232   }
00233 
00234   for(unsigned int i = 0, size = endpoints[2].size(); i < size; ++i)
00235   {
00236     if(endpoints[2][i].minmax == 0)
00237       endpoints[2][i].value = endpoints[2][i].obj->getAABB().min_[2];
00238     else
00239       endpoints[2][i].value = endpoints[2][i].obj->getAABB().max_[2];
00240   }
00241 
00242   setup();
00243 
00244 }
00245 
00246 
00247 void IntervalTreeCollisionManager::update(CollisionObject* updated_obj)
00248 {
00249   AABB old_aabb;
00250   const AABB& new_aabb = updated_obj->getAABB();
00251   for(int i = 0; i < 3; ++i)
00252   {
00253     std::map<CollisionObject*, SAPInterval*>::const_iterator it = obj_interval_maps[i].find(updated_obj);
00254     interval_trees[i]->deleteNode(it->second);
00255     old_aabb.min_[i] = it->second->low;
00256     old_aabb.max_[i] = it->second->high;
00257     it->second->low = new_aabb.min_[i];
00258     it->second->high = new_aabb.max_[i];
00259     interval_trees[i]->insert(it->second);
00260   }
00261 
00262   EndPoint dummy;
00263   std::vector<EndPoint>::iterator it;
00264   for(int i = 0; i < 3; ++i)
00265   {
00266     dummy.value = old_aabb.min_[i];
00267     it = std::lower_bound(endpoints[i].begin(), endpoints[i].end(), dummy, boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00268     for(; it != endpoints[i].end(); ++it)
00269     {
00270       if(it->obj == updated_obj && it->minmax == 0)
00271       {
00272         it->value = new_aabb.min_[i];
00273         break;
00274       }
00275     }
00276 
00277     dummy.value = old_aabb.max_[i];
00278     it = std::lower_bound(endpoints[i].begin(), endpoints[i].end(), dummy, boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00279     for(; it != endpoints[i].end(); ++it)
00280     {
00281       if(it->obj == updated_obj && it->minmax == 0)
00282       {
00283         it->value = new_aabb.max_[i];
00284         break;
00285       }
00286     }         
00287 
00288     std::sort(endpoints[i].begin(), endpoints[i].end(), boost::bind(&EndPoint::value, _1) < boost::bind(&EndPoint::value, _2));
00289   }
00290 }
00291 
00292 void IntervalTreeCollisionManager::update(const std::vector<CollisionObject*>& updated_objs)
00293 {
00294   for(size_t i = 0; i < updated_objs.size(); ++i)
00295     update(updated_objs[i]);
00296 }
00297 
00298 void IntervalTreeCollisionManager::clear()
00299 {
00300   endpoints[0].clear();
00301   endpoints[1].clear();
00302   endpoints[2].clear();
00303 
00304   delete interval_trees[0]; interval_trees[0] = NULL;
00305   delete interval_trees[1]; interval_trees[1] = NULL;
00306   delete interval_trees[2]; interval_trees[2] = NULL;
00307 
00308   for(int i = 0; i < 3; ++i)
00309   {
00310     for(std::map<CollisionObject*, SAPInterval*>::const_iterator it = obj_interval_maps[i].begin(), end = obj_interval_maps[i].end();
00311         it != end; ++it)
00312     {
00313       delete it->second;
00314     }
00315   }
00316 
00317   for(int i = 0; i < 3; ++i)
00318     obj_interval_maps[i].clear();
00319 
00320   setup_ = false;
00321 }
00322 
00323 void IntervalTreeCollisionManager::getObjects(std::vector<CollisionObject*>& objs) const
00324 {
00325   objs.resize(endpoints[0].size() / 2);
00326   unsigned int j = 0;
00327   for(unsigned int i = 0, size = endpoints[0].size(); i < size; ++i)
00328   {
00329     if(endpoints[0][i].minmax == 0)
00330     {
00331       objs[j] = endpoints[0][i].obj; j++;
00332     }
00333   }
00334 }
00335 
00336 void IntervalTreeCollisionManager::collide(CollisionObject* obj, void* cdata, CollisionCallBack callback) const
00337 {
00338   if(size() == 0) return;
00339   collide_(obj, cdata, callback);
00340 }
00341 
00342 bool IntervalTreeCollisionManager::collide_(CollisionObject* obj, void* cdata, CollisionCallBack callback) const
00343 {
00344   static const unsigned int CUTOFF = 100;
00345 
00346   std::deque<SimpleInterval*> results0, results1, results2;
00347 
00348   results0 = interval_trees[0]->query(obj->getAABB().min_[0], obj->getAABB().max_[0]);
00349   if(results0.size() > CUTOFF)
00350   {
00351     results1 = interval_trees[1]->query(obj->getAABB().min_[1], obj->getAABB().max_[1]);
00352     if(results1.size() > CUTOFF)
00353     {
00354       results2 = interval_trees[2]->query(obj->getAABB().min_[2], obj->getAABB().max_[2]);
00355       if(results2.size() > CUTOFF)
00356       {
00357         int d1 = results0.size();
00358         int d2 = results1.size();
00359         int d3 = results2.size();
00360 
00361         if(d1 >= d2 && d1 >= d3)
00362           return checkColl(results0.begin(), results0.end(), obj, cdata, callback);
00363         else if(d2 >= d1 && d2 >= d3)
00364           return checkColl(results1.begin(), results1.end(), obj, cdata, callback);
00365         else
00366           return checkColl(results2.begin(), results2.end(), obj, cdata, callback);
00367       }
00368       else
00369         return checkColl(results2.begin(), results2.end(), obj, cdata, callback);
00370     }
00371     else
00372       return checkColl(results1.begin(), results1.end(), obj, cdata, callback);
00373   }
00374   else
00375     return checkColl(results0.begin(), results0.end(), obj, cdata, callback);
00376 }
00377 
00378 void IntervalTreeCollisionManager::distance(CollisionObject* obj, void* cdata, DistanceCallBack callback) const
00379 {
00380   if(size() == 0) return;
00381   FCL_REAL min_dist = std::numeric_limits<FCL_REAL>::max();
00382   distance_(obj, cdata, callback, min_dist);
00383 }
00384 
00385 bool IntervalTreeCollisionManager::distance_(CollisionObject* obj, void* cdata, DistanceCallBack callback, FCL_REAL& min_dist) const
00386 {
00387   static const unsigned int CUTOFF = 100;
00388 
00389   Vec3f delta = (obj->getAABB().max_ - obj->getAABB().min_) * 0.5;
00390   AABB aabb = obj->getAABB();
00391   if(min_dist < std::numeric_limits<FCL_REAL>::max())
00392   {
00393     Vec3f min_dist_delta(min_dist, min_dist, min_dist);
00394     aabb.expand(min_dist_delta);
00395   }
00396 
00397   int status = 1;
00398   FCL_REAL old_min_distance;
00399   
00400   while(1)
00401   {
00402     bool dist_res = false;
00403 
00404     old_min_distance = min_dist;
00405 
00406     std::deque<SimpleInterval*> results0, results1, results2;
00407 
00408     results0 = interval_trees[0]->query(aabb.min_[0], aabb.max_[0]);
00409     if(results0.size() > CUTOFF)
00410     {
00411       results1 = interval_trees[1]->query(aabb.min_[1], aabb.max_[1]);
00412       if(results1.size() > CUTOFF)
00413       {
00414         results2 = interval_trees[2]->query(aabb.min_[2], aabb.max_[2]);
00415         if(results2.size() > CUTOFF)
00416         {
00417           int d1 = results0.size();
00418           int d2 = results1.size();
00419           int d3 = results2.size();
00420 
00421           if(d1 >= d2 && d1 >= d3)
00422             dist_res = checkDist(results0.begin(), results0.end(), obj, cdata, callback, min_dist);
00423           else if(d2 >= d1 && d2 >= d3)
00424             dist_res = checkDist(results1.begin(), results1.end(), obj, cdata, callback, min_dist);
00425           else
00426             dist_res = checkDist(results2.begin(), results2.end(), obj, cdata, callback, min_dist);
00427         }
00428         else
00429           dist_res = checkDist(results2.begin(), results2.end(), obj, cdata, callback, min_dist);
00430       }
00431       else
00432         dist_res = checkDist(results1.begin(), results1.end(), obj, cdata, callback, min_dist);
00433     }
00434     else
00435       dist_res = checkDist(results0.begin(), results0.end(), obj, cdata, callback, min_dist);
00436 
00437     if(dist_res) return true;
00438 
00439     results0.clear();
00440     results1.clear();
00441     results2.clear();
00442 
00443     if(status == 1)
00444     {
00445       if(old_min_distance < std::numeric_limits<FCL_REAL>::max())
00446         break;
00447       else
00448       {
00449         if(min_dist < old_min_distance)
00450         {
00451           Vec3f min_dist_delta(min_dist, min_dist, min_dist);
00452           aabb = AABB(obj->getAABB(), min_dist_delta);
00453           status = 0;
00454         }
00455         else
00456         {
00457           if(aabb.equal(obj->getAABB()))
00458             aabb.expand(delta);
00459           else
00460             aabb.expand(obj->getAABB(), 2.0);
00461         }
00462       }
00463     }
00464     else if(status == 0)
00465       break;
00466   }
00467 
00468   return false;
00469 }
00470 
00471 void IntervalTreeCollisionManager::collide(void* cdata, CollisionCallBack callback) const
00472 {
00473   if(size() == 0) return;
00474 
00475   std::set<CollisionObject*> active;
00476   std::set<std::pair<CollisionObject*, CollisionObject*> > overlap;
00477   unsigned int n = endpoints[0].size();
00478   double diff_x = endpoints[0][0].value - endpoints[0][n-1].value;
00479   double diff_y = endpoints[1][0].value - endpoints[1][n-1].value;
00480   double diff_z = endpoints[2][0].value - endpoints[2][n-1].value;
00481 
00482   int axis = 0;
00483   if(diff_y > diff_x && diff_y > diff_z)
00484     axis = 1;
00485   else if(diff_z > diff_y && diff_z > diff_x)
00486     axis = 2;
00487 
00488   for(unsigned int i = 0; i < n; ++i)
00489   {
00490     const EndPoint& endpoint = endpoints[axis][i];
00491     CollisionObject* index = endpoint.obj;
00492     if(endpoint.minmax == 0)
00493     {
00494       std::set<CollisionObject*>::iterator iter = active.begin();
00495       std::set<CollisionObject*>::iterator end = active.end();
00496       for(; iter != end; ++iter)
00497       {
00498         CollisionObject* active_index = *iter;
00499         const AABB& b0 = active_index->getAABB();
00500         const AABB& b1 = index->getAABB();
00501 
00502         int axis2 = (axis + 1) % 3;
00503         int axis3 = (axis + 2) % 3;
00504 
00505         if(b0.axisOverlap(b1, axis2) && b0.axisOverlap(b1, axis3))
00506         {
00507           std::pair<std::set<std::pair<CollisionObject*, CollisionObject*> >::iterator, bool> insert_res;
00508           if(active_index < index)
00509             insert_res = overlap.insert(std::make_pair(active_index, index));
00510           else
00511             insert_res = overlap.insert(std::make_pair(index, active_index));
00512 
00513           if(insert_res.second)
00514           {
00515             if(callback(active_index, index, cdata))
00516               return;
00517           }
00518         }
00519       }
00520       active.insert(index);
00521     }
00522     else
00523       active.erase(index);
00524   }
00525 
00526 }
00527 
00528 void IntervalTreeCollisionManager::distance(void* cdata, DistanceCallBack callback) const
00529 {
00530   if(size() == 0) return;
00531 
00532   enable_tested_set_ = true;
00533   tested_set.clear();
00534   FCL_REAL min_dist = std::numeric_limits<FCL_REAL>::max();
00535   
00536   for(size_t i = 0; i < endpoints[0].size(); ++i)
00537     if(distance_(endpoints[0][i].obj, cdata, callback, min_dist)) break;
00538   
00539   enable_tested_set_ = false;
00540   tested_set.clear();
00541 }
00542 
00543 void IntervalTreeCollisionManager::collide(BroadPhaseCollisionManager* other_manager_, void* cdata, CollisionCallBack callback) const
00544 {
00545   IntervalTreeCollisionManager* other_manager = static_cast<IntervalTreeCollisionManager*>(other_manager_);
00546 
00547   if((size() == 0) || (other_manager->size() == 0)) return;
00548 
00549   if(this == other_manager)
00550   {
00551     collide(cdata, callback);
00552     return;
00553   }
00554 
00555   if(this->size() < other_manager->size())
00556   {
00557     for(size_t i = 0, size = endpoints[0].size(); i < size; ++i)
00558       if(other_manager->collide_(endpoints[0][i].obj, cdata, callback)) return;
00559   }
00560   else
00561   {
00562     for(size_t i = 0, size = other_manager->endpoints[0].size(); i < size; ++i)
00563       if(collide_(other_manager->endpoints[0][i].obj, cdata, callback)) return;
00564   }
00565 }
00566 
00567 void IntervalTreeCollisionManager::distance(BroadPhaseCollisionManager* other_manager_, void* cdata, DistanceCallBack callback) const
00568 {
00569   IntervalTreeCollisionManager* other_manager = static_cast<IntervalTreeCollisionManager*>(other_manager_);
00570 
00571   if((size() == 0) || (other_manager->size() == 0)) return;
00572 
00573   if(this == other_manager)
00574   {
00575     distance(cdata, callback);
00576     return;
00577   }
00578 
00579   FCL_REAL min_dist = std::numeric_limits<FCL_REAL>::max();
00580   
00581   if(this->size() < other_manager->size())
00582   {
00583     for(size_t i = 0, size = endpoints[0].size(); i < size; ++i)
00584       if(other_manager->distance_(endpoints[0][i].obj, cdata, callback, min_dist)) return;
00585   }
00586   else
00587   {
00588     for(size_t i = 0, size = other_manager->endpoints[0].size(); i < size; ++i)
00589       if(distance_(other_manager->endpoints[0][i].obj, cdata, callback, min_dist)) return;
00590   }
00591 }
00592 
00593 bool IntervalTreeCollisionManager::empty() const
00594 {
00595   return endpoints[0].empty();
00596 }
00597 
00598 bool IntervalTreeCollisionManager::checkColl(std::deque<SimpleInterval*>::const_iterator pos_start, std::deque<SimpleInterval*>::const_iterator pos_end, CollisionObject* obj, void* cdata, CollisionCallBack callback) const
00599 {
00600   while(pos_start < pos_end)
00601   {
00602     SAPInterval* ivl = static_cast<SAPInterval*>(*pos_start); 
00603     if(ivl->obj != obj)
00604     {
00605       if(ivl->obj->getAABB().overlap(obj->getAABB()))
00606       {
00607         if(callback(ivl->obj, obj, cdata))
00608           return true;
00609       }
00610     }
00611       
00612     pos_start++;
00613   }
00614 
00615   return false;
00616 }
00617 
00618 bool IntervalTreeCollisionManager::checkDist(std::deque<SimpleInterval*>::const_iterator pos_start, std::deque<SimpleInterval*>::const_iterator pos_end, CollisionObject* obj, void* cdata, DistanceCallBack callback, FCL_REAL& min_dist) const
00619 {
00620   while(pos_start < pos_end)
00621   {
00622     SAPInterval* ivl = static_cast<SAPInterval*>(*pos_start);
00623     if(ivl->obj != obj)
00624     {
00625       if(!enable_tested_set_)
00626       {
00627         if(ivl->obj->getAABB().distance(obj->getAABB()) < min_dist)
00628         {
00629           if(callback(ivl->obj, obj, cdata, min_dist))
00630             return true;
00631         }
00632       }
00633       else
00634       {
00635         if(!inTestedSet(ivl->obj, obj))
00636         {
00637           if(ivl->obj->getAABB().distance(obj->getAABB()) < min_dist)
00638           {
00639             if(callback(ivl->obj, obj, cdata, min_dist))
00640               return true;
00641           }
00642 
00643           insertTestedSet(ivl->obj, obj);
00644         }
00645       }
00646     }
00647 
00648     pos_start++;
00649   }
00650 
00651   return false;
00652 }
00653 
00654 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


fcl
Author(s): Jia Pan
autogenerated on Tue Jan 15 2013 16:05:30