37 #ifndef MOVEIT_OMPL_INTERFACE_MODEL_BASED_PLANNING_CONTEXT_ 38 #define MOVEIT_OMPL_INTERFACE_MODEL_BASED_PLANNING_CONTEXT_ 45 #include <ompl/geometric/SimpleSetup.h> 46 #include <ompl/tools/benchmark/Benchmark.h> 47 #include <ompl/tools/multiplan/ParallelPlan.h> 48 #include <ompl/base/StateStorage.h> 50 #include <boost/thread/mutex.hpp> 54 namespace ob = ompl::base;
55 namespace og = ompl::geometric;
56 namespace ot = ompl::tools;
62 typedef boost::function<ob::PlannerPtr(
const ompl::base::SpaceInformationPtr& si,
const std::string& name,
69 std::map<std::string, std::string>
config_;
92 virtual bool terminate();
101 return spec_.config_;
106 spec_.config_ = config;
111 return spec_.state_space_->getRobotModel();
116 return spec_.state_space_->getJointModelGroup();
121 return complete_initial_robot_state_;
126 return spec_.state_space_;
141 return ompl_benchmark_;
146 return ompl_benchmark_;
151 return path_constraints_;
157 return max_state_sampling_attempts_;
163 max_state_sampling_attempts_ = max_state_sampling_attempts;
169 return max_goal_sampling_attempts_;
175 max_goal_sampling_attempts_ = max_goal_sampling_attempts;
181 return max_goal_samples_;
187 max_goal_samples_ = max_goal_samples;
193 return max_planning_threads_;
199 max_planning_threads_ = max_planning_threads;
205 return max_solution_segment_length_;
211 max_solution_segment_length_ = mssl;
216 return minimum_waypoint_count_;
222 minimum_waypoint_count_ = mwc;
227 return spec_.constraint_sampler_manager_;
232 spec_.constraint_sampler_manager_ = csm;
235 void setVerboseStateValidityChecks(
bool flag);
237 void setProjectionEvaluator(
const std::string& peval);
239 void setPlanningVolume(
const moveit_msgs::WorkspaceParameters& wparams);
241 void setCompleteInitialState(
const robot_state::RobotState& complete_initial_robot_state);
243 bool setGoalConstraints(
const std::vector<moveit_msgs::Constraints>& goal_constraints,
244 const moveit_msgs::Constraints& path_constraints, moveit_msgs::MoveItErrorCodes* error);
245 bool setPathConstraints(
const moveit_msgs::Constraints& path_constraints, moveit_msgs::MoveItErrorCodes* error);
249 spec_.constraints_library_ = constraints_library;
254 return use_state_validity_cache_;
259 use_state_validity_cache_ = flag;
264 return simplify_solutions_;
269 simplify_solutions_ = flag;
276 bool solve(
double timeout,
unsigned int count);
284 bool benchmark(
double timeout,
unsigned int count,
const std::string&
filename =
"");
289 return last_plan_time_;
295 return last_simplify_time_;
300 void simplifySolution(
double timeout);
303 void interpolateSolution();
310 virtual void configure();
316 void startSampling();
319 virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(
const std::string& peval)
const;
320 virtual ob::StateSamplerPtr allocPathConstrainedSampler(
const ompl::base::StateSpace* ss)
const;
321 virtual void useConfig();
322 virtual ob::GoalPtr constructGoal();
324 void registerTerminationCondition(
const ob::PlannerTerminationCondition& ptc);
325 void unregisterTerminationCondition();
346 const ob::PlannerTerminationCondition*
ptc_;
double last_simplify_time_
the time spent simplifying the last plan
og::SimpleSetupPtr & getOMPLSimpleSetup()
void setMaximumGoalSamples(unsigned int max_goal_samples)
boost::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
ModelBasedStateSpacePtr state_space_
ot::Benchmark ompl_benchmark_
the OMPL tool for benchmarking planners
bool useStateValidityCache() const
void setConstraintSamplerManager(const constraint_samplers::ConstraintSamplerManagerPtr &csm)
og::SimpleSetupPtr ompl_simple_setup_
double getLastSimplifyTime() const
void setMinimumWaypointCount(unsigned int mwc)
Get the minimum number of waypoints along the solution path.
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
const robot_model::JointModelGroup * getJointModelGroup() const
unsigned int getMaximumGoalSamples() const
unsigned int getMaximumGoalSamplingAttempts() const
const robot_state::RobotState & getCompleteInitialRobotState() const
unsigned int getMinimumWaypointCount() const
The MoveIt! interface to OMPL.
bool use_state_validity_cache_
void useStateValidityCache(bool flag)
void setSpecificationConfig(const std::map< std::string, std::string > &config)
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time ...
MOVEIT_CLASS_FORWARD(ConstraintsLibrary)
unsigned int getMaximumPlanningThreads() const
same_shared_ptr< ModelBasedStateSpace, ompl::base::StateSpacePtr >::type ModelBasedStateSpacePtr
boost::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
double getMaximumSolutionSegmentLength() const
bool simplifySolutions() const
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager()
double last_plan_time_
the time spent computing the last plan
const ob::PlannerTerminationCondition * ptc_
ot::ParallelPlan ompl_parallel_plan_
tool used to compute multiple plans in parallel; this uses the problem definition maintained by ompl_...
const ot::Benchmark & getOMPLBenchmark() const
unsigned int max_goal_samples_
double max_solution_segment_length_
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() const
ot::Benchmark & getOMPLBenchmark()
const std::map< std::string, std::string > & getSpecificationConfig() const
void setMaximumSolutionSegmentLength(double mssl)
ConfiguredPlannerSelector planner_selector_
og::SimpleSetupPtr ompl_simple_setup_
the OMPL planning context; this contains the problem definition and the planner used ...
ModelBasedPlanningContextSpecification spec_
void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
std::vector< int > space_signature_
unsigned int getMaximumStateSamplingAttempts() const
void setMaximumPlanningThreads(unsigned int max_planning_threads)
unsigned int minimum_waypoint_count_
double getLastPlanTime() const
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
std::vector< kinematic_constraints::KinematicConstraintSetPtr > goal_constraints_
unsigned int max_goal_sampling_attempts_
maximum number of attempts to be made at sampling a goal states
unsigned int max_state_sampling_attempts_
virtual ~ModelBasedPlanningContext()
void simplifySolutions(bool flag)
std::map< std::string, std::string > config_
const robot_model::RobotModelConstPtr & getRobotModel() const
void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
std::vector< ModelBasedStateSpacePtr > subspaces_
ConstraintsLibraryConstPtr constraints_library_
const ModelBasedPlanningContextSpecification & getSpecification() const
robot_state::RobotState complete_initial_robot_state_
moveit_msgs::Constraints path_constraints_msg_
void setConstraintsApproximations(const ConstraintsLibraryConstPtr &constraints_library)
const ModelBasedStateSpacePtr & getOMPLStateSpace() const