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_MODEL_BASED_PLANNING_CONTEXT_
00038 #define MOVEIT_OMPL_INTERFACE_MODEL_BASED_PLANNING_CONTEXT_
00039
00040 #include <moveit/ompl_interface/parameterization/model_based_state_space.h>
00041 #include <moveit/ompl_interface/detail/constrained_valid_state_sampler.h>
00042 #include <moveit/constraint_samplers/constraint_sampler_manager.h>
00043 #include <moveit/planning_interface/planning_interface.h>
00044
00045 #include <ompl/geometric/SimpleSetup.h>
00046 #include <ompl/tools/benchmark/Benchmark.h>
00047 #include <ompl/tools/multiplan/ParallelPlan.h>
00048 #include <ompl/base/StateStorage.h>
00049
00050 #include <boost/thread/mutex.hpp>
00051
00052 namespace ompl_interface
00053 {
00054 namespace ob = ompl::base;
00055 namespace og = ompl::geometric;
00056 namespace ot = ompl::tools;
00057
00058 MOVEIT_CLASS_FORWARD(ModelBasedPlanningContext);
00059 MOVEIT_CLASS_FORWARD(ConstraintsLibrary);
00060
00061 struct ModelBasedPlanningContextSpecification;
00062 typedef boost::function<ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name,
00063 const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator;
00064 typedef boost::function<ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector;
00065
00066 struct ModelBasedPlanningContextSpecification
00067 {
00068 std::map<std::string, std::string> config_;
00069 ConfiguredPlannerSelector planner_selector_;
00070 ConstraintsLibraryConstPtr constraints_library_;
00071 constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
00072
00073 ModelBasedStateSpacePtr state_space_;
00074 std::vector<ModelBasedStateSpacePtr> subspaces_;
00075 };
00076
00077 class ModelBasedPlanningContext : public planning_interface::PlanningContext
00078 {
00079 public:
00080
00081 ModelBasedPlanningContext(const std::string &name, const ModelBasedPlanningContextSpecification &spec);
00082
00083 virtual ~ModelBasedPlanningContext()
00084 {
00085 }
00086
00087 virtual bool solve(planning_interface::MotionPlanResponse &res);
00088 virtual bool solve(planning_interface::MotionPlanDetailedResponse &res);
00089
00090 virtual void clear();
00091 virtual bool terminate();
00092
00093 const ModelBasedPlanningContextSpecification& getSpecification() const
00094 {
00095 return spec_;
00096 }
00097
00098 const std::map<std::string, std::string>& getSpecificationConfig() const
00099 {
00100 return spec_.config_;
00101 }
00102
00103 void setSpecificationConfig(const std::map<std::string, std::string>& config)
00104 {
00105 spec_.config_ = config;
00106 }
00107
00108 const robot_model::RobotModelConstPtr& getRobotModel() const
00109 {
00110 return spec_.state_space_->getRobotModel();
00111 }
00112
00113 const robot_model::JointModelGroup* getJointModelGroup() const
00114 {
00115 return spec_.state_space_->getJointModelGroup();
00116 }
00117
00118 const robot_state::RobotState& getCompleteInitialRobotState() const
00119 {
00120 return complete_initial_robot_state_;
00121 }
00122
00123 const ModelBasedStateSpacePtr& getOMPLStateSpace() const
00124 {
00125 return spec_.state_space_;
00126 }
00127
00128 const og::SimpleSetup& getOMPLSimpleSetup() const
00129 {
00130 return ompl_simple_setup_;
00131 }
00132
00133 og::SimpleSetup& getOMPLSimpleSetup()
00134 {
00135 return ompl_simple_setup_;
00136 }
00137
00138 const ot::Benchmark& getOMPLBenchmark() const
00139 {
00140 return ompl_benchmark_;
00141 }
00142
00143 ot::Benchmark& getOMPLBenchmark()
00144 {
00145 return ompl_benchmark_;
00146 }
00147
00148 const kinematic_constraints::KinematicConstraintSetPtr& getPathConstraints() const
00149 {
00150 return path_constraints_;
00151 }
00152
00153
00154 unsigned int getMaximumStateSamplingAttempts() const
00155 {
00156 return max_state_sampling_attempts_;
00157 }
00158
00159
00160 void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
00161 {
00162 max_state_sampling_attempts_ = max_state_sampling_attempts;
00163 }
00164
00165
00166 unsigned int getMaximumGoalSamplingAttempts() const
00167 {
00168 return max_goal_sampling_attempts_;
00169 }
00170
00171
00172 void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
00173 {
00174 max_goal_sampling_attempts_ = max_goal_sampling_attempts;
00175 }
00176
00177
00178 unsigned int getMaximumGoalSamples() const
00179 {
00180 return max_goal_samples_;
00181 }
00182
00183
00184 void setMaximumGoalSamples(unsigned int max_goal_samples)
00185 {
00186 max_goal_samples_ = max_goal_samples;
00187 }
00188
00189
00190 unsigned int getMaximumPlanningThreads() const
00191 {
00192 return max_planning_threads_;
00193 }
00194
00195
00196 void setMaximumPlanningThreads(unsigned int max_planning_threads)
00197 {
00198 max_planning_threads_ = max_planning_threads;
00199 }
00200
00201
00202 double getMaximumSolutionSegmentLength() const
00203 {
00204 return max_solution_segment_length_;
00205 }
00206
00207
00208 void setMaximumSolutionSegmentLength(double mssl)
00209 {
00210 max_solution_segment_length_ = mssl;
00211 }
00212
00213 unsigned int getMinimumWaypointCount() const
00214 {
00215 return minimum_waypoint_count_;
00216 }
00217
00219 void setMinimumWaypointCount(unsigned int mwc)
00220 {
00221 minimum_waypoint_count_ = mwc;
00222 }
00223
00224 const constraint_samplers::ConstraintSamplerManagerPtr& getConstraintSamplerManager()
00225 {
00226 return spec_.constraint_sampler_manager_;
00227 }
00228
00229 void setConstraintSamplerManager(const constraint_samplers::ConstraintSamplerManagerPtr &csm)
00230 {
00231 spec_.constraint_sampler_manager_ = csm;
00232 }
00233
00234 void setVerboseStateValidityChecks(bool flag);
00235
00236 void setProjectionEvaluator(const std::string &peval);
00237
00238 void setPlanningVolume(const moveit_msgs::WorkspaceParameters &wparams);
00239
00240 void setCompleteInitialState(const robot_state::RobotState &complete_initial_robot_state);
00241
00242 bool setGoalConstraints(const std::vector<moveit_msgs::Constraints> &goal_constraints,
00243 const moveit_msgs::Constraints &path_constraints,
00244 moveit_msgs::MoveItErrorCodes *error);
00245 bool setPathConstraints(const moveit_msgs::Constraints &path_constraints,
00246 moveit_msgs::MoveItErrorCodes *error);
00247
00248 void setConstraintsApproximations(const ConstraintsLibraryConstPtr &constraints_library)
00249 {
00250 spec_.constraints_library_ = constraints_library;
00251 }
00252
00253 bool useStateValidityCache() const
00254 {
00255 return use_state_validity_cache_;
00256 }
00257
00258 void useStateValidityCache(bool flag)
00259 {
00260 use_state_validity_cache_ = flag;
00261 }
00262
00263 bool simplifySolutions() const
00264 {
00265 return simplify_solutions_;
00266 }
00267
00268 void simplifySolutions(bool flag)
00269 {
00270 simplify_solutions_ = flag;
00271 }
00272
00273
00274
00275
00276
00277 bool solve(double timeout, unsigned int count);
00278
00279
00280
00281
00282
00283
00284 bool benchmark(double timeout, unsigned int count, const std::string &filename = "");
00285
00286
00287 double getLastPlanTime() const
00288 {
00289 return last_plan_time_;
00290 }
00291
00292
00293 double getLastSimplifyTime() const
00294 {
00295 return last_simplify_time_;
00296 }
00297
00298
00299
00300 void simplifySolution(double timeout);
00301
00302
00303 void interpolateSolution();
00304
00305
00306 bool getSolutionPath(robot_trajectory::RobotTrajectory &traj) const;
00307
00308 void convertPath(const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const;
00309
00310 virtual void configure();
00311
00312 protected:
00313
00314 void preSolve();
00315 void postSolve();
00316
00317 virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string &peval) const;
00318 virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace *ss) const;
00319 virtual void useConfig();
00320 virtual ob::GoalPtr constructGoal();
00321
00322 void registerTerminationCondition(const ob::PlannerTerminationCondition &ptc);
00323 void unregisterTerminationCondition();
00324
00325 ModelBasedPlanningContextSpecification spec_;
00326
00327 robot_state::RobotState complete_initial_robot_state_;
00328
00330 og::SimpleSetup ompl_simple_setup_;
00331
00333 ot::Benchmark ompl_benchmark_;
00334
00336 ot::ParallelPlan ompl_parallel_plan_;
00337
00338 std::vector<int> space_signature_;
00339
00340 kinematic_constraints::KinematicConstraintSetPtr path_constraints_;
00341 moveit_msgs::Constraints path_constraints_msg_;
00342 std::vector<kinematic_constraints::KinematicConstraintSetPtr> goal_constraints_;
00343
00344 const ob::PlannerTerminationCondition *ptc_;
00345 boost::mutex ptc_lock_;
00346
00348 double last_plan_time_;
00349
00351 double last_simplify_time_;
00352
00354 unsigned int max_goal_samples_;
00355
00357 unsigned int max_state_sampling_attempts_;
00358
00360 unsigned int max_goal_sampling_attempts_;
00361
00363 unsigned int max_planning_threads_;
00364
00366 double max_solution_segment_length_;
00367
00369 unsigned int minimum_waypoint_count_;
00370
00371 bool use_state_validity_cache_;
00372
00373 bool simplify_solutions_;
00374 };
00375
00376 }
00377
00378 #endif