collision_common.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 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 
00035 /* Author: Ioan Sucan, Jia Pan */
00036 
00037 #include <moveit/collision_detection_fcl/collision_common.h>
00038 #include <fcl/BVH/BVH_model.h>
00039 #include <fcl/shape/geometric_shapes.h>
00040 #include <fcl/octree.h>
00041 #include <boost/thread/mutex.hpp>
00042 
00043 namespace collision_detection
00044 {
00045 
00046 bool collisionCallback(fcl::CollisionObject* o1, fcl::CollisionObject* o2, void *data)
00047 {
00048   CollisionData *cdata = reinterpret_cast<CollisionData*>(data);
00049   if (cdata->done_)
00050     return true;
00051   const CollisionGeometryData *cd1 = static_cast<const CollisionGeometryData*>(o1->getCollisionGeometry()->getUserData());
00052   const CollisionGeometryData *cd2 = static_cast<const CollisionGeometryData*>(o2->getCollisionGeometry()->getUserData());
00053 
00054   // do not collision check geoms part of the same object / link / attached body
00055   if (cd1->sameObject(*cd2))
00056     return false;
00057   
00058   // If active components are specified
00059   if (cdata->active_components_only_)
00060   {
00061     const robot_model::LinkModel *l1 = cd1->type == BodyTypes::ROBOT_LINK ? cd1->ptr.link : (cd1->type == BodyTypes::ROBOT_ATTACHED ? cd1->ptr.ab->getAttachedLink() : NULL);
00062     const robot_model::LinkModel *l2 = cd2->type == BodyTypes::ROBOT_LINK ? cd2->ptr.link : (cd2->type == BodyTypes::ROBOT_ATTACHED ? cd2->ptr.ab->getAttachedLink() : NULL);
00063 
00064     // If neither of the involved components is active
00065     if ((!l1 || cdata->active_components_only_->find(l1) == cdata->active_components_only_->end()) &&
00066         (!l2 || cdata->active_components_only_->find(l2) == cdata->active_components_only_->end()))
00067       return false;
00068   }
00069 
00070   // use the collision matrix (if any) to avoid certain collision checks
00071   DecideContactFn dcf;
00072   bool always_allow_collision = false;
00073   if (cdata->acm_)
00074   {
00075     AllowedCollision::Type type;
00076     bool found = cdata->acm_->getAllowedCollision(cd1->getID(), cd2->getID(), type);
00077     if (found)
00078     {
00079       // if we have an entry in the collision matrix, we read it
00080       if (type == AllowedCollision::ALWAYS)
00081       {
00082         always_allow_collision = true;
00083         if (cdata->req_->verbose)
00084           logDebug("Collision between '%s' (type '%s') and '%s' (type '%s') is always allowed. No contacts are computed.",
00085                    cd1->getID().c_str(),
00086                    cd1->getTypeString().c_str(),
00087                    cd2->getID().c_str(),
00088                    cd2->getTypeString().c_str());
00089       }
00090       else
00091         if (type == AllowedCollision::CONDITIONAL)
00092         {
00093           cdata->acm_->getAllowedCollision(cd1->getID(), cd2->getID(), dcf);
00094           if (cdata->req_->verbose)
00095             logDebug("Collision between '%s' and '%s' is conditionally allowed", cd1->getID().c_str(), cd2->getID().c_str());
00096         }
00097     }
00098   }
00099 
00100   // check if a link is touching an attached object
00101   if (cd1->type == BodyTypes::ROBOT_LINK && cd2->type == BodyTypes::ROBOT_ATTACHED)
00102   {
00103     const std::set<std::string> &tl = cd2->ptr.ab->getTouchLinks();
00104     if (tl.find(cd1->getID()) != tl.end())
00105     {
00106       always_allow_collision = true;
00107       if (cdata->req_->verbose)
00108         logDebug("Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
00109                  cd1->getID().c_str(), cd2->getID().c_str());
00110     }
00111   }
00112   else
00113     if (cd2->type == BodyTypes::ROBOT_LINK && cd1->type == BodyTypes::ROBOT_ATTACHED)
00114     {
00115       const std::set<std::string> &tl = cd1->ptr.ab->getTouchLinks();
00116       if (tl.find(cd2->getID()) != tl.end())
00117       {
00118         always_allow_collision = true;
00119         if (cdata->req_->verbose)
00120           logDebug("Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
00121                    cd2->getID().c_str(), cd1->getID().c_str());
00122       }
00123     }
00124   // bodies attached to the same link should not collide
00125   if (cd1->type == BodyTypes::ROBOT_ATTACHED && cd2->type == BodyTypes::ROBOT_ATTACHED)
00126   {
00127     if (cd1->ptr.ab->getAttachedLink() == cd2->ptr.ab->getAttachedLink())
00128       always_allow_collision = true;
00129   }
00130 
00131   // if collisions are always allowed, we are done
00132   if (always_allow_collision)
00133     return false;
00134 
00135   if (cdata->req_->verbose)
00136     logDebug("Actually checking collisions between %s and %s", cd1->getID().c_str(), cd2->getID().c_str());
00137 
00138   // see if we need to compute a contact
00139   std::size_t want_contact_count = 0;
00140   if (cdata->req_->contacts)
00141     if (cdata->res_->contact_count < cdata->req_->max_contacts)
00142     {
00143       std::size_t have;
00144       if (cd1->getID() < cd2->getID())
00145       {
00146         std::pair<std::string, std::string> cp(cd1->getID(), cd2->getID());
00147         have = cdata->res_->contacts.find(cp) != cdata->res_->contacts.end() ? cdata->res_->contacts[cp].size() : 0;
00148       }
00149       else
00150       {
00151         std::pair<std::string, std::string> cp(cd2->getID(), cd1->getID());
00152         have = cdata->res_->contacts.find(cp) != cdata->res_->contacts.end() ? cdata->res_->contacts[cp].size() : 0;
00153       }
00154       if (have < cdata->req_->max_contacts_per_pair)
00155         want_contact_count = std::min(cdata->req_->max_contacts_per_pair - have, cdata->req_->max_contacts - cdata->res_->contact_count);
00156     }
00157 
00158   if (dcf)
00159   {
00160     // if we have a decider for allowed contacts, we need to look at all the contacts
00161     bool enable_cost = cdata->req_->cost;
00162     std::size_t num_max_cost_sources = cdata->req_->max_cost_sources;
00163     bool enable_contact = true;
00164     fcl::CollisionResult col_result;
00165     int num_contacts = fcl::collide(o1, o2, fcl::CollisionRequest(std::numeric_limits<size_t>::max(), enable_contact, num_max_cost_sources, enable_cost), col_result);
00166     if (num_contacts > 0)
00167     {
00168       if (cdata->req_->verbose)
00169         logInform("Found %d contacts between '%s' and '%s'. These contacts will be evaluated to check if they are accepted or not",
00170                   num_contacts, cd1->getID().c_str(), cd2->getID().c_str());
00171       Contact c;
00172       const std::pair<std::string, std::string> &pc = cd1->getID() < cd2->getID() ?
00173         std::make_pair(cd1->getID(), cd2->getID()) : std::make_pair(cd2->getID(), cd1->getID());
00174       for (int i = 0 ; i < num_contacts ; ++i)
00175       {
00176         fcl2contact(col_result.getContact(i), c);
00177         // if the contact is  not allowed, we have a collision
00178         if (dcf(c) == false)
00179         {
00180           // store the contact, if it is needed
00181           if (want_contact_count > 0)
00182           {
00183             --want_contact_count;
00184             cdata->res_->contacts[pc].push_back(c);
00185             cdata->res_->contact_count++;
00186             if (cdata->req_->verbose)
00187               logInform("Found unacceptable contact between '%s' and '%s'. Contact was stored.",
00188                         cd1->getID().c_str(), cd2->getID().c_str());
00189           }
00190           else
00191             if (cdata->req_->verbose)
00192               logInform("Found unacceptable contact between '%s' (type '%s') and '%s' (type '%s'). Contact was stored.",
00193                         cd1->getID().c_str(), cd1->getTypeString().c_str(),
00194                         cd2->getID().c_str(), cd2->getTypeString().c_str());
00195           cdata->res_->collision = true;
00196           if (want_contact_count == 0)
00197             break;
00198         }
00199       }
00200     }
00201 
00202     if (enable_cost)
00203     {
00204       std::vector<fcl::CostSource> cost_sources;
00205       col_result.getCostSources(cost_sources);
00206 
00207       CostSource cs;
00208       for (std::size_t i = 0; i < cost_sources.size(); ++i)
00209       {
00210         fcl2costsource(cost_sources[i], cs);
00211         cdata->res_->cost_sources.insert(cs);
00212         while (cdata->res_->cost_sources.size() > cdata->req_->max_cost_sources)
00213           cdata->res_->cost_sources.erase(--cdata->res_->cost_sources.end());
00214       }
00215     }
00216   }
00217   else
00218   {
00219     if (want_contact_count > 0)
00220     {
00221       // otherwise, we need to compute more things
00222       bool enable_cost = cdata->req_->cost;
00223       std::size_t num_max_cost_sources = cdata->req_->max_cost_sources;
00224       bool enable_contact = true;
00225 
00226       fcl::CollisionResult col_result;
00227       int num_contacts = fcl::collide(o1, o2, fcl::CollisionRequest(want_contact_count, enable_contact, num_max_cost_sources, enable_cost), col_result);
00228       if (num_contacts > 0)
00229       {
00230         int num_contacts_initial = num_contacts;
00231 
00232         // make sure we don't get more contacts than we want
00233         if (want_contact_count >= (std::size_t)num_contacts)
00234           want_contact_count -= num_contacts;
00235         else
00236         {
00237           num_contacts = want_contact_count;
00238           want_contact_count = 0;
00239         }
00240 
00241         if (cdata->req_->verbose)
00242           logInform("Found %d contacts between '%s' (type '%s') and '%s' (type '%s'), which constitute a collision. %d contacts will be stored",
00243                     num_contacts_initial,
00244                     cd1->getID().c_str(), cd1->getTypeString().c_str(),
00245                     cd2->getID().c_str(), cd2->getTypeString().c_str(),
00246                     num_contacts);
00247 
00248         const std::pair<std::string, std::string> &pc = cd1->getID() < cd2->getID() ?
00249           std::make_pair(cd1->getID(), cd2->getID()) : std::make_pair(cd2->getID(), cd1->getID());
00250         cdata->res_->collision = true;
00251         for (int i = 0 ; i < num_contacts ; ++i)
00252         {
00253           Contact c;
00254           fcl2contact(col_result.getContact(i), c);
00255           cdata->res_->contacts[pc].push_back(c);
00256           cdata->res_->contact_count++;
00257         }
00258       }
00259 
00260       if (enable_cost)
00261       {
00262         std::vector<fcl::CostSource> cost_sources;
00263         col_result.getCostSources(cost_sources);
00264 
00265         CostSource cs;
00266         for (std::size_t i = 0; i < cost_sources.size(); ++i)
00267         {
00268           fcl2costsource(cost_sources[i], cs);
00269           cdata->res_->cost_sources.insert(cs);
00270           while (cdata->res_->cost_sources.size() > cdata->req_->max_cost_sources)
00271             cdata->res_->cost_sources.erase(--cdata->res_->cost_sources.end());
00272         }
00273       }
00274     }
00275     else
00276     {
00277       bool enable_cost = cdata->req_->cost;
00278       std::size_t num_max_cost_sources = cdata->req_->max_cost_sources;
00279       bool enable_contact = false;
00280       fcl::CollisionResult col_result;
00281       int num_contacts = fcl::collide(o1, o2, fcl::CollisionRequest(1, enable_contact, num_max_cost_sources, enable_cost), col_result);
00282       if (num_contacts > 0)
00283       {
00284         cdata->res_->collision = true;
00285         if (cdata->req_->verbose)
00286           logInform("Found a contact between '%s' (type '%s') and '%s' (type '%s'), which constitutes a collision. Contact information is not stored.",
00287                     cd1->getID().c_str(), cd1->getTypeString().c_str(), cd2->getID().c_str(), cd2->getTypeString().c_str());
00288       }
00289 
00290       if (enable_cost)
00291       {
00292         std::vector<fcl::CostSource> cost_sources;
00293         col_result.getCostSources(cost_sources);
00294 
00295         CostSource cs;
00296         for (std::size_t i = 0; i < cost_sources.size(); ++i)
00297         {
00298           fcl2costsource(cost_sources[i], cs);
00299           cdata->res_->cost_sources.insert(cs);
00300           while (cdata->res_->cost_sources.size() > cdata->req_->max_cost_sources)
00301             cdata->res_->cost_sources.erase(--cdata->res_->cost_sources.end());
00302         }
00303       }
00304     }
00305   }
00306 
00307 
00308   if (cdata->res_->collision)
00309     if (!cdata->req_->contacts || cdata->res_->contact_count >= cdata->req_->max_contacts)
00310     {
00311       if (!cdata->req_->cost)
00312         cdata->done_ = true;
00313       if (cdata->req_->verbose)
00314         logInform("Collision checking is considered complete (collision was found and %u contacts are stored)",
00315                   (unsigned int)cdata->res_->contact_count);
00316     }
00317 
00318   if (!cdata->done_ && cdata->req_->is_done)
00319   {
00320     cdata->done_ = cdata->req_->is_done(*cdata->res_);
00321     if (cdata->done_ && cdata->req_->verbose)
00322       logInform("Collision checking is considered complete due to external callback. %s was found. %u contacts are stored.",
00323                 cdata->res_->collision ? "Collision" : "No collision", (unsigned int)cdata->res_->contact_count);
00324   }
00325 
00326   return cdata->done_;
00327 }
00328 
00329 struct FCLShapeCache
00330 {
00331   FCLShapeCache() : clean_count_(0) {}
00332 
00333   void bumpUseCount(bool force = false)
00334   {
00335     clean_count_++;
00336 
00337     // clean-up for cache (we don't want to keep infinitely large number of weak ptrs stored)
00338     if (clean_count_ > MAX_CLEAN_COUNT || force)
00339     {
00340       clean_count_ = 0;
00341       unsigned int from = map_.size();
00342       for (std::map<boost::weak_ptr<const shapes::Shape>, FCLGeometryConstPtr>::iterator it = map_.begin() ; it != map_.end() ; )
00343       {
00344         std::map<boost::weak_ptr<const shapes::Shape>, FCLGeometryConstPtr>::iterator nit = it; ++nit;
00345         if (it->first.expired())
00346           map_.erase(it);
00347         it = nit;
00348       }
00349       //      logDebug("Cleaning up cache for FCL objects that correspond to static shapes. Cache size reduced from %u to %u", from, (unsigned int)map_.size());
00350     }
00351   }
00352 
00353   static const unsigned int MAX_CLEAN_COUNT = 100; // every this many uses of the cache, a cleaning operation is executed (this is only removal of expired entries)
00354   std::map<boost::weak_ptr<const shapes::Shape>, FCLGeometryConstPtr> map_;
00355   unsigned int clean_count_;
00356   boost::mutex lock_;
00357 };
00358 
00359 
00360 bool distanceCallback(fcl::CollisionObject* o1, fcl::CollisionObject* o2, void* data, double& min_dist)
00361 {
00362   CollisionData* cdata = reinterpret_cast<CollisionData*>(data);
00363 
00364   const CollisionGeometryData* cd1 = static_cast<const CollisionGeometryData*>(o1->getCollisionGeometry()->getUserData());
00365   const CollisionGeometryData* cd2 = static_cast<const CollisionGeometryData*>(o2->getCollisionGeometry()->getUserData());
00366 
00367   // If active components are specified
00368   if (cdata->active_components_only_)
00369   {
00370     const robot_model::LinkModel *l1 = cd1->type == BodyTypes::ROBOT_LINK ? cd1->ptr.link : (cd1->type == BodyTypes::ROBOT_ATTACHED ? cd1->ptr.ab->getAttachedLink() : NULL);
00371     const robot_model::LinkModel *l2 = cd2->type == BodyTypes::ROBOT_LINK ? cd2->ptr.link : (cd2->type == BodyTypes::ROBOT_ATTACHED ? cd2->ptr.ab->getAttachedLink() : NULL);
00372 
00373     // If neither of the involved components is active
00374     if ((!l1 || cdata->active_components_only_->find(l1) == cdata->active_components_only_->end()) &&
00375         (!l2 || cdata->active_components_only_->find(l2) == cdata->active_components_only_->end()))
00376     {
00377       min_dist = cdata->res_->distance;
00378       return cdata->done_;
00379     }
00380   }
00381 
00382   // use the collision matrix (if any) to avoid certain distance checks
00383   bool always_allow_collision = false;
00384   if (cdata->acm_)
00385   {
00386     AllowedCollision::Type type;
00387 
00388     bool found = cdata->acm_->getAllowedCollision(cd1->getID(), cd2->getID(), type);
00389     if (found)
00390     {
00391       // if we have an entry in the collision matrix, we read it
00392       if (type == AllowedCollision::ALWAYS)
00393       {
00394         always_allow_collision = true;
00395         if (cdata->req_->verbose)
00396           logDebug("Collision between '%s' and '%s' is always allowed. No contacts are computed.",
00397                    cd1->getID().c_str(), cd2->getID().c_str());
00398       }
00399     }
00400   }
00401 
00402   // check if a link is touching an attached object
00403   if (cd1->type == BodyTypes::ROBOT_LINK && cd2->type == BodyTypes::ROBOT_ATTACHED)
00404   {
00405     const std::set<std::string> &tl = cd2->ptr.ab->getTouchLinks();
00406     if (tl.find(cd1->getID()) != tl.end())
00407     {
00408       always_allow_collision = true;
00409       if (cdata->req_->verbose)
00410         logDebug("Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
00411                  cd1->getID().c_str(), cd2->getID().c_str());
00412     }
00413   }
00414   else
00415   {
00416     if (cd2->type == BodyTypes::ROBOT_LINK && cd1->type == BodyTypes::ROBOT_ATTACHED)
00417     {
00418       const std::set<std::string> &tl = cd1->ptr.ab->getTouchLinks();
00419       if (tl.find(cd2->getID()) != tl.end())
00420       {
00421         always_allow_collision = true;
00422         if (cdata->req_->verbose)
00423           logDebug("Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
00424                    cd2->getID().c_str(), cd1->getID().c_str());
00425       }
00426     }
00427   }
00428 
00429   if(always_allow_collision)
00430   {
00431     min_dist = cdata->res_->distance;
00432     return cdata->done_;
00433   }
00434 
00435   if (cdata->req_->verbose)
00436     logDebug("Actually checking collisions between %s and %s", cd1->getID().c_str(), cd2->getID().c_str());
00437 
00438   fcl::DistanceResult dist_result;
00439   dist_result.update(cdata->res_->distance, NULL, NULL, fcl::DistanceResult::NONE, fcl::DistanceResult::NONE); // can be faster
00440   double d = fcl::distance(o1, o2, fcl::DistanceRequest(), dist_result);
00441 
00442   if(d < 0)
00443   {
00444     cdata->done_ = true;
00445     cdata->res_->distance = -1;
00446   }
00447   else
00448   {
00449     if(cdata->res_->distance > d)
00450       cdata->res_->distance = d;
00451   }
00452 
00453   min_dist = cdata->res_->distance;
00454 
00455   return cdata->done_;
00456 }
00457 
00458 /* We template the function so we get a different cache for each of the template arguments combinations */
00459 template<typename BV, typename T>
00460 FCLShapeCache& GetShapeCache()
00461 {
00462   static FCLShapeCache cache;
00463   return cache;
00464 }
00465 
00466 template<typename T1, typename T2>
00467 struct IfSameType
00468 {
00469   enum { value = 0 };
00470 };
00471 
00472 template<typename T>
00473 struct IfSameType<T, T>
00474 {
00475   enum { value = 1 };
00476 };
00477 
00478 template<typename BV, typename T>
00479 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, const T *data, int shape_index)
00480 {
00481   FCLShapeCache &cache = GetShapeCache<BV, T>();
00482 
00483   boost::weak_ptr<const shapes::Shape> wptr(shape);
00484   {
00485     boost::mutex::scoped_lock slock(cache.lock_);
00486     std::map<boost::weak_ptr<const shapes::Shape>, FCLGeometryConstPtr>::const_iterator cache_it = cache.map_.find(wptr);
00487     if (cache_it != cache.map_.end())
00488     {
00489       if (cache_it->second->collision_geometry_data_->ptr.raw == (void*)data)
00490       {
00491         //        logDebug("Collision data structures for object %s retrieved from cache.", cache_it->second->collision_geometry_data_->getID().c_str());
00492         return cache_it->second;
00493       }
00494       else
00495         if (cache_it->second.unique())
00496         {
00497           const_cast<FCLGeometry*>(cache_it->second.get())->updateCollisionGeometryData(data, shape_index, false);
00498           //          logDebug("Collision data structures for object %s retrieved from cache after updating the source object.", cache_it->second->collision_geometry_data_->getID().c_str());
00499           return cache_it->second;
00500         }
00501     }
00502   }
00503 
00504   // attached objects could have previously been World::Object; we try to move them
00505   // from their old cache to the new one, if possible. the code is not pretty, but should help
00506   // when we attach/detach objects that are in the world
00507   if (IfSameType<T, robot_state::AttachedBody>::value == 1)
00508   {
00509     // get the cache that corresponds to objects; maybe this attached object used to be a world object
00510     FCLShapeCache &othercache = GetShapeCache<BV, World::Object>();
00511 
00512     // attached bodies could be just moved from the environment.
00513     othercache.lock_.lock(); // lock manually to avoid having 2 simultaneous locks active (avoids possible deadlock)
00514     std::map<boost::weak_ptr<const shapes::Shape>, FCLGeometryConstPtr>::iterator cache_it = othercache.map_.find(wptr);
00515     if (cache_it != othercache.map_.end())
00516     {
00517       if (cache_it->second.unique())
00518       {
00519         // remove from old cache
00520         FCLGeometryConstPtr obj_cache = cache_it->second;
00521         othercache.map_.erase(cache_it);
00522         othercache.lock_.unlock();
00523 
00524         // update the CollisionGeometryData; nobody has a pointer to this, so we can safely modify it
00525         const_cast<FCLGeometry*>(obj_cache.get())->updateCollisionGeometryData(data, shape_index, true);
00526 
00527         //        logDebug("Collision data structures for attached body %s retrieved from the cache for world objects.", obj_cache->collision_geometry_data_->getID().c_str());
00528 
00529         // add to the new cache
00530         boost::mutex::scoped_lock slock(cache.lock_);
00531         cache.map_[wptr] = obj_cache;
00532         cache.bumpUseCount();
00533         return obj_cache;
00534       }
00535     }
00536     othercache.lock_.unlock();
00537   }
00538   else
00539     // world objects could have previously been attached objects; we try to move them
00540     // from their old cache to the new one, if possible. the code is not pretty, but should help
00541     // when we attach/detach objects that are in the world
00542     if (IfSameType<T, World::Object>::value == 1)
00543     {
00544       // get the cache that corresponds to objects; maybe this attached object used to be a world object
00545       FCLShapeCache &othercache = GetShapeCache<BV, robot_state::AttachedBody>();
00546 
00547       // attached bodies could be just moved from the environment.
00548       othercache.lock_.lock(); // lock manually to avoid having 2 simultaneous locks active (avoids possible deadlock)
00549       std::map<boost::weak_ptr<const shapes::Shape>, FCLGeometryConstPtr>::iterator cache_it = othercache.map_.find(wptr);
00550       if (cache_it != othercache.map_.end())
00551       {
00552         if (cache_it->second.unique())
00553         {
00554           // remove from old cache
00555           FCLGeometryConstPtr obj_cache = cache_it->second;
00556           othercache.map_.erase(cache_it);
00557           othercache.lock_.unlock();
00558 
00559           // update the CollisionGeometryData; nobody has a pointer to this, so we can safely modify it
00560           const_cast<FCLGeometry*>(obj_cache.get())->updateCollisionGeometryData(data, shape_index, true);
00561 
00562           //          logDebug("Collision data structures for world object %s retrieved from the cache for attached bodies.",
00563           //                   obj_cache->collision_geometry_data_->getID().c_str());
00564 
00565           // add to the new cache
00566           boost::mutex::scoped_lock slock(cache.lock_);
00567           cache.map_[wptr] = obj_cache;
00568           cache.bumpUseCount();
00569           return obj_cache;
00570         }
00571       }
00572       othercache.lock_.unlock();
00573     }
00574 
00575   fcl::CollisionGeometry* cg_g = NULL;
00576   if (shape->type == shapes::PLANE) // shapes that directly produce CollisionGeometry
00577   {
00578     // handle cases individually
00579     switch (shape->type)
00580     {
00581     case shapes::PLANE:
00582       {
00583         const shapes::Plane* p = static_cast<const shapes::Plane*>(shape.get());
00584         cg_g = new fcl::Plane(p->a, p->b, p->c, p->d);
00585       }
00586       break;
00587     default:
00588       break;
00589     }
00590   }
00591   else
00592   {
00593     switch (shape->type)
00594     {
00595     case shapes::SPHERE:
00596       {
00597         const shapes::Sphere* s = static_cast<const shapes::Sphere*>(shape.get());
00598         cg_g = new fcl::Sphere(s->radius);
00599       }
00600       break;
00601     case shapes::BOX:
00602       {
00603         const shapes::Box* s = static_cast<const shapes::Box*>(shape.get());
00604         const double* size = s->size;
00605         cg_g = new fcl::Box(size[0], size[1], size[2]);
00606       }
00607       break;
00608     case shapes::CYLINDER:
00609       {
00610         const shapes::Cylinder* s = static_cast<const shapes::Cylinder*>(shape.get());
00611         cg_g = new fcl::Cylinder(s->radius, s->length);
00612       }
00613       break;
00614     case shapes::CONE:
00615       {
00616         const shapes::Cone* s = static_cast<const shapes::Cone*>(shape.get());
00617         cg_g = new fcl::Cone(s->radius, s->length);
00618       }
00619       break;
00620     case shapes::MESH:
00621       {
00622         fcl::BVHModel<BV>* g = new fcl::BVHModel<BV>();
00623         const shapes::Mesh *mesh = static_cast<const shapes::Mesh*>(shape.get());
00624         if (mesh->vertex_count > 0 && mesh->triangle_count > 0)
00625         {
00626           std::vector<fcl::Triangle> tri_indices(mesh->triangle_count);
00627           for(unsigned int i = 0; i < mesh->triangle_count; ++i)
00628             tri_indices[i] = fcl::Triangle(mesh->triangles[3 * i], mesh->triangles[3 * i + 1], mesh->triangles[3 * i + 2]);
00629 
00630           std::vector<fcl::Vec3f> points(mesh->vertex_count);
00631           for (unsigned int i = 0; i < mesh->vertex_count; ++i)
00632             points[i] = fcl::Vec3f(mesh->vertices[3 * i], mesh->vertices[3 * i + 1], mesh->vertices[3 * i + 2]);
00633 
00634           g->beginModel();
00635           g->addSubModel(points, tri_indices);
00636           g->endModel();
00637         }
00638         cg_g = g;
00639       }
00640       break;
00641     case shapes::OCTREE:
00642       {
00643         const shapes::OcTree* g = static_cast<const shapes::OcTree*>(shape.get());
00644         cg_g = new fcl::OcTree(g->octree);
00645       }
00646       break;
00647     default:
00648       logError("This shape type (%d) is not supported using FCL yet", (int)shape->type);
00649       cg_g = NULL;
00650     }
00651   }
00652   if (cg_g)
00653   {
00654     cg_g->computeLocalAABB();
00655     FCLGeometryConstPtr res(new FCLGeometry(cg_g, data, shape_index));
00656     boost::mutex::scoped_lock slock(cache.lock_);
00657     cache.map_[wptr] = res;
00658     cache.bumpUseCount();
00659     return res;
00660   }
00661   return FCLGeometryConstPtr();
00662 }
00663 
00664 
00666 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape,
00667                                             const robot_model::LinkModel *link, 
00668                                             int shape_index)
00669 {
00670   return createCollisionGeometry<fcl::OBBRSS, robot_model::LinkModel>(shape, link, shape_index);
00671 }
00672 
00673 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape,
00674                                             const robot_state::AttachedBody *ab,
00675                                             int shape_index)
00676 {
00677   return createCollisionGeometry<fcl::OBBRSS, robot_state::AttachedBody>(shape, ab, shape_index);
00678 }
00679 
00680 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape,
00681                                             const World::Object *obj)
00682 {
00683   return createCollisionGeometry<fcl::OBBRSS, World::Object>(shape, obj, 0);
00684 }
00685 
00686 template<typename BV, typename T>
00687 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, double scale, double padding, const T *data, int shape_index)
00688 {
00689   if (fabs(scale - 1.0) <= std::numeric_limits<double>::epsilon() && fabs(padding) <= std::numeric_limits<double>::epsilon())
00690     return createCollisionGeometry<BV, T>(shape, data, shape_index);
00691   else
00692   {
00693     boost::shared_ptr<shapes::Shape> scaled_shape(shape->clone());
00694     scaled_shape->scaleAndPadd(scale, padding);
00695     return createCollisionGeometry<BV, T>(scaled_shape, data, shape_index);
00696   }
00697 }
00698 
00699 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, double scale, double padding,
00700                                             const robot_model::LinkModel *link, int shape_index)
00701 {
00702   return createCollisionGeometry<fcl::OBBRSS, robot_model::LinkModel>(shape, scale, padding, link, shape_index);
00703 }
00704 
00705 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, double scale, double padding,
00706                                             const robot_state::AttachedBody *ab, int shape_index)
00707 {
00708   return createCollisionGeometry<fcl::OBBRSS, robot_state::AttachedBody>(shape, scale, padding, ab, shape_index);
00709 }
00710 
00711 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, double scale, double padding,
00712                                             const World::Object *obj)
00713 {
00714   return createCollisionGeometry<fcl::OBBRSS, World::Object>(shape, scale, padding, obj, 0);
00715 }
00716 
00717 void cleanCollisionGeometryCache()
00718 {
00719   FCLShapeCache &cache1 = GetShapeCache<fcl::OBBRSS, World::Object>();
00720   {
00721     boost::mutex::scoped_lock slock(cache1.lock_);
00722     cache1.bumpUseCount(true);
00723   }
00724   FCLShapeCache &cache2 = GetShapeCache<fcl::OBBRSS, robot_state::AttachedBody>();
00725   {
00726     boost::mutex::scoped_lock slock(cache2.lock_);
00727     cache2.bumpUseCount(true);
00728   }
00729 }
00730 
00731 }
00732 
00733 void collision_detection::CollisionData::enableGroup(const robot_model::RobotModelConstPtr &kmodel)
00734 {
00735   if (kmodel->hasJointModelGroup(req_->group_name))
00736     active_components_only_ = &kmodel->getJointModelGroup(req_->group_name)->getUpdatedLinkModelsWithGeometrySet();
00737   else
00738     active_components_only_ = NULL;
00739 }
00740 
00741 void collision_detection::FCLObject::registerTo(fcl::BroadPhaseCollisionManager *manager)
00742 {
00743   std::vector<fcl::CollisionObject*> collision_objects(collision_objects_.size());
00744   for(std::size_t i = 0; i < collision_objects_.size(); ++i)
00745     collision_objects[i] = collision_objects_[i].get();
00746   if (!collision_objects.empty())
00747     manager->registerObjects(collision_objects);
00748 }
00749 
00750 void collision_detection::FCLObject::unregisterFrom(fcl::BroadPhaseCollisionManager *manager)
00751 {
00752   for (std::size_t i = 0 ; i < collision_objects_.size() ; ++i)
00753     manager->unregisterObject(collision_objects_[i].get());
00754 }
00755 
00756 void collision_detection::FCLObject::clear()
00757 {
00758   collision_objects_.clear();
00759   collision_geometry_.clear();
00760 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:52