Go to the documentation of this file.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 #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 #include <moveit/macros/class_forward.h>
00044
00045 #include <boost/shared_ptr.hpp>
00046 #include <vector>
00047 #include <string>
00048 #include <map>
00049
00050 namespace ompl_interface
00051 {
00052 class PlanningContextManager
00053 {
00054 public:
00055 PlanningContextManager(const robot_model::RobotModelConstPtr& kmodel,
00056 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
00070 unsigned int getMaximumStateSamplingAttempts() const
00071 {
00072 return max_state_sampling_attempts_;
00073 }
00074
00075
00076 void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
00077 {
00078 max_state_sampling_attempts_ = max_state_sampling_attempts;
00079 }
00080
00081
00082 unsigned int getMaximumGoalSamplingAttempts() const
00083 {
00084 return max_goal_sampling_attempts_;
00085 }
00086
00087
00088 void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
00089 {
00090 max_goal_sampling_attempts_ = max_goal_sampling_attempts;
00091 }
00092
00093
00094 unsigned int getMaximumGoalSamples() const
00095 {
00096 return max_goal_samples_;
00097 }
00098
00099
00100 void setMaximumGoalSamples(unsigned int max_goal_samples)
00101 {
00102 max_goal_samples_ = max_goal_samples;
00103 }
00104
00105
00106 unsigned int getMaximumPlanningThreads() const
00107 {
00108 return max_planning_threads_;
00109 }
00110
00111
00112 void setMaximumPlanningThreads(unsigned int max_planning_threads)
00113 {
00114 max_planning_threads_ = max_planning_threads;
00115 }
00116
00117
00118 double getMaximumSolutionSegmentLength() const
00119 {
00120 return max_solution_segment_length_;
00121 }
00122
00123
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,
00148 const std::string& factory_type = "") const;
00149
00150 ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
00151 const planning_interface::MotionPlanRequest& req,
00152 moveit_msgs::MoveItErrorCodes& error_code) const;
00153
00154 void registerPlannerAllocator(const std::string& planner_id, const ConfiguredPlannerAllocator& pa)
00155 {
00156 known_planners_[planner_id] = pa;
00157 }
00158
00159 void registerStateSpaceFactory(const ModelBasedStateSpaceFactoryPtr& factory)
00160 {
00161 state_space_factories_[factory->getType()] = factory;
00162 }
00163
00164 const std::map<std::string, ConfiguredPlannerAllocator>& getRegisteredPlannerAllocators() const
00165 {
00166 return known_planners_;
00167 }
00168
00169 const std::map<std::string, ModelBasedStateSpaceFactoryPtr>& getRegisteredStateSpaceFactories() const
00170 {
00171 return state_space_factories_;
00172 }
00173
00174 ConfiguredPlannerSelector getPlannerSelector() const;
00175
00176 protected:
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
00185 ModelBasedPlanningContextPtr getPlanningContext(const planning_interface::PlannerConfigurationSettings& config,
00186 const StateSpaceFactoryTypeSelector& factory_selector,
00187 const moveit_msgs::MotionPlanRequest& req) const;
00188
00189 const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory1(const std::string& group_name,
00190 const std::string& factory_type) const;
00191 const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory2(const std::string& group_name,
00192 const moveit_msgs::MotionPlanRequest& req) const;
00193
00195 robot_model::RobotModelConstPtr kmodel_;
00196
00197 constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
00198
00199 std::map<std::string, ConfiguredPlannerAllocator> known_planners_;
00200 std::map<std::string, ModelBasedStateSpaceFactoryPtr> state_space_factories_;
00201
00207 planning_interface::PlannerConfigurationMap planner_configs_;
00208
00210 unsigned int max_goal_samples_;
00211
00214 unsigned int max_state_sampling_attempts_;
00215
00217 unsigned int max_goal_sampling_attempts_;
00218
00220 unsigned int max_planning_threads_;
00221
00224 double max_solution_segment_length_;
00225
00228 unsigned int minimum_waypoint_count_;
00229
00230 private:
00231 MOVEIT_CLASS_FORWARD(LastPlanningContext);
00232 LastPlanningContextPtr last_planning_context_;
00233
00234 MOVEIT_CLASS_FORWARD(CachedContexts);
00235 CachedContextsPtr cached_contexts_;
00236 };
00237 }
00238
00239 #endif