Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Private Attributes
ompl_interface::PlanningContextManager Class Reference

#include <planning_context_manager.h>

List of all members.

Classes

struct  CachedContexts
class  LastPlanningContext

Public Member Functions

ModelBasedPlanningContextPtr getLastPlanningContext () const
unsigned int getMaximumGoalSamples () const
unsigned int getMaximumGoalSamplingAttempts () const
unsigned int getMaximumPlanningThreads () const
double getMaximumSolutionSegmentLength () const
unsigned int getMaximumStateSamplingAttempts () const
unsigned int getMinimumWaypointCount () const
const
planning_interface::PlannerConfigurationMap
getPlannerConfigurations () const
 Return the previously set planner configurations.
ConfiguredPlannerSelector getPlannerSelector () const
ModelBasedPlanningContextPtr getPlanningContext (const std::string &config, const std::string &factory_type="") const
ModelBasedPlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const
const std::map< std::string,
ConfiguredPlannerAllocator > & 
getRegisteredPlannerAllocators () const
const std::map< std::string,
ModelBasedStateSpaceFactoryPtr > & 
getRegisteredStateSpaceFactories () const
const
robot_model::RobotModelConstPtr
getRobotModel () const
 PlanningContextManager (const robot_model::RobotModelConstPtr &kmodel, const constraint_samplers::ConstraintSamplerManagerPtr &csm)
void registerPlannerAllocator (const std::string &planner_id, const ConfiguredPlannerAllocator &pa)
void registerStateSpaceFactory (const ModelBasedStateSpaceFactoryPtr &factory)
void setMaximumGoalSamples (unsigned int max_goal_samples)
void setMaximumGoalSamplingAttempts (unsigned int max_goal_sampling_attempts)
void setMaximumPlanningThreads (unsigned int max_planning_threads)
void setMaximumSolutionSegmentLength (double mssl)
void setMaximumStateSamplingAttempts (unsigned int max_state_sampling_attempts)
void setMinimumWaypointCount (unsigned int mwc)
 Get the minimum number of waypoints along the solution path.
void setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pconfig)
 Specify configurations for the planners.
 ~PlanningContextManager ()

Protected Types

typedef boost::function< const
ModelBasedStateSpaceFactoryPtr
&(const std::string &)> 
StateSpaceFactoryTypeSelector

Protected Member Functions

ModelBasedPlanningContextPtr getPlanningContext (const planning_interface::PlannerConfigurationSettings &config, const StateSpaceFactoryTypeSelector &factory) const
const
ModelBasedStateSpaceFactoryPtr
getStateSpaceFactory1 (const std::string &group_name, const std::string &factory_type) const
const
ModelBasedStateSpaceFactoryPtr
getStateSpaceFactory2 (const std::string &group_name, const moveit_msgs::MotionPlanRequest &req) const
ConfiguredPlannerAllocator plannerSelector (const std::string &planner) const
void registerDefaultPlanners ()
void registerDefaultStateSpaces ()

Protected Attributes

constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
robot_model::RobotModelConstPtr kmodel_
 The kinematic model for which motion plans are computed.
std::map< std::string,
ConfiguredPlannerAllocator
known_planners_
unsigned int max_goal_samples_
 maximum number of states to sample in the goal region for any planning request (when such sampling is possible)
unsigned int max_goal_sampling_attempts_
 maximum number of attempts to be made at sampling goals
unsigned int max_planning_threads_
 when planning in parallel, this is the maximum number of threads to use at one time
double max_solution_segment_length_
 the maximum length that is allowed for segments that make up the motion plan; by default this is 1% from the extent of the space
unsigned int max_state_sampling_attempts_
 maximum number of attempts to be made at sampling a state when attempting to find valid states that satisfy some set of constraints
unsigned int minimum_waypoint_count_
 the minimum number of points to include on the solution path (interpolation is used to reach this number, if needed)
planning_interface::PlannerConfigurationMap planner_configs_
 All the existing planning configurations. The name of the configuration is the key of the map. This name can be of the form "group_name[config_name]" if there are particular configurations specified for a group, or of the form "group_name" if default settings are to be used.
std::map< std::string,
ModelBasedStateSpaceFactoryPtr
state_space_factories_

Private Attributes

boost::shared_ptr< CachedContextscached_contexts_
boost::shared_ptr
< LastPlanningContext
last_planning_context_

Detailed Description

Definition at line 52 of file planning_context_manager.h.


Member Typedef Documentation

typedef boost::function<const ModelBasedStateSpaceFactoryPtr&(const std::string&)> ompl_interface::PlanningContextManager::StateSpaceFactoryTypeSelector [protected]

Definition at line 177 of file planning_context_manager.h.


Constructor & Destructor Documentation

