planning_context_manager.h
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 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 #ifndef MOVEIT_OMPL_INTERFACE_PLANNING_CONTEXT_MANAGER_
00038 #define MOVEIT_OMPL_INTERFACE_PLANNING_CONTEXT_MANAGER_
00039 
00040 #include <moveit/ompl_interface/model_based_planning_context.h>
00041 #include <moveit/ompl_interface/parameterization/model_based_state_space_factory.h>
00042 #include <moveit/constraint_samplers/constraint_sampler_manager.h>
00043 
00044 #include <boost/shared_ptr.hpp>
00045 #include <vector>
00046 #include <string>
00047 #include <map>
00048 
00049 namespace ompl_interface
00050 {
00051 
00052 class PlanningContextManager
00053 {
00054 public:
00055 
00056   PlanningContextManager(const robot_model::RobotModelConstPtr &kmodel, const constraint_samplers::ConstraintSamplerManagerPtr &csm);
00057   ~PlanningContextManager();
00058 
00061   void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig);
00062 
00064   const planning_interface::PlannerConfigurationMap& getPlannerConfigurations() const
00065   {
00066     return planner_configs_;
00067   }
00068 
00069   /* \brief Get the maximum number of sampling attempts allowed when sampling states is needed */
00070   unsigned int getMaximumStateSamplingAttempts() const
00071   {
00072     return max_state_sampling_attempts_;
00073   }
00074 
00075   /* \brief Set the maximum number of sampling attempts allowed when sampling states is needed */
00076   void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
00077   {
00078     max_state_sampling_attempts_ = max_state_sampling_attempts;
00079   }
00080 
00081   /* \brief Get the maximum number of sampling attempts allowed when sampling goals is needed */
00082   unsigned int getMaximumGoalSamplingAttempts() const
00083   {
00084     return max_goal_sampling_attempts_;
00085   }
00086 
00087   /* \brief Set the maximum number of sampling attempts allowed when sampling goals is needed */
00088   void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
00089   {
00090     max_goal_sampling_attempts_ = max_goal_sampling_attempts;
00091   }
00092 
00093   /* \brief Get the maximum number of goal samples */
00094   unsigned int getMaximumGoalSamples() const
00095   {
00096     return max_goal_samples_;
00097   }
00098 
00099   /* \brief Set the maximum number of goal samples */
00100   void setMaximumGoalSamples(unsigned int max_goal_samples)
00101   {
00102     max_goal_samples_ = max_goal_samples;
00103   }
00104 
00105   /* \brief Get the maximum number of planning threads allowed */
00106   unsigned int getMaximumPlanningThreads() const
00107   {
00108     return max_planning_threads_;
00109   }
00110 
00111   /* \brief Set the maximum number of planning threads */
00112   void setMaximumPlanningThreads(unsigned int max_planning_threads)
00113   {
00114     max_planning_threads_ = max_planning_threads;
00115   }
00116 
00117   /* \brief Get the maximum solution segment length */
00118   double getMaximumSolutionSegmentLength() const
00119   {
00120     return max_solution_segment_length_;
00121   }
00122 
00123   /* \brief Set the maximum solution segment length */
00124   void setMaximumSolutionSegmentLength(double mssl)
00125   {
00126     max_solution_segment_length_ = mssl;
00127   }
00128 
00129   unsigned int getMinimumWaypointCount() const
00130   {
00131     return minimum_waypoint_count_;
00132   }
00133 
00135   void setMinimumWaypointCount(unsigned int mwc)
00136   {
00137     minimum_waypoint_count_ = mwc;
00138   }
00139 
00140   const robot_model::RobotModelConstPtr& getRobotModel() const
00141   {
00142     return kmodel_;
00143   }
00144 
00145   ModelBasedPlanningContextPtr getLastPlanningContext() const;
00146 
00147   ModelBasedPlanningContextPtr getPlanningContext(const std::string &config, const std::string &factory_type = "") const;
00148 
00149   ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene,
00150                                                   const planning_interface::MotionPlanRequest &req,
00151                                                   moveit_msgs::MoveItErrorCodes &error_code) const;
00152 
00153   void registerPlannerAllocator(const std::string &planner_id, const ConfiguredPlannerAllocator &pa)
00154   {
00155     known_planners_[planner_id] = pa;
00156   }
00157 
00158   void registerStateSpaceFactory(const ModelBasedStateSpaceFactoryPtr &factory)
00159   {
00160     state_space_factories_[factory->getType()] = factory;
00161   }
00162 
00163   const std::map<std::string, ConfiguredPlannerAllocator>& getRegisteredPlannerAllocators() const
00164   {
00165     return known_planners_;
00166   }
00167 
00168   const std::map<std::string, ModelBasedStateSpaceFactoryPtr>& getRegisteredStateSpaceFactories() const
00169   {
00170     return state_space_factories_;
00171   }
00172 
00173   ConfiguredPlannerSelector getPlannerSelector() const;
00174 
00175 protected:
00176 
00177   typedef boost::function<const ModelBasedStateSpaceFactoryPtr&(const std::string&)> StateSpaceFactoryTypeSelector;
00178 
00179   ConfiguredPlannerAllocator plannerSelector(const std::string &planner) const;
00180 
00181   void registerDefaultPlanners();
00182   void registerDefaultStateSpaces();
00183 
00184   ModelBasedPlanningContextPtr getPlanningContext(const planning_interface::PlannerConfigurationSettings &config, const StateSpaceFactoryTypeSelector &factory) const;
00185   const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory1(const std::string &group_name, const std::string &factory_type) const;
00186   const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory2(const std::string &group_name, const moveit_msgs::MotionPlanRequest &req) const;
00187 
00189   robot_model::RobotModelConstPtr                       kmodel_;
00190 
00191   constraint_samplers::ConstraintSamplerManagerPtr      constraint_sampler_manager_;
00192 
00193   std::map<std::string, ConfiguredPlannerAllocator>     known_planners_;
00194   std::map<std::string, ModelBasedStateSpaceFactoryPtr> state_space_factories_;
00195 
00201   planning_interface::PlannerConfigurationMap           planner_configs_;
00202 
00204   unsigned int                                          max_goal_samples_;
00205 
00207   unsigned int                                          max_state_sampling_attempts_;
00208 
00210   unsigned int                                          max_goal_sampling_attempts_;
00211 
00213   unsigned int                                          max_planning_threads_;
00214 
00216   double                                                max_solution_segment_length_;
00217 
00219   unsigned int                                          minimum_waypoint_count_;
00220 
00221 private:
00222 
00223   class LastPlanningContext;
00224   boost::shared_ptr<LastPlanningContext>                last_planning_context_;
00225 
00226   struct CachedContexts;
00227   boost::shared_ptr<CachedContexts>                     cached_contexts_;
00228 };
00229 
00230 }
00231 
00232 
00233 #endif


ompl
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 11:12:03