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
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
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, 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
00185 ModelBasedPlanningContextPtr getPlanningContext(const planning_interface::PlannerConfigurationSettings &config, const StateSpaceFactoryTypeSelector &factory_selector, const moveit_msgs::MotionPlanRequest &req) const;
00186
00187 const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory1(const std::string &group_name, const std::string &factory_type) const;
00188 const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory2(const std::string &group_name, const moveit_msgs::MotionPlanRequest &req) const;
00189
00191 robot_model::RobotModelConstPtr kmodel_;
00192
00193 constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
00194
00195 std::map<std::string, ConfiguredPlannerAllocator> known_planners_;
00196 std::map<std::string, ModelBasedStateSpaceFactoryPtr> state_space_factories_;
00197
00203 planning_interface::PlannerConfigurationMap planner_configs_;
00204
00206 unsigned int max_goal_samples_;
00207
00209 unsigned int max_state_sampling_attempts_;
00210
00212 unsigned int max_goal_sampling_attempts_;
00213
00215 unsigned int max_planning_threads_;
00216
00218 double max_solution_segment_length_;
00219
00221 unsigned int minimum_waypoint_count_;
00222
00223 private:
00224
00225 class LastPlanningContext;
00226 boost::shared_ptr<LastPlanningContext> last_planning_context_;
00227
00228 struct CachedContexts;
00229 boost::shared_ptr<CachedContexts> cached_contexts_;
00230 };
00231
00232 }
00233
00234
00235 #endif