planning_context_manager.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, 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/ompl_interface/planning_context_manager.h>
00038 #include <moveit/robot_state/conversions.h>
00039 #include <moveit/profiler/profiler.h>
00040 #include <algorithm>
00041 #include <set>
00042 
00043 #include <ompl/geometric/planners/rrt/RRT.h>
00044 #include <ompl/geometric/planners/rrt/pRRT.h>
00045 #include <ompl/geometric/planners/rrt/RRTConnect.h>
00046 #include <ompl/geometric/planners/rrt/TRRT.h>
00047 #include <ompl/geometric/planners/rrt/LazyRRT.h>
00048 #include <ompl/geometric/planners/est/EST.h>
00049 #include <ompl/geometric/planners/sbl/SBL.h>
00050 #include <ompl/geometric/planners/sbl/pSBL.h>
00051 #include <ompl/geometric/planners/kpiece/KPIECE1.h>
00052 #include <ompl/geometric/planners/kpiece/BKPIECE1.h>
00053 #include <ompl/geometric/planners/kpiece/LBKPIECE1.h>
00054 #include <ompl/geometric/planners/rrt/RRTstar.h>
00055 #include <ompl/geometric/planners/prm/PRM.h>
00056 #include <ompl/geometric/planners/prm/PRMstar.h>
00057 
00058 #include <moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h>
00059 #include <moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h>
00060 
00061 namespace ompl_interface
00062 {
00063 class PlanningContextManager::LastPlanningContext
00064 {
00065 public:
00066 
00067   ModelBasedPlanningContextPtr getContext()
00068   {
00069     boost::mutex::scoped_lock slock(lock_);
00070     return last_planning_context_solve_;
00071   }
00072 
00073   void setContext(const ModelBasedPlanningContextPtr &context)
00074   {
00075     boost::mutex::scoped_lock slock(lock_);
00076     last_planning_context_solve_ = context;
00077   }
00078 
00079   void clear()
00080   {
00081     boost::mutex::scoped_lock slock(lock_);
00082     last_planning_context_solve_.reset();
00083   }
00084 
00085 private:
00086   /* The planning group for which solve() was called last */
00087   ModelBasedPlanningContextPtr last_planning_context_solve_;
00088   boost::mutex                 lock_;
00089 };
00090 
00091 struct PlanningContextManager::CachedContexts
00092 {
00093   std::map<std::pair<std::string, std::string>,
00094            std::vector<ModelBasedPlanningContextPtr> > contexts_;
00095   boost::mutex                                         lock_;
00096 };
00097 
00098 } // namespace ompl_interface
00099 
00100 ompl_interface::PlanningContextManager::PlanningContextManager(const robot_model::RobotModelConstPtr &kmodel, const constraint_samplers::ConstraintSamplerManagerPtr &csm) :
00101   kmodel_(kmodel), constraint_sampler_manager_(csm),
00102   max_goal_samples_(10), max_state_sampling_attempts_(4), max_goal_sampling_attempts_(1000),
00103   max_planning_threads_(4), max_solution_segment_length_(0.0), minimum_waypoint_count_(2)
00104 {
00105   last_planning_context_.reset(new LastPlanningContext());
00106   cached_contexts_.reset(new CachedContexts());
00107   registerDefaultPlanners();
00108   registerDefaultStateSpaces();
00109 }
00110 
00111 ompl_interface::PlanningContextManager::~PlanningContextManager()
00112 {
00113 }
00114 
00115 namespace
00116 {
00117 using namespace ompl_interface;
00118 
00119 template<typename T>
00120 static ompl::base::PlannerPtr allocatePlanner(const ob::SpaceInformationPtr &si, const std::string &new_name, const ModelBasedPlanningContextSpecification &spec)
00121 {
00122   ompl::base::PlannerPtr planner(new T(si));
00123   if (!new_name.empty())
00124     planner->setName(new_name);
00125   planner->params().setParams(spec.config_, true);
00126   planner->setup();
00127   return planner;
00128 }
00129 }
00130 
00131 ompl_interface::ConfiguredPlannerAllocator ompl_interface::PlanningContextManager::plannerSelector(const std::string &planner) const
00132 {
00133   std::map<std::string, ConfiguredPlannerAllocator>::const_iterator it = known_planners_.find(planner);
00134   if (it != known_planners_.end())
00135     return it->second;
00136   else
00137   {
00138     logError("Unknown planner: '%s'", planner.c_str());
00139     return ConfiguredPlannerAllocator();
00140   }
00141 }
00142 
00143 void ompl_interface::PlanningContextManager::registerDefaultPlanners()
00144 {
00145   registerPlannerAllocator("geometric::RRT", boost::bind(&allocatePlanner<og::RRT>, _1, _2, _3));
00146   registerPlannerAllocator("geometric::RRTConnect", boost::bind(&allocatePlanner<og::RRTConnect>, _1, _2, _3));
00147   registerPlannerAllocator("geometric::LazyRRT", boost::bind(&allocatePlanner<og::LazyRRT>, _1, _2, _3));
00148   registerPlannerAllocator("geometric::TRRT", boost::bind(&allocatePlanner<og::TRRT>, _1, _2, _3));
00149   registerPlannerAllocator("geometric::EST", boost::bind(&allocatePlanner<og::EST>, _1, _2, _3));
00150   registerPlannerAllocator("geometric::SBL", boost::bind(&allocatePlanner<og::SBL>, _1, _2, _3));
00151   registerPlannerAllocator("geometric::KPIECE", boost::bind(&allocatePlanner<og::KPIECE1>, _1, _2, _3));
00152   registerPlannerAllocator("geometric::BKPIECE", boost::bind(&allocatePlanner<og::BKPIECE1>, _1, _2, _3));
00153   registerPlannerAllocator("geometric::LBKPIECE", boost::bind(&allocatePlanner<og::LBKPIECE1>, _1, _2, _3));
00154   registerPlannerAllocator("geometric::RRTstar", boost::bind(&allocatePlanner<og::RRTstar>, _1, _2, _3));
00155   registerPlannerAllocator("geometric::PRM", boost::bind(&allocatePlanner<og::PRM>, _1, _2, _3));
00156   registerPlannerAllocator("geometric::PRMstar", boost::bind(&allocatePlanner<og::PRMstar>, _1, _2, _3));
00157 }
00158 
00159 void ompl_interface::PlanningContextManager::registerDefaultStateSpaces()
00160 {
00161   registerStateSpaceFactory(ModelBasedStateSpaceFactoryPtr(new JointModelStateSpaceFactory()));
00162   registerStateSpaceFactory(ModelBasedStateSpaceFactoryPtr(new PoseModelStateSpaceFactory()));
00163 }
00164 
00165 ompl_interface::ConfiguredPlannerSelector ompl_interface::PlanningContextManager::getPlannerSelector() const
00166 {
00167   return boost::bind(&PlanningContextManager::plannerSelector, this, _1);
00168 }
00169 
00170 void ompl_interface::PlanningContextManager::setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
00171 {
00172   planner_configs_ = pconfig;
00173 }
00174 
00175 ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getPlanningContext(const std::string &config, const std::string& factory_type) const
00176 {
00177   planning_interface::PlannerConfigurationMap::const_iterator pc = planner_configs_.find(config);
00178 
00179   if (pc != planner_configs_.end())
00180   {
00181     moveit_msgs::MotionPlanRequest req; // dummy request with default values
00182     return getPlanningContext(pc->second, boost::bind(&PlanningContextManager::getStateSpaceFactory1, this, _1, factory_type), req);
00183   }
00184   else
00185   {
00186     logError("Planning configuration '%s' was not found", config.c_str());
00187     return ModelBasedPlanningContextPtr();
00188   }
00189 }
00190 
00191 ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getPlanningContext(const planning_interface::PlannerConfigurationSettings &config,
00192                                                                                                         const StateSpaceFactoryTypeSelector &factory_selector,
00193                                                                                                         const moveit_msgs::MotionPlanRequest &req) const
00194 {
00195   const ompl_interface::ModelBasedStateSpaceFactoryPtr &factory = factory_selector(config.group);
00196 
00197   // Check for a cached planning context
00198   ModelBasedPlanningContextPtr context;
00199 
00200   {
00201     boost::mutex::scoped_lock slock(cached_contexts_->lock_);
00202     std::map<std::pair<std::string, std::string>, std::vector<ModelBasedPlanningContextPtr> >::const_iterator cc =
00203       cached_contexts_->contexts_.find(std::make_pair(config.name, factory->getType()));
00204     if (cc != cached_contexts_->contexts_.end())
00205     {
00206       for (std::size_t i = 0 ; i < cc->second.size() ; ++i)
00207         if (cc->second[i].unique())
00208         {
00209           logDebug("Reusing cached planning context");
00210           context = cc->second[i];
00211           break;
00212         }
00213     }
00214   }
00215 
00216   // Create a new planning context
00217   if (!context)
00218   {
00219     ModelBasedStateSpaceSpecification space_spec(kmodel_, config.group);
00220     ModelBasedPlanningContextSpecification context_spec;
00221     context_spec.config_ = config.config;
00222     context_spec.planner_selector_ = getPlannerSelector();
00223     context_spec.constraint_sampler_manager_ = constraint_sampler_manager_;
00224     context_spec.state_space_ = factory->getNewStateSpace(space_spec);
00225 
00226     // Choose the correct simple setup type to load
00227     context_spec.ompl_simple_setup_.reset(new ompl::geometric::SimpleSetup(context_spec.state_space_));
00228 
00229     bool state_validity_cache = true;
00230     if (config.config.find("subspaces") != config.config.end())
00231     {
00232       context_spec.config_.erase("subspaces");
00233       // if the planner operates at subspace level the cache may be unsafe
00234       state_validity_cache = false;
00235       boost::char_separator<char> sep(" ");
00236       boost::tokenizer<boost::char_separator<char> > tok(config.config.at("subspaces"), sep);
00237       for(boost::tokenizer<boost::char_separator<char> >::iterator beg = tok.begin() ; beg != tok.end(); ++beg)
00238       {
00239         const ompl_interface::ModelBasedStateSpaceFactoryPtr &sub_fact = factory_selector(*beg);
00240         if (sub_fact)
00241         {
00242           ModelBasedStateSpaceSpecification sub_space_spec(kmodel_, *beg);
00243           context_spec.subspaces_.push_back(sub_fact->getNewStateSpace(sub_space_spec));
00244         }
00245       }
00246     }
00247 
00248     logDebug("Creating new planning context");
00249     context.reset(new ModelBasedPlanningContext(config.name, context_spec));
00250     context->useStateValidityCache(state_validity_cache);
00251     {
00252       boost::mutex::scoped_lock slock(cached_contexts_->lock_);
00253       cached_contexts_->contexts_[std::make_pair(config.name, factory->getType())].push_back(context);
00254     }
00255   }
00256 
00257   context->setMaximumPlanningThreads(max_planning_threads_);
00258   context->setMaximumGoalSamples(max_goal_samples_);
00259   context->setMaximumStateSamplingAttempts(max_state_sampling_attempts_);
00260   context->setMaximumGoalSamplingAttempts(max_goal_sampling_attempts_);
00261   if (max_solution_segment_length_ <= std::numeric_limits<double>::epsilon())
00262     context->setMaximumSolutionSegmentLength(context->getOMPLSimpleSetup()->getStateSpace()->getMaximumExtent() / 100.0);
00263   else
00264     context->setMaximumSolutionSegmentLength(max_solution_segment_length_);
00265   context->setMinimumWaypointCount(minimum_waypoint_count_);
00266 
00267   context->setSpecificationConfig(config.config);
00268 
00269   last_planning_context_->setContext(context);
00270   return context;
00271 }
00272 
00273 const ompl_interface::ModelBasedStateSpaceFactoryPtr& ompl_interface::PlanningContextManager::getStateSpaceFactory1(const std::string & /* dummy */, const std::string &factory_type) const
00274 {
00275   std::map<std::string, ModelBasedStateSpaceFactoryPtr>::const_iterator f =
00276     factory_type.empty() ? state_space_factories_.begin() : state_space_factories_.find(factory_type);
00277   if (f != state_space_factories_.end())
00278     return f->second;
00279   else
00280   {
00281     logError("Factory of type '%s' was not found", factory_type.c_str());
00282     static const ModelBasedStateSpaceFactoryPtr empty;
00283     return empty;
00284   }
00285 }
00286 
00287 const ompl_interface::ModelBasedStateSpaceFactoryPtr& ompl_interface::PlanningContextManager::getStateSpaceFactory2(const std::string &group, const moveit_msgs::MotionPlanRequest &req) const
00288 {
00289   // find the problem representation to use
00290   std::map<std::string, ModelBasedStateSpaceFactoryPtr>::const_iterator best = state_space_factories_.end();
00291   int prev_priority = -1;
00292   for (std::map<std::string, ModelBasedStateSpaceFactoryPtr>::const_iterator it = state_space_factories_.begin() ; it != state_space_factories_.end() ; ++it)
00293   {
00294     int priority = it->second->canRepresentProblem(group, req, kmodel_);
00295     if (priority > 0)
00296       if (best == state_space_factories_.end() || priority > prev_priority)
00297       {
00298         best = it;
00299         prev_priority = priority;
00300       }
00301   }
00302 
00303   if (best == state_space_factories_.end())
00304   {
00305     logError("There are no known state spaces that can represent the given planning problem");
00306     static const ModelBasedStateSpaceFactoryPtr empty;
00307     return empty;
00308   }
00309   else
00310   {
00311     logDebug("Using '%s' parameterization for solving problem", best->first.c_str());
00312     return best->second;
00313   }
00314 }
00315 
00316 ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene,
00317                                                                                                         const moveit_msgs::MotionPlanRequest &req,
00318                                                                                                         moveit_msgs::MoveItErrorCodes &error_code) const
00319 {
00320   if (req.group_name.empty())
00321   {
00322     logError("No group specified to plan for");
00323     error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
00324     return ModelBasedPlanningContextPtr();
00325   }
00326 
00327   error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00328 
00329   if (!planning_scene)
00330   {
00331     logError("No planning scene supplied as input");
00332     return ModelBasedPlanningContextPtr();
00333   }
00334 
00335   // identify the correct planning configuration
00336   planning_interface::PlannerConfigurationMap::const_iterator pc = planner_configs_.end();
00337   if (!req.planner_id.empty())
00338   {
00339     pc = planner_configs_.find(req.planner_id.find(req.group_name) == std::string::npos ? req.group_name + "[" + req.planner_id + "]" : req.planner_id);
00340     if (pc == planner_configs_.end())
00341       logWarn("Cannot find planning configuration for group '%s' using planner '%s'. Will use defaults instead.",
00342               req.group_name.c_str(), req.planner_id.c_str());
00343 
00344   }
00345   if (pc == planner_configs_.end())
00346   {
00347     pc = planner_configs_.find(req.group_name);
00348     if (pc == planner_configs_.end())
00349     {
00350       logError("Cannot find planning configuration for group '%s'", req.group_name.c_str());
00351       return ModelBasedPlanningContextPtr();
00352     }
00353   }
00354 
00355   ModelBasedPlanningContextPtr context = getPlanningContext(pc->second, boost::bind(&PlanningContextManager::getStateSpaceFactory2, this, _1, req), req);
00356   if (context)
00357   {
00358     context->clear();
00359 
00360     robot_state::RobotStatePtr start_state = planning_scene->getCurrentStateUpdated(req.start_state);
00361 
00362     // Setup the context
00363     context->setPlanningScene(planning_scene);
00364     context->setMotionPlanRequest(req);
00365     context->setCompleteInitialState(*start_state);
00366 
00367     context->setPlanningVolume(req.workspace_parameters);
00368     if (!context->setPathConstraints(req.path_constraints, &error_code))
00369       return ModelBasedPlanningContextPtr();
00370 
00371     if (!context->setGoalConstraints(req.goal_constraints, req.path_constraints, &error_code))
00372       return ModelBasedPlanningContextPtr();
00373 
00374     try
00375     {
00376       context->configure();
00377       logDebug("%s: New planning context is set.", context->getName().c_str());
00378       error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00379     }
00380     catch (ompl::Exception &ex)
00381     {
00382       logError("OMPL encountered an error: %s", ex.what());
00383       context.reset();
00384     }
00385   }
00386 
00387   return context;
00388 }
00389 
00390 ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getLastPlanningContext() const
00391 {
00392   return last_planning_context_->getContext();
00393 }


ompl
Author(s): Ioan Sucan
autogenerated on Wed Sep 16 2015 04:42:27