constraint_sampler_manager.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 */
00036 
00037 #include <moveit/constraint_samplers/constraint_sampler_manager.h>
00038 #include <moveit/constraint_samplers/default_constraint_samplers.h>
00039 #include <moveit/constraint_samplers/union_constraint_sampler.h>
00040 #include <sstream>
00041 
00042 constraint_samplers::ConstraintSamplerPtr constraint_samplers::ConstraintSamplerManager::selectSampler(const planning_scene::PlanningSceneConstPtr &scene,
00043                                                                                                        const std::string &group_name,
00044                                                                                                        const moveit_msgs::Constraints &constr) const
00045 {
00046   for (std::size_t i = 0 ; i < sampler_alloc_.size() ; ++i)
00047     if (sampler_alloc_[i]->canService(scene, group_name, constr))
00048       return sampler_alloc_[i]->alloc(scene, group_name, constr);
00049 
00050   // if no default sampler was used, try a default one
00051   return selectDefaultSampler(scene, group_name, constr);
00052 }
00053 
00054 constraint_samplers::ConstraintSamplerPtr constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(const planning_scene::PlanningSceneConstPtr &scene,
00055                                                                                                               const std::string &group_name,
00056                                                                                                               const moveit_msgs::Constraints &constr)
00057 {
00058   const robot_model::JointModelGroup *jmg = scene->getRobotModel()->getJointModelGroup(group_name);
00059   if (!jmg)
00060     return constraint_samplers::ConstraintSamplerPtr();
00061   std::stringstream ss; ss << constr;
00062   logDebug("Attempting to construct constrained state sampler for group '%s', using constraints:\n%s.\n", jmg->getName().c_str(), ss.str().c_str());
00063 
00064   ConstraintSamplerPtr joint_sampler; // location to put chosen joint sampler if needed
00065   // if there are joint constraints, we could possibly get a sampler from those
00066   if (!constr.joint_constraints.empty())
00067   {
00068     logDebug("There are joint constraints specified. Attempting to construct a JointConstraintSampler for group '%s'", jmg->getName().c_str());
00069 
00070     std::map<std::string, bool> joint_coverage;
00071     for(std::size_t i = 0; i < jmg->getVariableNames().size() ; ++i)
00072       joint_coverage[jmg->getVariableNames()[i]] = false;
00073 
00074     // construct the constraints
00075     std::vector<kinematic_constraints::JointConstraint> jc;
00076     for (std::size_t i = 0 ; i < constr.joint_constraints.size() ; ++i)
00077     {
00078       kinematic_constraints::JointConstraint j(scene->getRobotModel());
00079       if (j.configure(constr.joint_constraints[i]))
00080       {
00081         if (joint_coverage.find(j.getJointVariableName()) != joint_coverage.end())
00082         {
00083           joint_coverage[j.getJointVariableName()] = true;
00084           jc.push_back(j);
00085         }
00086       }
00087     }
00088 
00089     // check if every joint is covered (constrained) by just joint samplers
00090     bool full_coverage = true;
00091     for (std::map<std::string, bool>::iterator it = joint_coverage.begin(); it != joint_coverage.end(); ++it)
00092       if (!it->second)
00093       {
00094         full_coverage = false;
00095         break;
00096       }
00097 
00098     // if we have constrained every joint, then we just use a sampler using these constraints
00099     if (full_coverage)
00100     {
00101       boost::shared_ptr<JointConstraintSampler> sampler(new JointConstraintSampler(scene, jmg->getName()));
00102       if (sampler->configure(jc))
00103       {
00104         logDebug("Allocated a sampler satisfying joint constraints for group '%s'", jmg->getName().c_str());
00105         return sampler;
00106       }
00107     }
00108     else
00109       // if a smaller set of joints has been specified, keep the constraint sampler around, but use it only if no IK sampler has been specified.
00110       if (!jc.empty())
00111       {
00112         boost::shared_ptr<JointConstraintSampler> sampler(new JointConstraintSampler(scene, jmg->getName()));
00113         if (sampler->configure(jc))
00114         {
00115           logDebug("Temporary sampler satisfying joint constraints for group '%s' allocated. Looking for different types of constraints before returning though.", jmg->getName().c_str());
00116           joint_sampler = sampler;
00117         }
00118       }
00119   }
00120 
00121   std::vector<ConstraintSamplerPtr> samplers;
00122   if (joint_sampler) // Start making a union of constraint samplers
00123     samplers.push_back(joint_sampler);
00124 
00125   // read the ik allocators, if any
00126   const robot_model::JointModelGroup::KinematicsSolver &ik_alloc = jmg->getGroupKinematics().first;
00127   const robot_model::JointModelGroup::KinematicsSolverMap &ik_subgroup_alloc = jmg->getGroupKinematics().second;
00128 
00129   // if we have a means of computing complete states for the group using IK, then we try to see if any IK constraints should be used
00130   if (ik_alloc)
00131   {
00132     logDebug("There is an IK allocator for '%s'. Checking for corresponding position and/or orientation constraints", jmg->getName().c_str());
00133 
00134     // keep track of which links we constrained
00135     std::map<std::string, boost::shared_ptr<IKConstraintSampler> > usedL;
00136 
00137     // if we have position and/or orientation constraints on links that we can perform IK for,
00138     // we will use a sampleable goal region that employs IK to sample goals;
00139     // if there are multiple constraints for the same link, we keep the one with the smallest
00140     // volume for sampling
00141     for (std::size_t p = 0 ; p < constr.position_constraints.size() ; ++p)
00142       for (std::size_t o = 0 ; o < constr.orientation_constraints.size() ; ++o)
00143         if (constr.position_constraints[p].link_name == constr.orientation_constraints[o].link_name)
00144         {
00145           boost::shared_ptr<kinematic_constraints::PositionConstraint> pc(new kinematic_constraints::PositionConstraint(scene->getRobotModel()));
00146           boost::shared_ptr<kinematic_constraints::OrientationConstraint> oc(new kinematic_constraints::OrientationConstraint(scene->getRobotModel()));
00147           if (pc->configure(constr.position_constraints[p], scene->getTransforms()) && oc->configure(constr.orientation_constraints[o], scene->getTransforms()))
00148           {
00149             boost::shared_ptr<IKConstraintSampler> iks(new IKConstraintSampler(scene, jmg->getName()));
00150             if(iks->configure(IKSamplingPose(pc, oc))) {
00151               bool use = true;
00152               // Check if there already is a constraint on this link
00153               if (usedL.find(constr.position_constraints[p].link_name) != usedL.end())
00154                 // If there is, check if the previous one has a smaller volume for sampling
00155                 if (usedL[constr.position_constraints[p].link_name]->getSamplingVolume() < iks->getSamplingVolume())
00156                   use = false; // only use new constraint if it has a smaller sampling volume
00157               if (use)
00158               {
00159                 // assign the link to a new constraint sampler
00160                 usedL[constr.position_constraints[p].link_name] = iks;
00161                 logDebug("Allocated an IK-based sampler for group '%s' satisfying position and orientation constraints on link '%s'",
00162                          jmg->getName().c_str(), constr.position_constraints[p].link_name.c_str());
00163               }
00164             }
00165           }
00166         }
00167 
00168     // keep track of links constrained with a full pose
00169     std::map<std::string, boost::shared_ptr<IKConstraintSampler> > usedL_fullPose = usedL;
00170 
00171     for (std::size_t p = 0 ; p < constr.position_constraints.size() ; ++p)
00172     {
00173       // if we are constraining this link with a full pose, we do not attempt to constrain it with a position constraint only
00174       if (usedL_fullPose.find(constr.position_constraints[p].link_name) != usedL_fullPose.end())
00175         continue;
00176 
00177       boost::shared_ptr<kinematic_constraints::PositionConstraint> pc(new kinematic_constraints::PositionConstraint(scene->getRobotModel()));
00178       if (pc->configure(constr.position_constraints[p], scene->getTransforms()))
00179       {
00180         boost::shared_ptr<IKConstraintSampler> iks(new IKConstraintSampler(scene, jmg->getName()));
00181         if(iks->configure(IKSamplingPose(pc)))
00182         {
00183           bool use = true;
00184           if (usedL.find(constr.position_constraints[p].link_name) != usedL.end())
00185             if (usedL[constr.position_constraints[p].link_name]->getSamplingVolume() < iks->getSamplingVolume())
00186               use = false;
00187           if (use)
00188           {
00189             usedL[constr.position_constraints[p].link_name] = iks;
00190             logDebug("Allocated an IK-based sampler for group '%s' satisfying position constraints on link '%s'",
00191                      jmg->getName().c_str(), constr.position_constraints[p].link_name.c_str());
00192           }
00193         }
00194       }
00195     }
00196 
00197     for (std::size_t o = 0 ; o < constr.orientation_constraints.size() ; ++o)
00198     {
00199       // if we are constraining this link with a full pose, we do not attempt to constrain it with an orientation constraint only
00200       if (usedL_fullPose.find(constr.orientation_constraints[o].link_name) != usedL_fullPose.end())
00201         continue;
00202 
00203       boost::shared_ptr<kinematic_constraints::OrientationConstraint> oc(new kinematic_constraints::OrientationConstraint(scene->getRobotModel()));
00204       if (oc->configure(constr.orientation_constraints[o], scene->getTransforms()))
00205       {
00206         boost::shared_ptr<IKConstraintSampler> iks(new IKConstraintSampler(scene, jmg->getName()));
00207         if(iks->configure(IKSamplingPose(oc)))
00208         {
00209           bool use = true;
00210           if (usedL.find(constr.orientation_constraints[o].link_name) != usedL.end())
00211             if (usedL[constr.orientation_constraints[o].link_name]->getSamplingVolume() < iks->getSamplingVolume())
00212               use = false;
00213           if (use)
00214           {
00215             usedL[constr.orientation_constraints[o].link_name] = iks;
00216             logDebug("Allocated an IK-based sampler for group '%s' satisfying orientation constraints on link '%s'",
00217                      jmg->getName().c_str(), constr.orientation_constraints[o].link_name.c_str());
00218           }
00219         }
00220       }
00221     }
00222 
00223     if (usedL.size() == 1)
00224     {
00225       if (samplers.empty())
00226         return usedL.begin()->second;
00227       else
00228       {
00229         samplers.push_back(usedL.begin()->second);
00230         return ConstraintSamplerPtr(new UnionConstraintSampler(scene, jmg->getName(), samplers));
00231       }
00232     }
00233     else
00234       if (usedL.size() > 1)
00235       {
00236         logDebug("Too many IK-based samplers for group '%s'. Keeping the one with minimal sampling volume", jmg->getName().c_str());
00237         // find the sampler with the smallest sampling volume; delete the rest
00238         boost::shared_ptr<IKConstraintSampler> iks = usedL.begin()->second;
00239         double msv = iks->getSamplingVolume();
00240         for (std::map<std::string, boost::shared_ptr<IKConstraintSampler> >::const_iterator it = ++usedL.begin() ; it != usedL.end() ; ++it)
00241         {
00242           double v = it->second->getSamplingVolume();
00243           if (v < msv)
00244           {
00245             iks = it->second;
00246             msv = v;
00247           }
00248         }
00249         if (samplers.empty())
00250         {
00251           return iks;
00252         }
00253         else
00254         {
00255           samplers.push_back(iks);
00256           return ConstraintSamplerPtr(new UnionConstraintSampler(scene, jmg->getName(), samplers));
00257         }
00258       }
00259   }
00260 
00261   // if we got to this point, we have not decided on a sampler.
00262   // we now check to see if we can use samplers from subgroups
00263   if (!ik_subgroup_alloc.empty())
00264   {
00265     logDebug("There are IK allocators for subgroups of group '%s'. Checking for corresponding position and/or orientation constraints", jmg->getName().c_str());
00266 
00267     bool some_sampler_valid = false;
00268 
00269     std::set<std::size_t> usedP, usedO;
00270     for (robot_model::JointModelGroup::KinematicsSolverMap::const_iterator it = ik_subgroup_alloc.begin() ; it != ik_subgroup_alloc.end() ; ++it)
00271     {
00272       // construct a sub-set of constraints that operate on the sub-group for which we have an IK allocator
00273       moveit_msgs::Constraints sub_constr;
00274       for (std::size_t p = 0 ; p < constr.position_constraints.size() ; ++p)
00275         if (it->first->hasLinkModel(constr.position_constraints[p].link_name))
00276           if (usedP.find(p) == usedP.end())
00277           {
00278             sub_constr.position_constraints.push_back(constr.position_constraints[p]);
00279             usedP.insert(p);
00280           }
00281 
00282       for (std::size_t o = 0 ; o < constr.orientation_constraints.size() ; ++o)
00283         if (it->first->hasLinkModel(constr.orientation_constraints[o].link_name))
00284           if (usedO.find(o) == usedO.end())
00285           {
00286             sub_constr.orientation_constraints.push_back(constr.orientation_constraints[o]);
00287             usedO.insert(o);
00288           }
00289 
00290       // if some matching constraints were found, construct the allocator
00291       if (!sub_constr.orientation_constraints.empty() || !sub_constr.position_constraints.empty())
00292       {
00293         logDebug("Attempting to construct a sampler for the '%s' subgroup of '%s'", it->first->getName().c_str(), jmg->getName().c_str());
00294         ConstraintSamplerPtr cs = selectDefaultSampler(scene, it->first->getName(), sub_constr);
00295         if (cs)
00296         {
00297           logDebug("Constructed a sampler for the joints corresponding to group '%s', but part of group '%s'",
00298                    it->first->getName().c_str(), jmg->getName().c_str());
00299           some_sampler_valid = true;
00300           samplers.push_back(cs);
00301         }
00302       }
00303     }
00304     if (some_sampler_valid)
00305     {
00306       logDebug("Constructing sampler for group '%s' as a union of %u samplers", jmg->getName().c_str(), (unsigned int)samplers.size());
00307       return ConstraintSamplerPtr(new UnionConstraintSampler(scene, jmg->getName(), samplers));
00308     }
00309   }
00310 
00311   //if we've gotten here, just return joint sampler
00312   if (joint_sampler)
00313   {
00314     logDebug("Allocated a sampler satisfying joint constraints for group '%s'", jmg->getName().c_str());
00315     return joint_sampler;
00316   }
00317 
00318   logDebug("No constraints sampler allocated for group '%s'", jmg->getName().c_str());
00319 
00320   return ConstraintSamplerPtr();
00321 }


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