00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #include <moveit/robot_model/robot_model.h>
00038 #include <moveit/collision_distance_field/collision_robot_distance_field.h>
00039 #include <moveit/collision_distance_field/collision_common_distance_field.h>
00040 #include <moveit/distance_field/propagation_distance_field.h>
00041 #include <ros/console.h>
00042 #include <ros/assert.h>
00043 #include <eigen_conversions/eigen_msg.h>
00044 
00045 namespace collision_detection
00046 {
00047 const double EPSILON = 0.001f;
00048 
00049 CollisionRobotDistanceField::CollisionRobotDistanceField(const robot_model::RobotModelConstPtr& kmodel)
00050   : CollisionRobot(kmodel)
00051 {
00052   
00053 
00054   std::map<std::string, std::vector<CollisionSphere>> link_body_decompositions;
00055   Eigen::Vector3d size(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z);
00056   initialize(link_body_decompositions, size, Eigen::Vector3d(0, 0, 0), DEFAULT_USE_SIGNED_DISTANCE_FIELD,
00057              DEFAULT_RESOLUTION, DEFAULT_COLLISION_TOLERANCE, DEFAULT_MAX_PROPOGATION_DISTANCE);
00058   setPadding(0.0);
00059 }
00060 
00061 CollisionRobotDistanceField::CollisionRobotDistanceField(
00062     const robot_model::RobotModelConstPtr& kmodel,
00063     const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, double size_x, double size_y,
00064     double size_z, bool use_signed_distance_field, double resolution, double collision_tolerance,
00065     double max_propogation_distance, double padding, double scale)
00066   : CollisionRobot(kmodel, padding, scale)
00067 {
00068   initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), Eigen::Vector3d(0, 0, 0),
00069              use_signed_distance_field, resolution, collision_tolerance, max_propogation_distance);
00070 }
00071 
00072 CollisionRobotDistanceField::CollisionRobotDistanceField(const CollisionRobot& col_robot, const Eigen::Vector3d& size,
00073                                                          const Eigen::Vector3d& origin, bool use_signed_distance_field,
00074                                                          double resolution, double collision_tolerance,
00075                                                          double max_propogation_distance, double padding)
00076   : CollisionRobot(col_robot)
00077 {
00078   std::map<std::string, std::vector<CollisionSphere>> link_body_decompositions;
00079   initialize(link_body_decompositions, size, origin, use_signed_distance_field, resolution, collision_tolerance,
00080              max_propogation_distance);
00081   setPadding(padding);
00082 }
00083 
00084 CollisionRobotDistanceField::CollisionRobotDistanceField(const CollisionRobotDistanceField& other)
00085   : CollisionRobot(other)
00086 {
00087   size_ = other.size_;
00088   origin_ = other.origin_;
00089 
00090   use_signed_distance_field_ = other.use_signed_distance_field_;
00091   resolution_ = other.resolution_;
00092   collision_tolerance_ = other.collision_tolerance_;
00093   max_propogation_distance_ = other.max_propogation_distance_;
00094   link_body_decomposition_vector_ = other.link_body_decomposition_vector_;
00095   link_body_decomposition_index_map_ = other.link_body_decomposition_index_map_;
00096   in_group_update_map_ = other.in_group_update_map_;
00097   pregenerated_group_state_representation_map_ = other.pregenerated_group_state_representation_map_;
00098   planning_scene_.reset(new planning_scene::PlanningScene(robot_model_));
00099 }
00100 
00101 void CollisionRobotDistanceField::initialize(
00102     const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, const Eigen::Vector3d& size,
00103     const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution, double collision_tolerance,
00104     double max_propogation_distance)
00105 {
00106   size_ = size;
00107   origin_ = origin;
00108   use_signed_distance_field_ = use_signed_distance_field;
00109   resolution_ = resolution;
00110   collision_tolerance_ = collision_tolerance;
00111   max_propogation_distance_ = max_propogation_distance;
00112   addLinkBodyDecompositions(resolution_, link_body_decompositions);
00113   moveit::core::RobotState state(robot_model_);
00114   planning_scene_.reset(new planning_scene::PlanningScene(robot_model_));
00115 
00116   const std::vector<const moveit::core::JointModelGroup*>& jmg = robot_model_->getJointModelGroups();
00117   for (std::vector<const moveit::core::JointModelGroup*>::const_iterator it = jmg.begin(); it != jmg.end(); it++)
00118   {
00119     const moveit::core::JointModelGroup* jm = *it;
00120 
00121     std::map<std::string, bool> updated_group_entry;
00122     std::vector<std::string> links = jm->getUpdatedLinkModelsWithGeometryNames();
00123     for (unsigned int i = 0; i < links.size(); i++)
00124     {
00125       updated_group_entry[links[i]] = true;
00126     }
00127     in_group_update_map_[jm->getName()] = updated_group_entry;
00128     state.updateLinkTransforms();
00129     boost::shared_ptr<DistanceFieldCacheEntry> dfce =
00130         generateDistanceFieldCacheEntry(jm->getName(), state, &planning_scene_->getAllowedCollisionMatrix(), false);
00131     getGroupStateRepresentation(dfce, state, pregenerated_group_state_representation_map_[jm->getName()]);
00132   }
00133 }
00134 
00135 void CollisionRobotDistanceField::generateCollisionCheckingStructures(
00136     const std::string& group_name, const moveit::core::RobotState& state,
00137     const collision_detection::AllowedCollisionMatrix* acm, boost::shared_ptr<GroupStateRepresentation>& gsr,
00138     bool generate_distance_field) const
00139 {
00140   boost::shared_ptr<const DistanceFieldCacheEntry> dfce = getDistanceFieldCacheEntry(group_name, state, acm);
00141   if (!dfce || (generate_distance_field && !dfce->distance_field_))
00142   {
00143     
00144     
00145     boost::shared_ptr<DistanceFieldCacheEntry> new_dfce =
00146         generateDistanceFieldCacheEntry(group_name, state, acm, generate_distance_field);
00147     boost::mutex::scoped_lock slock(update_cache_lock_);
00148     (const_cast<CollisionRobotDistanceField*>(this))->distance_field_cache_entry_ = new_dfce;
00149     dfce = new_dfce;
00150   }
00151   getGroupStateRepresentation(dfce, state, gsr);
00152 }
00153 
00154 void CollisionRobotDistanceField::checkSelfCollisionHelper(const collision_detection::CollisionRequest& req,
00155                                                            collision_detection::CollisionResult& res,
00156                                                            const moveit::core::RobotState& state,
00157                                                            const collision_detection::AllowedCollisionMatrix* acm,
00158                                                            boost::shared_ptr<GroupStateRepresentation>& gsr) const
00159 {
00160   if (!gsr)
00161   {
00162     generateCollisionCheckingStructures(req.group_name, state, acm, gsr, true);
00163   }
00164   else
00165   {
00166     updateGroupStateRepresentationState(state, gsr);
00167   }
00168   
00169   bool done = getSelfCollisions(req, res, gsr);
00170 
00171   if (!done)
00172   {
00173     getIntraGroupCollisions(req, res, gsr);
00174     ROS_DEBUG_COND(res.collision, "Intra Group Collision found");
00175   }
00176 }
00177 
00178 boost::shared_ptr<const DistanceFieldCacheEntry> CollisionRobotDistanceField::getDistanceFieldCacheEntry(
00179     const std::string& group_name, const moveit::core::RobotState& state,
00180     const collision_detection::AllowedCollisionMatrix* acm) const
00181 {
00182   boost::shared_ptr<const DistanceFieldCacheEntry> ret;
00183   if (!distance_field_cache_entry_)
00184   {
00185     ROS_DEBUG_STREAM("No current Distance field cache entry");
00186     return ret;
00187   }
00188   boost::shared_ptr<const DistanceFieldCacheEntry> cur = distance_field_cache_entry_;
00189   if (group_name != cur->group_name_)
00190   {
00191     ROS_DEBUG("No cache entry as group name changed from %s to %s", cur->group_name_.c_str(), group_name.c_str());
00192     return ret;
00193   }
00194   else if (!compareCacheEntryToState(cur, state))
00195   {
00196     
00197     
00198     
00199     return ret;
00200   }
00201   else if (acm && !compareCacheEntryToAllowedCollisionMatrix(cur, *acm))
00202   {
00203     ROS_DEBUG("Regenerating distance field as some relevant part of the acm changed");
00204     return ret;
00205   }
00206   return cur;
00207 }
00208 
00209 void CollisionRobotDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req,
00210                                                      collision_detection::CollisionResult& res,
00211                                                      const moveit::core::RobotState& state) const
00212 {
00213   boost::shared_ptr<GroupStateRepresentation> gsr;
00214   checkSelfCollisionHelper(req, res, state, NULL, gsr);
00215 }
00216 
00217 void CollisionRobotDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req,
00218                                                      collision_detection::CollisionResult& res,
00219                                                      const moveit::core::RobotState& state,
00220                                                      boost::shared_ptr<GroupStateRepresentation>& gsr) const
00221 {
00222   checkSelfCollisionHelper(req, res, state, NULL, gsr);
00223 }
00224 
00225 void CollisionRobotDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req,
00226                                                      collision_detection::CollisionResult& res,
00227                                                      const moveit::core::RobotState& state,
00228                                                      const collision_detection::AllowedCollisionMatrix& acm) const
00229 {
00230   boost::shared_ptr<GroupStateRepresentation> gsr;
00231   checkSelfCollisionHelper(req, res, state, &acm, gsr);
00232 }
00233 
00234 void CollisionRobotDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req,
00235                                                      collision_detection::CollisionResult& res,
00236                                                      const moveit::core::RobotState& state,
00237                                                      const collision_detection::AllowedCollisionMatrix& acm,
00238                                                      boost::shared_ptr<GroupStateRepresentation>& gsr) const
00239 {
00240   if (gsr)
00241   {
00242     ROS_WARN("Shouldn't be calling this function with initialized gsr - ACM "
00243              "will be ignored");
00244   }
00245   checkSelfCollisionHelper(req, res, state, &acm, gsr);
00246 }
00247 
00248 bool CollisionRobotDistanceField::getSelfCollisions(const collision_detection::CollisionRequest& req,
00249                                                     collision_detection::CollisionResult& res,
00250                                                     boost::shared_ptr<GroupStateRepresentation>& gsr) const
00251 {
00252   for (unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); i++)
00253   {
00254     bool is_link = i < gsr->dfce_->link_names_.size();
00255     if ((is_link && !gsr->dfce_->link_has_geometry_[i]) || !gsr->dfce_->self_collision_enabled_[i])
00256       continue;
00257     const std::vector<CollisionSphere>* collision_spheres_1;
00258     const EigenSTL::vector_Vector3d* sphere_centers_1;
00259 
00260     if (is_link)
00261     {
00262       collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
00263       sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
00264     }
00265     else
00266     {
00267       collision_spheres_1 =
00268           &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
00269       sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
00270     }
00271 
00272     if (req.contacts)
00273     {
00274       std::vector<unsigned int> colls;
00275       bool coll = getCollisionSphereCollision(
00276           gsr->dfce_->distance_field_.get(), *collision_spheres_1, *sphere_centers_1, max_propogation_distance_,
00277           collision_tolerance_, std::min(req.max_contacts_per_pair, req.max_contacts - res.contact_count), colls);
00278       if (coll)
00279       {
00280         res.collision = true;
00281         for (unsigned int j = 0; j < colls.size(); j++)
00282         {
00283           collision_detection::Contact con;
00284           if (is_link)
00285           {
00286             con.pos = gsr->link_body_decompositions_[i]->getSphereCenters()[colls[j]];
00287             con.body_type_1 = collision_detection::BodyTypes::ROBOT_LINK;
00288             con.body_name_1 = gsr->dfce_->link_names_[i];
00289           }
00290           else
00291           {
00292             con.pos =
00293                 gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()[colls[j]];
00294             con.body_type_1 = collision_detection::BodyTypes::ROBOT_ATTACHED;
00295             con.body_name_1 = gsr->dfce_->attached_body_names_[i - gsr->dfce_->link_names_.size()];
00296           }
00297 
00298           ROS_DEBUG_STREAM("Self collision detected for link " << con.body_name_1);
00299 
00300           con.body_type_2 = collision_detection::BodyTypes::ROBOT_LINK;
00301           con.body_name_2 = "self";
00302           res.contact_count++;
00303           res.contacts[std::pair<std::string, std::string>(con.body_name_1, con.body_name_2)].push_back(con);
00304           gsr->gradients_[i].types[colls[j]] = SELF;
00305         }
00306         gsr->gradients_[i].collision = true;
00307 
00308         if (res.contact_count >= req.max_contacts)
00309         {
00310           return true;
00311         }
00312       }
00313     }
00314     else
00315     {
00316       bool coll = getCollisionSphereCollision(gsr->dfce_->distance_field_.get(), *collision_spheres_1,
00317                                               *sphere_centers_1, max_propogation_distance_, collision_tolerance_);
00318       if (coll)
00319       {
00320         ROS_DEBUG("Link %s in self collision", gsr->dfce_->link_names_[i].c_str());
00321         res.collision = true;
00322         return true;
00323       }
00324     }
00325   }
00326   return (res.contact_count >= req.max_contacts);
00327 }
00328 
00329 bool CollisionRobotDistanceField::getSelfProximityGradients(boost::shared_ptr<GroupStateRepresentation>& gsr) const
00330 {
00331   bool in_collision = false;
00332 
00333   
00334   ros::Time start_time = ros::Time::now();
00335 
00336   for (unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++)
00337   {
00338     const std::string& link_name = gsr->dfce_->link_names_[i];
00339     bool is_link = i < gsr->dfce_->link_names_.size();
00340     if ((is_link && !gsr->dfce_->link_has_geometry_[i]) || !gsr->dfce_->self_collision_enabled_[i])
00341     {
00342       continue;
00343     }
00344 
00345     const std::vector<CollisionSphere>* collision_spheres_1;
00346     const EigenSTL::vector_Vector3d* sphere_centers_1;
00347     if (is_link)
00348     {
00349       collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
00350       sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
00351     }
00352     else
00353     {
00354       collision_spheres_1 =
00355           &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
00356       sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
00357     }
00358 
00359     
00360     
00361     bool coll = false;
00362     if (gsr->dfce_->acm_.getSize() > 0)
00363     {
00364       AllowedCollision::Type col_type;
00365       for (unsigned int j = 0; j < gsr->dfce_->link_names_.size(); j++)
00366       {
00367         
00368         if (link_name == gsr->dfce_->link_names_[j])
00369         {
00370           continue;
00371         }
00372 
00373         
00374         if (gsr->dfce_->acm_.getEntry(link_name, gsr->dfce_->link_names_[j], col_type) &&
00375             col_type != AllowedCollision::NEVER)
00376         {
00377           continue;
00378         }
00379 
00380         if (gsr->link_distance_fields_[j])
00381         {
00382           coll = gsr->link_distance_fields_[j]->getCollisionSphereGradients(
00383               *collision_spheres_1, *sphere_centers_1, gsr->gradients_[i], collision_detection::SELF,
00384               collision_tolerance_, false, max_propogation_distance_, false);
00385 
00386           if (coll)
00387           {
00388             in_collision = true;
00389           }
00390         }
00391       }
00392     }
00393 
00394     coll = getCollisionSphereGradients(gsr->dfce_->distance_field_.get(), *collision_spheres_1, *sphere_centers_1,
00395                                        gsr->gradients_[i], collision_detection::SELF, collision_tolerance_, false,
00396                                        max_propogation_distance_, false);
00397 
00398     if (coll)
00399     {
00400       in_collision = true;
00401     }
00402   }
00403 
00404   return in_collision;
00405 }
00406 
00407 bool CollisionRobotDistanceField::getIntraGroupCollisions(const collision_detection::CollisionRequest& req,
00408                                                           collision_detection::CollisionResult& res,
00409                                                           boost::shared_ptr<GroupStateRepresentation>& gsr) const
00410 {
00411   unsigned int num_links = gsr->dfce_->link_names_.size();
00412   unsigned int num_attached_bodies = gsr->dfce_->attached_body_names_.size();
00413 
00414   for (unsigned int i = 0; i < num_links + num_attached_bodies; i++)
00415   {
00416     for (unsigned int j = i + 1; j < num_links + num_attached_bodies; j++)
00417     {
00418       if (i == j)
00419         continue;
00420       bool i_is_link = i < num_links;
00421       bool j_is_link = j < num_links;
00422 
00423       if ((i_is_link && !gsr->dfce_->link_has_geometry_[i]) || (j_is_link && !gsr->dfce_->link_has_geometry_[j]))
00424         continue;
00425 
00426       if (!gsr->dfce_->intra_group_collision_enabled_[i][j])
00427         continue;
00428 
00429       if (i_is_link && j_is_link &&
00430           !doBoundingSpheresIntersect(gsr->link_body_decompositions_[i], gsr->link_body_decompositions_[j]))
00431       {
00432         
00433         
00434         
00435         continue;
00436       }
00437       else if (!i_is_link || !j_is_link)
00438       {
00439         bool all_ok = true;
00440         if (!i_is_link && j_is_link)
00441         {
00442           for (unsigned int k = 0; k < gsr->attached_body_decompositions_[i - num_links]->getSize(); k++)
00443           {
00444             if (doBoundingSpheresIntersect(
00445                     gsr->link_body_decompositions_[j],
00446                     gsr->attached_body_decompositions_[i - num_links]->getPosedBodySphereDecomposition(k)))
00447             {
00448               all_ok = false;
00449               break;
00450             }
00451           }
00452         }
00453         else if (i_is_link && !j_is_link)
00454         {
00455           for (unsigned int k = 0; k < gsr->attached_body_decompositions_[j - num_links]->getSize(); k++)
00456           {
00457             if (doBoundingSpheresIntersect(
00458                     gsr->link_body_decompositions_[i],
00459                     gsr->attached_body_decompositions_[j - num_links]->getPosedBodySphereDecomposition(k)))
00460             {
00461               all_ok = false;
00462               break;
00463             }
00464           }
00465         }
00466         else
00467         {
00468           for (unsigned int k = 0; k < gsr->attached_body_decompositions_[i - num_links]->getSize() && all_ok; k++)
00469           {
00470             for (unsigned int l = 0; l < gsr->attached_body_decompositions_[j - num_links]->getSize(); l++)
00471             {
00472               if (doBoundingSpheresIntersect(
00473                       gsr->attached_body_decompositions_[i - num_links]->getPosedBodySphereDecomposition(k),
00474                       gsr->attached_body_decompositions_[j - num_links]->getPosedBodySphereDecomposition(l)))
00475               {
00476                 all_ok = false;
00477                 break;
00478               }
00479             }
00480           }
00481         }
00482         if (all_ok)
00483         {
00484           continue;
00485         }
00486         
00487         
00488         
00489       }
00490       int num_pair = -1;
00491       std::string name_1;
00492       std::string name_2;
00493       if (i_is_link)
00494       {
00495         name_1 = gsr->dfce_->link_names_[i];
00496       }
00497       else
00498       {
00499         name_1 = gsr->dfce_->attached_body_names_[i - num_links];
00500       }
00501 
00502       if (j_is_link)
00503       {
00504         name_2 = gsr->dfce_->link_names_[j];
00505       }
00506       else
00507       {
00508         name_2 = gsr->dfce_->attached_body_names_[j - num_links];
00509       }
00510       if (req.contacts)
00511       {
00512         collision_detection::CollisionResult::ContactMap::iterator it =
00513             res.contacts.find(std::pair<std::string, std::string>(name_1, name_2));
00514         if (it == res.contacts.end())
00515         {
00516           num_pair = 0;
00517         }
00518         else
00519         {
00520           num_pair = it->second.size();
00521         }
00522       }
00523       const std::vector<CollisionSphere>* collision_spheres_1;
00524       const std::vector<CollisionSphere>* collision_spheres_2;
00525       const EigenSTL::vector_Vector3d* sphere_centers_1;
00526       const EigenSTL::vector_Vector3d* sphere_centers_2;
00527       if (i_is_link)
00528       {
00529         collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
00530         sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
00531       }
00532       else
00533       {
00534         collision_spheres_1 = &(gsr->attached_body_decompositions_[i - num_links]->getCollisionSpheres());
00535         sphere_centers_1 = &(gsr->attached_body_decompositions_[i - num_links]->getSphereCenters());
00536       }
00537       if (j_is_link)
00538       {
00539         collision_spheres_2 = &(gsr->link_body_decompositions_[j]->getCollisionSpheres());
00540         sphere_centers_2 = &(gsr->link_body_decompositions_[j]->getSphereCenters());
00541       }
00542       else
00543       {
00544         collision_spheres_2 = &(gsr->attached_body_decompositions_[j - num_links]->getCollisionSpheres());
00545         sphere_centers_2 = &(gsr->attached_body_decompositions_[j - num_links]->getSphereCenters());
00546       }
00547 
00548       for (unsigned int k = 0; k < collision_spheres_1->size() && num_pair < (int)req.max_contacts_per_pair; k++)
00549       {
00550         for (unsigned int l = 0; l < collision_spheres_2->size() && num_pair < (int)req.max_contacts_per_pair; l++)
00551         {
00552           Eigen::Vector3d gradient = (*sphere_centers_1)[k] - (*sphere_centers_2)[l];
00553           double dist = gradient.norm();
00554           
00555           
00556           
00557 
00558           if (dist < (*collision_spheres_1)[k].radius_ + (*collision_spheres_2)[l].radius_)
00559           {
00560             
00561             
00562             
00563             
00564             
00565             
00566             
00567             
00568             
00569             
00570             
00571             res.collision = true;
00572 
00573             if (req.contacts)
00574             {
00575               collision_detection::Contact con;
00576               con.pos = gsr->link_body_decompositions_[i]->getSphereCenters()[k];
00577               con.body_name_1 = name_1;
00578               con.body_name_2 = name_2;
00579               if (i_is_link)
00580               {
00581                 con.body_type_1 = collision_detection::BodyTypes::ROBOT_LINK;
00582               }
00583               else
00584               {
00585                 con.body_type_1 = collision_detection::BodyTypes::ROBOT_ATTACHED;
00586               }
00587               if (j_is_link)
00588               {
00589                 con.body_type_2 = collision_detection::BodyTypes::ROBOT_LINK;
00590               }
00591               else
00592               {
00593                 con.body_type_2 = collision_detection::BodyTypes::ROBOT_ATTACHED;
00594               }
00595               res.contact_count++;
00596               res.contacts[std::pair<std::string, std::string>(con.body_name_1, con.body_name_2)].push_back(con);
00597               num_pair++;
00598               
00599               
00600               gsr->gradients_[i].types[k] = INTRA;
00601               gsr->gradients_[i].collision = true;
00602               gsr->gradients_[j].types[l] = INTRA;
00603               gsr->gradients_[j].collision = true;
00604               
00605               
00606               
00607               
00608               
00609               
00610               
00611               
00612               
00613               
00614               
00615               
00616               
00617               
00618               
00619               if (res.contact_count >= req.max_contacts)
00620               {
00621                 return true;
00622               }
00623             }
00624             else
00625             {
00626               return true;
00627             }
00628           }
00629         }
00630       }
00631     }
00632   }
00633   return false;
00634 }
00635 
00636 bool CollisionRobotDistanceField::getIntraGroupProximityGradients(
00637     boost::shared_ptr<GroupStateRepresentation>& gsr) const
00638 {
00639   bool in_collision = false;
00640   unsigned int num_links = gsr->dfce_->link_names_.size();
00641   unsigned int num_attached_bodies = gsr->dfce_->attached_body_names_.size();
00642   
00643   for (unsigned int i = 0; i < num_links + num_attached_bodies; i++)
00644   {
00645     for (unsigned int j = i + 1; j < num_links + num_attached_bodies; j++)
00646     {
00647       if (i == j)
00648         continue;
00649       bool i_is_link = i < num_links;
00650       bool j_is_link = j < num_links;
00651       if ((i_is_link && !gsr->dfce_->link_has_geometry_[i]) || (j_is_link && !gsr->dfce_->link_has_geometry_[j]))
00652         continue;
00653       if (!gsr->dfce_->intra_group_collision_enabled_[i][j])
00654         continue;
00655       const std::vector<CollisionSphere>* collision_spheres_1;
00656       const std::vector<CollisionSphere>* collision_spheres_2;
00657       const EigenSTL::vector_Vector3d* sphere_centers_1;
00658       const EigenSTL::vector_Vector3d* sphere_centers_2;
00659       if (i_is_link)
00660       {
00661         collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
00662         sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
00663       }
00664       else
00665       {
00666         collision_spheres_1 = &(gsr->attached_body_decompositions_[i - num_links]->getCollisionSpheres());
00667         sphere_centers_1 = &(gsr->attached_body_decompositions_[i - num_links]->getSphereCenters());
00668       }
00669       if (j_is_link)
00670       {
00671         collision_spheres_2 = &(gsr->link_body_decompositions_[j]->getCollisionSpheres());
00672         sphere_centers_2 = &(gsr->link_body_decompositions_[j]->getSphereCenters());
00673       }
00674       else
00675       {
00676         collision_spheres_2 = &(gsr->attached_body_decompositions_[j - num_links]->getCollisionSpheres());
00677         sphere_centers_2 = &(gsr->attached_body_decompositions_[j - num_links]->getSphereCenters());
00678       }
00679       for (unsigned int k = 0; k < collision_spheres_1->size(); k++)
00680       {
00681         for (unsigned int l = 0; l < collision_spheres_2->size(); l++)
00682         {
00683           Eigen::Vector3d gradient = (*sphere_centers_1)[k] - (*sphere_centers_2)[l];
00684           double dist = gradient.norm();
00685           if (dist < gsr->gradients_[i].distances[k])
00686           {
00687             gsr->gradients_[i].distances[k] = dist;
00688             gsr->gradients_[i].gradients[k] = gradient;
00689             gsr->gradients_[i].types[k] = INTRA;
00690           }
00691           if (dist < gsr->gradients_[j].distances[l])
00692           {
00693             gsr->gradients_[j].distances[l] = dist;
00694             gsr->gradients_[j].gradients[l] = -gradient;
00695             gsr->gradients_[j].types[l] = INTRA;
00696           }
00697         }
00698       }
00699     }
00700   }
00701   return in_collision;
00702 }
00703 boost::shared_ptr<DistanceFieldCacheEntry> CollisionRobotDistanceField::generateDistanceFieldCacheEntry(
00704     const std::string& group_name, const moveit::core::RobotState& state,
00705     const collision_detection::AllowedCollisionMatrix* acm, bool generate_distance_field) const
00706 {
00707   ros::WallTime n = ros::WallTime::now();
00708   boost::shared_ptr<DistanceFieldCacheEntry> dfce(new DistanceFieldCacheEntry());
00709 
00710   if (robot_model_->getJointModelGroup(group_name) == NULL)
00711   {
00712     ROS_WARN("No group %s", group_name.c_str());
00713     return dfce;
00714   }
00715 
00716   dfce->group_name_ = group_name;
00717   dfce->state_.reset(new moveit::core::RobotState(state));
00718   if (acm)
00719   {
00720     dfce->acm_ = *acm;
00721   }
00722   else
00723   {
00724     ROS_WARN_STREAM("Allowed Collision Matrix is null, enabling all collisions "
00725                     "in the DistanceFieldCacheEntry");
00726   }
00727 
00728   
00729   dfce->link_names_ = robot_model_->getJointModelGroup(group_name)->getUpdatedLinkModelNames();
00730   std::vector<const moveit::core::AttachedBody*> all_attached_bodies;
00731   dfce->state_->getAttachedBodies(all_attached_bodies);
00732   unsigned int att_count = 0;
00733 
00734   
00735   std::vector<bool> all_true(dfce->link_names_.size() + all_attached_bodies.size(), true);
00736   std::vector<bool> all_false(dfce->link_names_.size() + all_attached_bodies.size(), false);
00737 
00738   const std::vector<const moveit::core::LinkModel*>& lsv = state.getJointModelGroup(group_name)->getUpdatedLinkModels();
00739   dfce->self_collision_enabled_.resize(dfce->link_names_.size() + all_attached_bodies.size(), true);
00740   dfce->intra_group_collision_enabled_.resize(dfce->link_names_.size() + all_attached_bodies.size());
00741 
00742   for (unsigned int i = 0; i < dfce->link_names_.size(); i++)
00743   {
00744     std::string link_name = dfce->link_names_[i];
00745     const moveit::core::LinkModel* link_state = dfce->state_->getLinkModel(link_name);
00746     bool found = false;
00747 
00748     for (unsigned int j = 0; j < lsv.size(); j++)
00749     {
00750       if (lsv[j]->getName() == link_name)
00751       {
00752         dfce->link_state_indices_.push_back(j);
00753         found = true;
00754         break;
00755       }
00756     }
00757 
00758     if (!found)
00759     {
00760       ROS_DEBUG("No link state found for link %s", dfce->link_names_[i].c_str());
00761       continue;
00762     }
00763 
00764     if (link_state->getShapes().size() > 0)
00765     {
00766       dfce->link_has_geometry_.push_back(true);
00767       dfce->link_body_indices_.push_back(link_body_decomposition_index_map_.find(link_name)->second);
00768 
00769       if (acm)
00770       {
00771         collision_detection::AllowedCollision::Type t;
00772         if (acm->getEntry(link_name, link_name, t) && t == collision_detection::AllowedCollision::ALWAYS)
00773         {
00774           dfce->self_collision_enabled_[i] = false;
00775         }
00776 
00777         dfce->intra_group_collision_enabled_[i] = all_true;
00778         for (unsigned int j = i + 1; j < dfce->link_names_.size(); j++)
00779         {
00780           if (link_name == dfce->link_names_[j])
00781           {
00782             dfce->intra_group_collision_enabled_[i][j] = false;
00783             continue;
00784           }
00785           if (acm->getEntry(link_name, dfce->link_names_[j], t) && t == collision_detection::AllowedCollision::ALWAYS)
00786           {
00787             dfce->intra_group_collision_enabled_[i][j] = false;
00788           }
00789         }
00790 
00791         std::vector<const moveit::core::AttachedBody*> link_attached_bodies;
00792         state.getAttachedBodies(link_attached_bodies, link_state);
00793         for (unsigned int j = 0; j < link_attached_bodies.size(); j++, att_count++)
00794         {
00795           dfce->attached_body_names_.push_back(link_attached_bodies[j]->getName());
00796           dfce->attached_body_link_state_indices_.push_back(dfce->link_state_indices_[i]);
00797 
00798           if (acm->getEntry(link_name, link_attached_bodies[j]->getName(), t))
00799           {
00800             if (t == collision_detection::AllowedCollision::ALWAYS)
00801             {
00802               dfce->intra_group_collision_enabled_[i][att_count + dfce->link_names_.size()] = false;
00803             }
00804           }
00805           
00806           
00807           
00808           
00809           
00810           if (link_attached_bodies[j]->getTouchLinks().find(link_name) !=
00811               link_attached_bodies[j]->getTouchLinks().end())
00812           {
00813             dfce->intra_group_collision_enabled_[i][att_count + dfce->link_names_.size()] = false;
00814             
00815             
00816             
00817           }
00818         }
00819       }
00820       else
00821       {
00822         dfce->self_collision_enabled_[i] = true;
00823         dfce->intra_group_collision_enabled_[i] = all_true;
00824       }
00825     }
00826     else
00827     {
00828       dfce->link_has_geometry_.push_back(false);
00829       dfce->link_body_indices_.push_back(0);
00830       dfce->self_collision_enabled_[i] = false;
00831       dfce->intra_group_collision_enabled_[i] = all_false;
00832     }
00833   }
00834 
00835   for (unsigned int i = 0; i < dfce->attached_body_names_.size(); i++)
00836   {
00837     dfce->intra_group_collision_enabled_[i + dfce->link_names_.size()] = all_true;
00838     if (acm)
00839     {
00840       collision_detection::AllowedCollision::Type t;
00841       if (acm->getEntry(dfce->attached_body_names_[i], dfce->attached_body_names_[i], t) &&
00842           t == collision_detection::AllowedCollision::ALWAYS)
00843       {
00844         dfce->self_collision_enabled_[i + dfce->link_names_.size()] = false;
00845       }
00846       for (unsigned int j = i + 1; j < dfce->attached_body_names_.size(); j++)
00847       {
00848         if (acm->getEntry(dfce->attached_body_names_[i], dfce->attached_body_names_[j], t) &&
00849             t == collision_detection::AllowedCollision::ALWAYS)
00850         {
00851           dfce->intra_group_collision_enabled_[i + dfce->link_names_.size()][j + dfce->link_names_.size()] = false;
00852         }
00853         
00854         
00855         
00856         
00857         
00858       }
00859     }
00860   }
00861 
00862   std::map<std::string, boost::shared_ptr<GroupStateRepresentation>>::const_iterator it =
00863       pregenerated_group_state_representation_map_.find(dfce->group_name_);
00864   if (it != pregenerated_group_state_representation_map_.end())
00865   {
00866     dfce->pregenerated_group_state_representation_ = it->second;
00867   }
00868 
00869   std::map<std::string, bool> updated_map;
00870   if (!dfce->link_names_.empty())
00871   {
00872     const std::vector<const moveit::core::JointModel*>& child_joint_models =
00873         dfce->state_->getJointModelGroup(dfce->group_name_)->getActiveJointModels();
00874     for (unsigned int i = 0; i < child_joint_models.size(); i++)
00875     {
00876       updated_map[child_joint_models[i]->getName()] = true;
00877       ROS_DEBUG_STREAM("Joint " << child_joint_models[i]->getName() << " has been added to updated list");
00878     }
00879   }
00880 
00881   const std::vector<std::string> state_variable_names = state.getVariableNames();
00882   for (std::vector<std::string>::const_iterator name_iter = state_variable_names.begin();
00883        name_iter != state_variable_names.end(); name_iter++)
00884   {
00885     double val = state.getVariablePosition(*name_iter);
00886     dfce->state_values_.push_back(val);
00887     if (updated_map.count(*name_iter) == 0)
00888     {
00889       dfce->state_check_indices_.push_back(dfce->state_values_.size() - 1);
00890       ROS_DEBUG_STREAM("Non-group joint " << *name_iter << " will be checked for state changes");
00891     }
00892   }
00893 
00894   if (generate_distance_field)
00895   {
00896     if (dfce->distance_field_)
00897     {
00898       ROS_DEBUG_STREAM("CollisionRobot skipping distance field generation, "
00899                        "will use existing one");
00900     }
00901     else
00902     {
00903       std::vector<PosedBodyPointDecompositionPtr> non_group_link_decompositions;
00904       std::vector<PosedBodyPointDecompositionVectorPtr> non_group_attached_body_decompositions;
00905       const std::map<std::string, bool>& updated_group_map = in_group_update_map_.find(group_name)->second;
00906       for (unsigned int i = 0; i < robot_model_->getLinkModelsWithCollisionGeometry().size(); i++)
00907       {
00908         std::string link_name = robot_model_->getLinkModelsWithCollisionGeometry()[i]->getName();
00909         const moveit::core::LinkModel* link_state = dfce->state_->getLinkModel(link_name);
00910         if (updated_group_map.find(link_name) != updated_group_map.end())
00911         {
00912           continue;
00913         }
00914 
00915         
00916         non_group_link_decompositions.push_back(getPosedLinkBodyPointDecomposition(link_state));
00917         non_group_link_decompositions.back()->updatePose(dfce->state_->getFrameTransform(link_state->getName()));
00918 
00919         std::vector<const moveit::core::AttachedBody*> attached_bodies;
00920         dfce->state_->getAttachedBodies(attached_bodies, link_state);
00921         for (unsigned int j = 0; j < attached_bodies.size(); j++)
00922         {
00923           non_group_attached_body_decompositions.push_back(
00924               getAttachedBodyPointDecomposition(attached_bodies[j], resolution_));
00925         }
00926       }
00927       dfce->distance_field_.reset(new distance_field::PropagationDistanceField(
00928           size_.x(), size_.y(), size_.z(), resolution_, origin_.x() - 0.5 * size_.x(), origin_.y() - 0.5 * size_.y(),
00929           origin_.z() - 0.5 * size_.z(), max_propogation_distance_, use_signed_distance_field_));
00930 
00931       
00932       
00933       
00934       
00935       
00936       EigenSTL::vector_Vector3d all_points;
00937       for (unsigned int i = 0; i < non_group_link_decompositions.size(); i++)
00938       {
00939         all_points.insert(all_points.end(), non_group_link_decompositions[i]->getCollisionPoints().begin(),
00940                           non_group_link_decompositions[i]->getCollisionPoints().end());
00941       }
00942 
00943       for (unsigned int i = 0; i < non_group_attached_body_decompositions.size(); i++)
00944       {
00945         all_points.insert(all_points.end(), non_group_attached_body_decompositions[i]->getCollisionPoints().begin(),
00946                           non_group_attached_body_decompositions[i]->getCollisionPoints().end());
00947       }
00948 
00949       dfce->distance_field_->addPointsToField(all_points);
00950       ROS_DEBUG_STREAM("CollisionRobot distance field has been initialized with " << all_points.size() << " points.");
00951     }
00952   }
00953   return dfce;
00954 }
00955 
00956 void CollisionRobotDistanceField::addLinkBodyDecompositions(double resolution)
00957 {
00958   const std::vector<const moveit::core::LinkModel*>& link_models = robot_model_->getLinkModelsWithCollisionGeometry();
00959   for (unsigned int i = 0; i < link_models.size(); i++)
00960   {
00961     if (link_models[i]->getShapes().empty())
00962     {
00963       ROS_WARN("No collision geometry for link model %s though there should be", link_models[i]->getName().c_str());
00964       continue;
00965     }
00966 
00967     ROS_DEBUG("Generating model for %s", link_models[i]->getName().c_str());
00968     BodyDecompositionConstPtr bd(new BodyDecomposition(link_models[i]->getShapes(),
00969                                                        link_models[i]->getCollisionOriginTransforms(), resolution,
00970                                                        getLinkPadding(link_models[i]->getName())));
00971     link_body_decomposition_vector_.push_back(bd);
00972     link_body_decomposition_index_map_[link_models[i]->getName()] = link_body_decomposition_vector_.size() - 1;
00973   }
00974 }
00975 
00976 void CollisionRobotDistanceField::createCollisionModelMarker(const moveit::core::RobotState& state,
00977                                                              visualization_msgs::MarkerArray& model_markers) const
00978 {
00979   
00980   std_msgs::ColorRGBA robot_color;
00981   robot_color.r = 0;
00982   robot_color.b = 0.8f;
00983   robot_color.g = 0;
00984   robot_color.a = 0.5;
00985 
00986   std_msgs::ColorRGBA world_links_color;
00987   world_links_color.r = 1;
00988   world_links_color.g = 1;
00989   world_links_color.b = 0;
00990   world_links_color.a = 0.5;
00991 
00992   
00993   visualization_msgs::Marker sphere_marker;
00994   sphere_marker.header.frame_id = robot_model_->getRootLinkName();
00995   sphere_marker.header.stamp = ros::Time(0);
00996   sphere_marker.ns = distance_field_cache_entry_->group_name_ + "_sphere_decomposition";
00997   sphere_marker.id = 0;
00998   sphere_marker.type = visualization_msgs::Marker::SPHERE;
00999   sphere_marker.action = visualization_msgs::Marker::ADD;
01000   sphere_marker.pose.orientation.x = 0;
01001   sphere_marker.pose.orientation.y = 0;
01002   sphere_marker.pose.orientation.z = 0;
01003   sphere_marker.pose.orientation.w = 1;
01004   sphere_marker.color = robot_color;
01005   sphere_marker.lifetime = ros::Duration(0);
01006 
01007   unsigned int id = 0;
01008   const std::vector<const moveit::core::LinkModel*>& link_models = robot_model_->getLinkModelsWithCollisionGeometry();
01009   const moveit::core::JointModelGroup* joint_group = state.getJointModelGroup(distance_field_cache_entry_->group_name_);
01010   const std::vector<std::string>& group_link_names = joint_group->getUpdatedLinkModelNames();
01011 
01012   std::map<std::string, unsigned int>::const_iterator map_iter;
01013   for (map_iter = link_body_decomposition_index_map_.begin(); map_iter != link_body_decomposition_index_map_.end();
01014        map_iter++)
01015   {
01016     const std::string& link_name = map_iter->first;
01017     unsigned int link_index = map_iter->second;
01018 
01019     
01020     if (std::find(group_link_names.begin(), group_link_names.end(), link_name) != group_link_names.end())
01021     {
01022       sphere_marker.color = robot_color;
01023     }
01024     else
01025     {
01026       sphere_marker.color = world_links_color;
01027     }
01028 
01029     collision_detection::PosedBodySphereDecompositionPtr sphere_representation(
01030         new PosedBodySphereDecomposition(link_body_decomposition_vector_[link_index]));
01031     sphere_representation->updatePose(state.getGlobalLinkTransform(link_name));
01032     for (unsigned int j = 0; j < sphere_representation->getCollisionSpheres().size(); j++)
01033     {
01034       tf::pointEigenToMsg(sphere_representation->getSphereCenters()[j], sphere_marker.pose.position);
01035       sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z =
01036           2 * sphere_representation->getCollisionSpheres()[j].radius_;
01037       sphere_marker.id = id;
01038       id++;
01039 
01040       model_markers.markers.push_back(sphere_marker);
01041     }
01042   }
01043 }
01044 
01045 void CollisionRobotDistanceField::addLinkBodyDecompositions(
01046     double resolution, const std::map<std::string, std::vector<CollisionSphere>>& link_spheres)
01047 {
01048   ROS_ASSERT_MSG(robot_model_, "RobotModelPtr is invalid");
01049   const std::vector<const moveit::core::LinkModel*>& link_models = robot_model_->getLinkModelsWithCollisionGeometry();
01050 
01051   for (unsigned int i = 0; i < link_models.size(); i++)
01052   {
01053     if (link_models[i]->getShapes().empty())
01054     {
01055       ROS_WARN_STREAM("Skipping model generation for link " << link_models[i]->getName() << " since it contains no "
01056                                                                                             "geometries");
01057       continue;
01058     }
01059 
01060     BodyDecompositionPtr bd(new BodyDecomposition(link_models[i]->getShapes(),
01061                                                   link_models[i]->getCollisionOriginTransforms(), resolution,
01062                                                   getLinkPadding(link_models[i]->getName())));
01063 
01064     ROS_DEBUG("Generated model for %s", link_models[i]->getName().c_str());
01065 
01066     if (link_spheres.find(link_models[i]->getName()) != link_spheres.end())
01067     {
01068       bd->replaceCollisionSpheres(link_spheres.find(link_models[i]->getName())->second, Eigen::Affine3d::Identity());
01069     }
01070     link_body_decomposition_vector_.push_back(bd);
01071     link_body_decomposition_index_map_[link_models[i]->getName()] = link_body_decomposition_vector_.size() - 1;
01072   }
01073   ROS_DEBUG_STREAM(__FUNCTION__ << " Finished ");
01074 }
01075 
01076 PosedBodySphereDecompositionPtr CollisionRobotDistanceField::getPosedLinkBodySphereDecomposition(
01077     const moveit::core::LinkModel* ls, unsigned int ind) const
01078 {
01079   PosedBodySphereDecompositionPtr ret;
01080   ret.reset(new PosedBodySphereDecomposition(link_body_decomposition_vector_[ind]));
01081   return ret;
01082 }
01083 
01084 PosedBodyPointDecompositionPtr
01085 CollisionRobotDistanceField::getPosedLinkBodyPointDecomposition(const moveit::core::LinkModel* ls) const
01086 {
01087   PosedBodyPointDecompositionPtr ret;
01088   std::map<std::string, unsigned int>::const_iterator it = link_body_decomposition_index_map_.find(ls->getName());
01089   if (it == link_body_decomposition_index_map_.end())
01090   {
01091     logError("No link body decomposition for link %s.", ls->getName().c_str());
01092     return ret;
01093   }
01094   ret.reset(new PosedBodyPointDecomposition(link_body_decomposition_vector_[it->second]));
01095   return ret;
01096 }
01097 
01098 void CollisionRobotDistanceField::updateGroupStateRepresentationState(
01099     const moveit::core::RobotState& state, boost::shared_ptr<GroupStateRepresentation>& gsr) const
01100 {
01101   for (unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++)
01102   {
01103     const moveit::core::LinkModel* ls = state.getLinkModel(gsr->dfce_->link_names_[i]);
01104     if (gsr->dfce_->link_has_geometry_[i])
01105     {
01106       gsr->link_body_decompositions_[i]->updatePose(state.getFrameTransform(ls->getName()));
01107       gsr->link_distance_fields_[i]->updatePose(state.getFrameTransform(ls->getName()));
01108       gsr->gradients_[i].closest_distance = DBL_MAX;
01109       gsr->gradients_[i].collision = false;
01110       gsr->gradients_[i].types.assign(gsr->link_body_decompositions_[i]->getCollisionSpheres().size(), NONE);
01111       gsr->gradients_[i].distances.assign(gsr->link_body_decompositions_[i]->getCollisionSpheres().size(), DBL_MAX);
01112       gsr->gradients_[i].gradients.assign(gsr->link_body_decompositions_[i]->getCollisionSpheres().size(),
01113                                           Eigen::Vector3d(0.0, 0.0, 0.0));
01114       gsr->gradients_[i].sphere_locations = gsr->link_body_decompositions_[i]->getSphereCenters();
01115     }
01116   }
01117 
01118   for (unsigned int i = 0; i < gsr->dfce_->attached_body_names_.size(); i++)
01119   {
01120     int link_index = gsr->dfce_->attached_body_link_state_indices_[i];
01121     const moveit::core::AttachedBody* att = state.getAttachedBody(gsr->dfce_->attached_body_names_[i]);
01122     if (!att)
01123     {
01124       ROS_WARN("Attached body discrepancy");
01125       continue;
01126     }
01127 
01128     
01129     if (gsr->attached_body_decompositions_.size() != att->getShapes().size())
01130     {
01131       ROS_WARN("Attached body size discrepancy");
01132       continue;
01133     }
01134 
01135     for (unsigned int j = 0; j < att->getShapes().size(); j++)
01136     {
01137       gsr->attached_body_decompositions_[i]->updatePose(j, att->getGlobalCollisionBodyTransforms()[j]);
01138     }
01139 
01140     gsr->gradients_[i + gsr->dfce_->link_names_.size()].closest_distance = DBL_MAX;
01141     gsr->gradients_[i + gsr->dfce_->link_names_.size()].collision = false;
01142     gsr->gradients_[i + gsr->dfce_->link_names_.size()].types.assign(
01143         gsr->attached_body_decompositions_[i]->getCollisionSpheres().size(), NONE);
01144     gsr->gradients_[i + gsr->dfce_->link_names_.size()].distances.assign(
01145         gsr->attached_body_decompositions_[i]->getCollisionSpheres().size(), DBL_MAX);
01146     gsr->gradients_[i + gsr->dfce_->link_names_.size()].gradients.assign(
01147         gsr->attached_body_decompositions_[i]->getCollisionSpheres().size(), Eigen::Vector3d(0.0, 0.0, 0.0));
01148     gsr->gradients_[i + gsr->dfce_->link_names_.size()].sphere_locations =
01149         gsr->attached_body_decompositions_[i]->getSphereCenters();
01150   }
01151 }
01152 
01153 void CollisionRobotDistanceField::getGroupStateRepresentation(
01154     const boost::shared_ptr<const DistanceFieldCacheEntry>& dfce, const moveit::core::RobotState& state,
01155     boost::shared_ptr<GroupStateRepresentation>& gsr) const
01156 {
01157   if (!dfce->pregenerated_group_state_representation_)
01158   {
01159     ROS_DEBUG_STREAM("Creating GroupStateRepresentation");
01160 
01161     
01162     ros::WallTime b = ros::WallTime::now();
01163     gsr.reset(new GroupStateRepresentation());
01164     gsr->dfce_ = dfce;
01165     gsr->gradients_.resize(dfce->link_names_.size() + dfce->attached_body_names_.size());
01166 
01167     Eigen::Vector3d link_size;
01168     Eigen::Vector3d link_origin;
01169     for (unsigned int i = 0; i < dfce->link_names_.size(); i++)
01170     {
01171       const moveit::core::LinkModel* ls = state.getLinkModel(dfce->link_names_[i]);
01172       if (dfce->link_has_geometry_[i])
01173       {
01174         
01175         gsr->link_body_decompositions_.push_back(getPosedLinkBodySphereDecomposition(ls, dfce->link_body_indices_[i]));
01176 
01177         
01178         PosedBodySphereDecompositionPtr& link_bd = gsr->link_body_decompositions_.back();
01179         double diameter = 2 * link_bd->getBoundingSphereRadius();
01180         link_size = Eigen::Vector3d(diameter, diameter, diameter);
01181         link_origin = link_bd->getBoundingSphereCenter() - 0.5 * link_size;
01182 
01183         ROS_DEBUG_STREAM("Creating PosedDistanceField for link "
01184                          << dfce->link_names_[i] << " with size [" << link_size.x() << ", " << link_size.y() << ", "
01185                          << link_size.z() << "] and origin " << link_origin.x() << ", " << link_origin.y() << ", "
01186                          << link_origin.z());
01187 
01188         gsr->link_distance_fields_.push_back(PosedDistanceFieldPtr(new PosedDistanceField(
01189             link_size, link_origin, resolution_, max_propogation_distance_, use_signed_distance_field_)));
01190         gsr->link_distance_fields_.back()->addPointsToField(link_bd->getCollisionPoints());
01191         ROS_DEBUG_STREAM("Created PosedDistanceField for link " << dfce->link_names_[i] << " with "
01192                                                                 << link_bd->getCollisionPoints().size() << " points");
01193 
01194         gsr->link_body_decompositions_.back()->updatePose(state.getFrameTransform(ls->getName()));
01195         gsr->link_distance_fields_.back()->updatePose(state.getFrameTransform(ls->getName()));
01196         gsr->gradients_[i].types.resize(gsr->link_body_decompositions_.back()->getCollisionSpheres().size(), NONE);
01197         gsr->gradients_[i].distances.resize(gsr->link_body_decompositions_.back()->getCollisionSpheres().size(),
01198                                             DBL_MAX);
01199         gsr->gradients_[i].gradients.resize(gsr->link_body_decompositions_.back()->getCollisionSpheres().size());
01200         gsr->gradients_[i].sphere_radii = gsr->link_body_decompositions_.back()->getSphereRadii();
01201         gsr->gradients_[i].joint_name = ls->getParentJointModel()->getName();
01202       }
01203       else
01204       {
01205         gsr->link_body_decompositions_.push_back(PosedBodySphereDecompositionPtr());
01206         gsr->link_distance_fields_.push_back(PosedDistanceFieldPtr());
01207       }
01208     }
01209   }
01210   else
01211   {
01212     gsr.reset(new GroupStateRepresentation(*(dfce->pregenerated_group_state_representation_)));
01213     gsr->dfce_ = dfce;
01214     gsr->gradients_.resize(dfce->link_names_.size() + dfce->attached_body_names_.size());
01215     for (unsigned int i = 0; i < dfce->link_names_.size(); i++)
01216     {
01217       const moveit::core::LinkModel* ls = state.getLinkModel(dfce->link_names_[i]);
01218       if (dfce->link_has_geometry_[i])
01219       {
01220         gsr->link_body_decompositions_[i]->updatePose(state.getFrameTransform(ls->getName()));
01221         gsr->link_distance_fields_[i]->updatePose(state.getFrameTransform(ls->getName()));
01222         gsr->gradients_[i].sphere_locations = gsr->link_body_decompositions_[i]->getSphereCenters();
01223       }
01224     }
01225   }
01226 
01227   for (unsigned int i = 0; i < dfce->attached_body_names_.size(); i++)
01228   {
01229     int link_index = dfce->attached_body_link_state_indices_[i];
01230     const moveit::core::LinkModel* ls =
01231         state.getJointModelGroup(gsr->dfce_->group_name_)->getUpdatedLinkModels()[link_index];
01232     
01233     
01236     gsr->attached_body_decompositions_.push_back(
01237         getAttachedBodySphereDecomposition(state.getAttachedBody(dfce->attached_body_names_[i]), resolution_));
01238     gsr->gradients_[i + dfce->link_names_.size()].types.resize(
01239         gsr->attached_body_decompositions_.back()->getCollisionSpheres().size(), NONE);
01240     gsr->gradients_[i + dfce->link_names_.size()].distances.resize(
01241         gsr->attached_body_decompositions_.back()->getCollisionSpheres().size(), DBL_MAX);
01242     gsr->gradients_[i + dfce->link_names_.size()].gradients.resize(
01243         gsr->attached_body_decompositions_.back()->getCollisionSpheres().size());
01244     gsr->gradients_[i + dfce->link_names_.size()].sphere_locations =
01245         gsr->attached_body_decompositions_.back()->getSphereCenters();
01246     gsr->gradients_[i + dfce->link_names_.size()].sphere_radii =
01247         gsr->attached_body_decompositions_.back()->getSphereRadii();
01248     gsr->gradients_[i + dfce->link_names_.size()].joint_name = ls->getParentJointModel()->getName();
01249   }
01250 }
01251 
01252 bool CollisionRobotDistanceField::compareCacheEntryToState(const boost::shared_ptr<const DistanceFieldCacheEntry>& dfce,
01253                                                            const moveit::core::RobotState& state) const
01254 {
01255   std::vector<double> new_state_values(state.getVariableCount());
01256   for (unsigned int i = 0; i < new_state_values.size(); i++)
01257   {
01258     new_state_values[i] = state.getVariablePosition(i);
01259   }
01260 
01261   if (dfce->state_values_.size() != new_state_values.size())
01262   {
01263     ROS_ERROR("State value size mismatch");
01264     return false;
01265   }
01266 
01267   for (unsigned int i = 0; i < dfce->state_check_indices_.size(); i++)
01268   {
01269     double diff =
01270         fabs(dfce->state_values_[dfce->state_check_indices_[i]] - new_state_values[dfce->state_check_indices_[i]]);
01271     if (diff > EPSILON)
01272     {
01273       ROS_WARN_STREAM("State for Variable " << state.getVariableNames()[dfce->state_check_indices_[i]]
01274                                             << " has changed by " << diff << " radians");
01275       return false;
01276     }
01277   }
01278   std::vector<const moveit::core::AttachedBody*> attached_bodies_dfce;
01279   std::vector<const moveit::core::AttachedBody*> attached_bodies_state;
01280   dfce->state_->getAttachedBodies(attached_bodies_dfce);
01281   state.getAttachedBodies(attached_bodies_state);
01282   if (attached_bodies_dfce.size() != attached_bodies_state.size())
01283   {
01284     return false;
01285   }
01286   
01287   for (unsigned int i = 0; i < attached_bodies_dfce.size(); i++)
01288   {
01289     if (attached_bodies_dfce[i]->getName() != attached_bodies_state[i]->getName())
01290     {
01291       return false;
01292     }
01293     if (attached_bodies_dfce[i]->getTouchLinks() != attached_bodies_state[i]->getTouchLinks())
01294     {
01295       return false;
01296     }
01297     if (attached_bodies_dfce[i]->getShapes().size() != attached_bodies_state[i]->getShapes().size())
01298     {
01299       return false;
01300     }
01301     for (unsigned int j = 0; j < attached_bodies_dfce[i]->getShapes().size(); j++)
01302     {
01303       if (attached_bodies_dfce[i]->getShapes()[j] != attached_bodies_state[i]->getShapes()[j])
01304       {
01305         return false;
01306       }
01307     }
01308   }
01309   return true;
01310 }
01311 
01312 bool CollisionRobotDistanceField::compareCacheEntryToAllowedCollisionMatrix(
01313     const boost::shared_ptr<const DistanceFieldCacheEntry>& dfce,
01314     const collision_detection::AllowedCollisionMatrix& acm) const
01315 {
01316   if (dfce->acm_.getSize() != acm.getSize())
01317   {
01318     ROS_DEBUG("Allowed collision matrix size mismatch");
01319     return false;
01320   }
01321   std::vector<const moveit::core::AttachedBody*> attached_bodies;
01322   dfce->state_->getAttachedBodies(attached_bodies);
01323   for (unsigned int i = 0; i < dfce->link_names_.size(); i++)
01324   {
01325     std::string link_name = dfce->link_names_[i];
01326     if (dfce->link_has_geometry_[i])
01327     {
01328       bool self_collision_enabled = true;
01329       collision_detection::AllowedCollision::Type t;
01330       if (acm.getEntry(link_name, link_name, t))
01331       {
01332         if (t == collision_detection::AllowedCollision::ALWAYS)
01333         {
01334           self_collision_enabled = false;
01335         }
01336       }
01337       if (self_collision_enabled != dfce->self_collision_enabled_[i])
01338       {
01339         
01340         
01341         
01342         return false;
01343       }
01344       for (unsigned int j = i; j < dfce->link_names_.size(); j++)
01345       {
01346         if (i == j)
01347           continue;
01348         if (dfce->link_has_geometry_[j])
01349         {
01350           bool intra_collision_enabled = true;
01351           if (acm.getEntry(link_name, dfce->link_names_[j], t))
01352           {
01353             if (t == collision_detection::AllowedCollision::ALWAYS)
01354             {
01355               intra_collision_enabled = false;
01356             }
01357           }
01358           if (dfce->intra_group_collision_enabled_[i][j] != intra_collision_enabled)
01359           {
01360             
01361             
01362             
01363             
01364             
01365             return false;
01366           }
01367         }
01368       }
01369     }
01370   }
01371   return true;
01372 }
01373 
01374 
01375 
01376 
01377 
01378 
01379 
01380 
01381 
01382 
01383 }