Definition at line 100 of file planning_context_manager.cpp.

Definition at line 111 of file planning_context_manager.cpp.


Member Function Documentation

ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getLastPlanningContext ( ) const

Definition at line 386 of file planning_context_manager.cpp.

Definition at line 94 of file planning_context_manager.h.

Definition at line 82 of file planning_context_manager.h.

Definition at line 106 of file planning_context_manager.h.

Definition at line 118 of file planning_context_manager.h.

Definition at line 70 of file planning_context_manager.h.

Definition at line 129 of file planning_context_manager.h.

Return the previously set planner configurations.

Definition at line 64 of file planning_context_manager.h.

Definition at line 165 of file planning_context_manager.cpp.

ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getPlanningContext ( const std::string &  config,
const std::string &  factory_type = "" 
) const

Definition at line 175 of file planning_context_manager.cpp.

ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getPlanningContext ( const planning_scene::PlanningSceneConstPtr planning_scene,
const planning_interface::MotionPlanRequest req,
moveit_msgs::MoveItErrorCodes &  error_code 
) const

Definition at line 310 of file planning_context_manager.cpp.

ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getPlanningContext ( const planning_interface::PlannerConfigurationSettings config,
const StateSpaceFactoryTypeSelector factory 
) const [protected]

Definition at line 190 of file planning_context_manager.cpp.

Definition at line 163 of file planning_context_manager.h.

Definition at line 168 of file planning_context_manager.h.

Definition at line 140 of file planning_context_manager.h.

const ompl_interface::ModelBasedStateSpaceFactoryPtr & ompl_interface::PlanningContextManager::getStateSpaceFactory1 ( const std::string &  group_name,
const std::string &  factory_type 
) const [protected]

Definition at line 267 of file planning_context_manager.cpp.

Definition at line 281 of file planning_context_manager.cpp.

Definition at line 131 of file planning_context_manager.cpp.

Definition at line 143 of file planning_context_manager.cpp.

Definition at line 159 of file planning_context_manager.cpp.

void ompl_interface::PlanningContextManager::registerPlannerAllocator ( const std::string &  planner_id,
const ConfiguredPlannerAllocator pa 
) [inline]

Definition at line 153 of file planning_context_manager.h.

Definition at line 158 of file planning_context_manager.h.

void ompl_interface::PlanningContextManager::setMaximumGoalSamples ( unsigned int  max_goal_samples) [inline]

Definition at line 100 of file planning_context_manager.h.

void ompl_interface::PlanningContextManager::setMaximumGoalSamplingAttempts ( unsigned int  max_goal_sampling_attempts) [inline]

Definition at line 88 of file planning_context_manager.h.

void ompl_interface::PlanningContextManager::setMaximumPlanningThreads ( unsigned int  max_planning_threads) [inline]

Definition at line 112 of file planning_context_manager.h.

Definition at line 124 of file planning_context_manager.h.

void ompl_interface::PlanningContextManager::setMaximumStateSamplingAttempts ( unsigned int  max_state_sampling_attempts) [inline]

Definition at line 76 of file planning_context_manager.h.

Get the minimum number of waypoints along the solution path.

Definition at line 135 of file planning_context_manager.h.

Specify configurations for the planners.

Parameters:
pconfigConfigurations for the different planners

Definition at line 170 of file planning_context_manager.cpp.


Member Data Documentation

Definition at line 226 of file planning_context_manager.h.

Definition at line 191 of file planning_context_manager.h.

The kinematic model for which motion plans are computed.

Definition at line 189 of file planning_context_manager.h.

Definition at line 193 of file planning_context_manager.h.

Definition at line 223 of file planning_context_manager.h.

maximum number of states to sample in the goal region for any planning request (when such sampling is possible)

Definition at line 204 of file planning_context_manager.h.

maximum number of attempts to be made at sampling goals

Definition at line 210 of file planning_context_manager.h.

when planning in parallel, this is the maximum number of threads to use at one time

Definition at line 213 of file planning_context_manager.h.

the maximum length that is allowed for segments that make up the motion plan; by default this is 1% from the extent of the space

Definition at line 216 of file planning_context_manager.h.

maximum number of attempts to be made at sampling a state when attempting to find valid states that satisfy some set of constraints

Definition at line 207 of file planning_context_manager.h.

the minimum number of points to include on the solution path (interpolation is used to reach this number, if needed)

Definition at line 219 of file planning_context_manager.h.

All the existing planning configurations. The name of the configuration is the key of the map. This name can be of the form "group_name[config_name]" if there are particular configurations specified for a group, or of the form "group_name" if default settings are to be used.

Definition at line 201 of file planning_context_manager.h.

Definition at line 194 of file planning_context_manager.h.


The documentation for this class was generated from the following files:


ompl
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 11:12:04