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 the 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;
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     bool full_coverage = true;
00090     for (std::map<std::string, bool>::iterator it = joint_coverage.begin(); it != joint_coverage.end(); ++it)
00091       if (!it->second)
00092       {
00093         full_coverage = false;
00094         break;
00095       }
00096 
00097     // if we have constrained every joint, then we just use a sampler using these constraints
00098     if (full_coverage)
00099     {
00100       boost::shared_ptr<JointConstraintSampler> sampler(new JointConstraintSampler(scene, jmg->getName()));
00101       if (sampler->configure(jc))
00102       {
00103         logDebug("Allocated a sampler satisfying joint constraints for group '%s'", jmg->getName().c_str());
00104         return sampler;
00105       }
00106     }
00107     else
00108       // 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.
00109       if (!jc.empty())
00110       {
00111         boost::shared_ptr<JointConstraintSampler> sampler(new JointConstraintSampler(scene, jmg->getName()));
00112         if (sampler->configure(jc))
00113         {
00114           logDebug("Temporary sampler satisfying joint constraints for group '%s' allocated. Looking for different types of constraints before returning though.", jmg->getName().c_str());
00115           joint_sampler = sampler;
00116         }
00117       }
00118   }
00119 
00120   std::vector<ConstraintSamplerPtr> samplers;
00121   if (joint_sampler)
00122     samplers.push_back(joint_sampler);
00123 
00124   // read the ik allocators, if any
00125   robot_model::SolverAllocatorFn ik_alloc = jmg->getSolverAllocators().first;
00126   std::map<const robot_model::JointModelGroup*, robot_model::SolverAllocatorFn> ik_subgroup_alloc = jmg->getSolverAllocators().second;
00127 
00128   // 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
00129   if (ik_alloc)
00130   {
00131     logDebug("There is an IK allocator for '%s'. Checking for corresponding position and/or orientation constraints", jmg->getName().c_str());
00132 
00133     // keep track of which links we constrained
00134     std::map<std::string, boost::shared_ptr<IKConstraintSampler> > usedL;
00135 
00136     // if we have position and/or orientation constraints on links that we can perform IK for,
00137     // we will use a sampleable goal region that employs IK to sample goals;
00138     // if there are multiple constraints for the same link, we keep the one with the smallest
00139     // volume for sampling
00140     for (std::size_t p = 0 ; p < constr.position_constraints.size() ; ++p)
00141       for (std::size_t o = 0 ; o < constr.orientation_constraints.size() ; ++o)
00142         if (constr.position_constraints[p].link_name == constr.orientation_constraints[o].link_name)
00143         {
00144           boost::shared_ptr<kinematic_constraints::PositionConstraint> pc(new kinematic_constraints::PositionConstraint(scene->getRobotModel()));
00145           boost::shared_ptr<kinematic_constraints::OrientationConstraint> oc(new kinematic_constraints::OrientationConstraint(scene->getRobotModel()));
00146           if (pc->configure(constr.position_constraints[p], scene->getTransforms()) && oc->configure(constr.orientation_constraints[o], scene->getTransforms()))
00147           {
00148             boost::shared_ptr<IKConstraintSampler> iks(new IKConstraintSampler(scene, jmg->getName()));
00149             if(iks->configure(IKSamplingPose(pc, oc))) {
00150               bool use = true;
00151               if (usedL.find(constr.position_constraints[p].link_name) != usedL.end())
00152                 if (usedL[constr.position_constraints[p].link_name]->getSamplingVolume() < iks->getSamplingVolume())
00153                   use = false;
00154               if (use)
00155               {
00156                 usedL[constr.position_constraints[p].link_name] = iks;
00157                 logDebug("Allocated an IK-based sampler for group '%s' satisfying position and orientation constraints on link '%s'",
00158                          jmg->getName().c_str(), constr.position_constraints[p].link_name.c_str());
00159               }
00160             }
00161           }
00162         }
00163 
00164     // keep track of links constrained with a full pose
00165     std::map<std::string, boost::shared_ptr<IKConstraintSampler> > usedL_fullPose = usedL;
00166 
00167     for (std::size_t p = 0 ; p < constr.position_constraints.size() ; ++p)
00168     {
00169       // if we are constraining this link with a full pose, we do not attempt to constrain it with a position constraint only
00170       if (usedL_fullPose.find(constr.position_constraints[p].link_name) != usedL_fullPose.end())
00171         continue;
00172 
00173       boost::shared_ptr<kinematic_constraints::PositionConstraint> pc(new kinematic_constraints::PositionConstraint(scene->getRobotModel()));
00174       if (pc->configure(constr.position_constraints[p], scene->getTransforms()))
00175       {
00176         boost::shared_ptr<IKConstraintSampler> iks(new IKConstraintSampler(scene, jmg->getName()));
00177         if(iks->configure(IKSamplingPose(pc)))
00178         {
00179           bool use = true;
00180           if (usedL.find(constr.position_constraints[p].link_name) != usedL.end())
00181             if (usedL[constr.position_constraints[p].link_name]->getSamplingVolume() < iks->getSamplingVolume())
00182               use = false;
00183           if (use)
00184           {
00185             usedL[constr.position_constraints[p].link_name] = iks;
00186             logDebug("Allocated an IK-based sampler for group '%s' satisfying position constraints on link '%s'",
00187                      jmg->getName().c_str(), constr.position_constraints[p].link_name.c_str());
00188           }
00189         }
00190       }
00191     }
00192 
00193     for (std::size_t o = 0 ; o < constr.orientation_constraints.size() ; ++o)
00194     {
00195       // if we are constraining this link with a full pose, we do not attempt to constrain it with an orientation constraint only
00196       if (usedL_fullPose.find(constr.orientation_constraints[o].link_name) != usedL_fullPose.end())
00197         continue;
00198 
00199       boost::shared_ptr<kinematic_constraints::OrientationConstraint> oc(new kinematic_constraints::OrientationConstraint(scene->getRobotModel()));
00200       if (oc->configure(constr.orientation_constraints[o], scene->getTransforms()))
00201       {
00202         boost::shared_ptr<IKConstraintSampler> iks(new IKConstraintSampler(scene, jmg->getName()));
00203         if(iks->configure(IKSamplingPose(oc)))
00204         {
00205           bool use = true;
00206           if (usedL.find(constr.orientation_constraints[o].link_name) != usedL.end())
00207             if (usedL[constr.orientation_constraints[o].link_name]->getSamplingVolume() < iks->getSamplingVolume())
00208               use = false;
00209           if (use)
00210           {
00211             usedL[constr.orientation_constraints[o].link_name] = iks;
00212             logDebug("Allocated an IK-based sampler for group '%s' satisfying orientation constraints on link '%s'",
00213                      jmg->getName().c_str(), constr.orientation_constraints[o].link_name.c_str());
00214           }
00215         }
00216       }
00217     }
00218 
00219     if (usedL.size() == 1)
00220     {
00221       if (samplers.empty())
00222         return usedL.begin()->second;
00223       else
00224       {
00225         samplers.push_back(usedL.begin()->second);
00226         return ConstraintSamplerPtr(new UnionConstraintSampler(scene, jmg->getName(), samplers));
00227       }
00228     }
00229     else
00230       if (usedL.size() > 1)
00231       {
00232         logDebug("Too many IK-based samplers for group '%s'. Keeping the one with minimal sampling volume", jmg->getName().c_str());
00233         // find the sampler with the smallest sampling volume; delete the rest
00234         boost::shared_ptr<IKConstraintSampler> iks = usedL.begin()->second;
00235         double msv = iks->getSamplingVolume();
00236         for (std::map<std::string, boost::shared_ptr<IKConstraintSampler> >::const_iterator it = ++usedL.begin() ; it != usedL.end() ; ++it)
00237         {
00238           double v = it->second->getSamplingVolume();
00239           if (v < msv)
00240           {
00241             iks = it->second;
00242             msv = v;
00243           }
00244         }
00245         if (samplers.empty())
00246         {
00247           return iks;
00248         }
00249         else
00250         {
00251           samplers.push_back(iks);
00252           return ConstraintSamplerPtr(new UnionConstraintSampler(scene, jmg->getName(), samplers));
00253         }
00254       }
00255   }
00256 
00257   // if we got to this point, we have not decided on a sampler.
00258   // we now check to see if we can use samplers from subgroups
00259   if (!ik_subgroup_alloc.empty())
00260   {
00261     logDebug("There are IK allocators for subgroups of group '%s'. Checking for corresponding position and/or orientation constraints", jmg->getName().c_str());
00262 
00263     bool some_sampler_valid = false;
00264 
00265     std::set<std::size_t> usedP, usedO;
00266     for (std::map<const robot_model::JointModelGroup*, robot_model::SolverAllocatorFn>::const_iterator it = ik_subgroup_alloc.begin() ; it != ik_subgroup_alloc.end() ; ++it)
00267     {
00268       // construct a sub-set of constraints that operate on the sub-group for which we have an IK allocator
00269       moveit_msgs::Constraints sub_constr;
00270       for (std::size_t p = 0 ; p < constr.position_constraints.size() ; ++p)
00271         if (it->first->hasLinkModel(constr.position_constraints[p].link_name))
00272           if (usedP.find(p) == usedP.end())
00273           {
00274             sub_constr.position_constraints.push_back(constr.position_constraints[p]);
00275             usedP.insert(p);
00276           }
00277 
00278       for (std::size_t o = 0 ; o < constr.orientation_constraints.size() ; ++o)
00279         if (it->first->hasLinkModel(constr.orientation_constraints[o].link_name))
00280           if (usedO.find(o) == usedO.end())
00281           {
00282             sub_constr.orientation_constraints.push_back(constr.orientation_constraints[o]);
00283             usedO.insert(o);
00284           }
00285 
00286       // if some matching constraints were found, construct the allocator
00287       if (!sub_constr.orientation_constraints.empty() || !sub_constr.position_constraints.empty())
00288       {
00289         logDebug("Attempting to construct a sampler for the '%s' subgroup of '%s'", it->first->getName().c_str(), jmg->getName().c_str());
00290         ConstraintSamplerPtr cs = selectDefaultSampler(scene, it->first->getName(), sub_constr);
00291         if (cs)
00292         {
00293           logDebug("Constructed a sampler for the joints corresponding to group '%s', but part of group '%s'",
00294                    it->first->getName().c_str(), jmg->getName().c_str());
00295           some_sampler_valid = true;
00296           samplers.push_back(cs);
00297         }
00298       }
00299     }
00300     if (some_sampler_valid)
00301     {
00302       logDebug("Constructing sampler for group '%s' as a union of %u samplers", jmg->getName().c_str(), (unsigned int)samplers.size());
00303       return ConstraintSamplerPtr(new UnionConstraintSampler(scene, jmg->getName(), samplers));
00304     }
00305   }
00306 
00307   //if we've gotten here, just return joint sampler
00308   if (joint_sampler)
00309   {
00310     logDebug("Allocated a sampler satisfying joint constraints for group '%s'", jmg->getName().c_str());
00311     return joint_sampler;
00312   }
00313 
00314   logDebug("No constraints sampler allocated for group '%s'", jmg->getName().c_str());
00315 
00316   return ConstraintSamplerPtr();
00317 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:46