37 #ifndef MOVEIT_OMPL_INTERFACE_PLANNING_CONTEXT_MANAGER_ 38 #define MOVEIT_OMPL_INTERFACE_PLANNING_CONTEXT_MANAGER_ 55 const constraint_samplers::ConstraintSamplerManagerPtr& csm);
147 const std::string& factory_type =
"")
const;
151 moveit_msgs::MoveItErrorCodes& error_code)
const;
185 const StateSpaceFactoryTypeSelector& factory_selector,
186 const moveit_msgs::MotionPlanRequest& req)
const;
189 const std::string& factory_type)
const;
191 const moveit_msgs::MotionPlanRequest& req)
const;
const robot_model::RobotModelConstPtr & getRobotModel() const
boost::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
void setMaximumPlanningThreads(unsigned int max_planning_threads)
robot_model::RobotModelConstPtr kmodel_
The kinematic model for which motion plans are computed.
ModelBasedPlanningContextPtr getPlanningContext(const std::string &config, const std::string &factory_type="") const
double max_solution_segment_length_
void setMinimumWaypointCount(unsigned int mwc)
Get the minimum number of waypoints along the solution path.
MOVEIT_CLASS_FORWARD(LastPlanningContext)
unsigned int getMaximumGoalSamples() const
const std::map< std::string, ConfiguredPlannerAllocator > & getRegisteredPlannerAllocators() const
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
unsigned int getMaximumStateSamplingAttempts() const
CachedContextsPtr cached_contexts_
The MoveIt! interface to OMPL.
PlanningContextManager(const robot_model::RobotModelConstPtr &kmodel, const constraint_samplers::ConstraintSamplerManagerPtr &csm)
std::map< std::string, ModelBasedStateSpaceFactoryPtr > state_space_factories_
const ModelBasedStateSpaceFactoryPtr & getStateSpaceFactory2(const std::string &group_name, const moveit_msgs::MotionPlanRequest &req) const
void setMaximumSolutionSegmentLength(double mssl)
unsigned int getMaximumGoalSamplingAttempts() const
void registerDefaultStateSpaces()
unsigned int minimum_waypoint_count_
boost::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
unsigned int max_state_sampling_attempts_
void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
unsigned int getMaximumPlanningThreads() const
ConfiguredPlannerSelector getPlannerSelector() const
void registerPlannerAllocator(const std::string &planner_id, const ConfiguredPlannerAllocator &pa)
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
planning_interface::PlannerConfigurationMap planner_configs_
All the existing planning configurations. The name of the configuration is the key of the map...
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time ...
double getMaximumSolutionSegmentLength() const
ConfiguredPlannerAllocator plannerSelector(const std::string &planner) const
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
unsigned int max_goal_sampling_attempts_
maximum number of attempts to be made at sampling goals
moveit_msgs::MotionPlanRequest MotionPlanRequest
void registerDefaultPlanners()
void registerStateSpaceFactory(const ModelBasedStateSpaceFactoryPtr &factory)
void setMaximumGoalSamples(unsigned int max_goal_samples)
const ModelBasedStateSpaceFactoryPtr & getStateSpaceFactory1(const std::string &group_name, const std::string &factory_type) const
unsigned int max_goal_samples_
maximum number of states to sample in the goal region for any planning request (when such sampling is...
ModelBasedPlanningContextPtr getLastPlanningContext() const
LastPlanningContextPtr last_planning_context_
boost::function< const ModelBasedStateSpaceFactoryPtr &(const std::string &)> StateSpaceFactoryTypeSelector
std::map< std::string, ConfiguredPlannerAllocator > known_planners_
unsigned int getMinimumWaypointCount() const
~PlanningContextManager()
void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
const std::map< std::string, ModelBasedStateSpaceFactoryPtr > & getRegisteredStateSpaceFactories() const