Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
ompl_interface::PlanningContextManager Class Reference

#include <planning_context_manager.h>

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::PlannerConfigurationMapgetPlannerConfigurations () const
 Return the previously set planner configurations. More...
 
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. More...
 
void setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pconfig)
 Specify configurations for the planners. More...
 
 ~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_selector, const moveit_msgs::MotionPlanRequest &req) const
 This is the function that constructs new planning contexts if no previous ones exist that are suitable. More...
 
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. More...
 
std::map< std::string, ConfiguredPlannerAllocatorknown_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) More...
 
unsigned int max_goal_sampling_attempts_
 maximum number of attempts to be made at sampling goals More...
 
unsigned int max_planning_threads_
 when planning in parallel, this is the maximum number of threads to use at one time More...
 
double max_solution_segment_length_
 
unsigned int max_state_sampling_attempts_
 
unsigned int minimum_waypoint_count_
 
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. More...
 
std::map< std::string, ModelBasedStateSpaceFactoryPtr > state_space_factories_
 

Private Member Functions

 MOVEIT_CLASS_FORWARD (LastPlanningContext)
 
 MOVEIT_CLASS_FORWARD (CachedContexts)
 

Private Attributes

CachedContextsPtr cached_contexts_
 
LastPlanningContextPtr last_planning_context_
 

Detailed Description

Definition at line 51 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 176 of file planning_context_manager.h.

Constructor & Destructor Documentation

ompl_interface::PlanningContextManager::PlanningContextManager ( const robot_model::RobotModelConstPtr &  kmodel,
const constraint_samplers::ConstraintSamplerManagerPtr &  csm 
)

Definition at line 111 of file planning_context_manager.cpp.

ompl_interface::PlanningContextManager::~PlanningContextManager ( )

Definition at line 128 of file planning_context_manager.cpp.

Member Function Documentation

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

Definition at line 448 of file planning_context_manager.cpp.

unsigned int ompl_interface::PlanningContextManager::getMaximumGoalSamples ( ) const
inline

Definition at line 93 of file planning_context_manager.h.

unsigned int ompl_interface::PlanningContextManager::getMaximumGoalSamplingAttempts ( ) const
inline

Definition at line 81 of file planning_context_manager.h.

unsigned int ompl_interface::PlanningContextManager::getMaximumPlanningThreads ( ) const
inline

Definition at line 105 of file planning_context_manager.h.

double ompl_interface::PlanningContextManager::getMaximumSolutionSegmentLength ( ) const
inline

Definition at line 117 of file planning_context_manager.h.

unsigned int ompl_interface::PlanningContextManager::getMaximumStateSamplingAttempts ( ) const
inline

Definition at line 69 of file planning_context_manager.h.

unsigned int ompl_interface::PlanningContextManager::getMinimumWaypointCount ( ) const
inline

Definition at line 128 of file planning_context_manager.h.

const planning_interface::PlannerConfigurationMap& ompl_interface::PlanningContextManager::getPlannerConfigurations ( ) const
inline

Return the previously set planner configurations.

Definition at line 63 of file planning_context_manager.h.

ompl_interface::ConfiguredPlannerSelector ompl_interface::PlanningContextManager::getPlannerSelector ( ) const

Definition at line 196 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 207 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 353 of file planning_context_manager.cpp.

ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getPlanningContext ( const planning_interface::PlannerConfigurationSettings config,
const StateSpaceFactoryTypeSelector factory_selector,
const moveit_msgs::MotionPlanRequest req 
) const
protected

This is the function that constructs new planning contexts if no previous ones exist that are suitable.

Definition at line 225 of file planning_context_manager.cpp.

const std::map<std::string, ConfiguredPlannerAllocator>& ompl_interface::PlanningContextManager::getRegisteredPlannerAllocators ( ) const
inline

Definition at line 163 of file planning_context_manager.h.

const std::map<std::string, ModelBasedStateSpaceFactoryPtr>& ompl_interface::PlanningContextManager::getRegisteredStateSpaceFactories ( ) const
inline

Definition at line 168 of file planning_context_manager.h.

const robot_model::RobotModelConstPtr& ompl_interface::PlanningContextManager::getRobotModel ( ) const
inline

Definition at line 139 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 305 of file planning_context_manager.cpp.

const ompl_interface::ModelBasedStateSpaceFactoryPtr & ompl_interface::PlanningContextManager::getStateSpaceFactory2 ( const std::string &  group_name,
const moveit_msgs::MotionPlanRequest req 
) const
protected

Definition at line 320 of file planning_context_manager.cpp.

ompl_interface::PlanningContextManager::MOVEIT_CLASS_FORWARD ( LastPlanningContext  )
private
ompl_interface::PlanningContextManager::MOVEIT_CLASS_FORWARD ( CachedContexts  )
private
ompl_interface::ConfiguredPlannerAllocator ompl_interface::PlanningContextManager::plannerSelector ( const std::string &  planner) const
protected

Definition at line 150 of file planning_context_manager.cpp.

void ompl_interface::PlanningContextManager::registerDefaultPlanners ( )
protected

Definition at line 162 of file planning_context_manager.cpp.

void ompl_interface::PlanningContextManager::registerDefaultStateSpaces ( )
protected

Definition at line 190 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.

void ompl_interface::PlanningContextManager::registerStateSpaceFactory ( const ModelBasedStateSpaceFactoryPtr &  factory)
inline

Definition at line 158 of file planning_context_manager.h.

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

Definition at line 99 of file planning_context_manager.h.

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

Definition at line 87 of file planning_context_manager.h.

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

Definition at line 111 of file planning_context_manager.h.

void ompl_interface::PlanningContextManager::setMaximumSolutionSegmentLength ( double  mssl)
inline

Definition at line 123 of file planning_context_manager.h.

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

Definition at line 75 of file planning_context_manager.h.

void ompl_interface::PlanningContextManager::setMinimumWaypointCount ( unsigned int  mwc)
inline

Get the minimum number of waypoints along the solution path.

Definition at line 134 of file planning_context_manager.h.

void ompl_interface::PlanningContextManager::setPlannerConfigurations ( const planning_interface::PlannerConfigurationMap pconfig)

Specify configurations for the planners.

Parameters
pconfigConfigurations for the different planners

Definition at line 201 of file planning_context_manager.cpp.

Member Data Documentation

CachedContextsPtr ompl_interface::PlanningContextManager::cached_contexts_
private

Definition at line 234 of file planning_context_manager.h.

constraint_samplers::ConstraintSamplerManagerPtr ompl_interface::PlanningContextManager::constraint_sampler_manager_
protected

Definition at line 196 of file planning_context_manager.h.

robot_model::RobotModelConstPtr ompl_interface::PlanningContextManager::kmodel_
protected

The kinematic model for which motion plans are computed.

Definition at line 194 of file planning_context_manager.h.

std::map<std::string, ConfiguredPlannerAllocator> ompl_interface::PlanningContextManager::known_planners_
protected

Definition at line 198 of file planning_context_manager.h.

LastPlanningContextPtr ompl_interface::PlanningContextManager::last_planning_context_
private

Definition at line 231 of file planning_context_manager.h.

unsigned int ompl_interface::PlanningContextManager::max_goal_samples_
protected

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

Definition at line 209 of file planning_context_manager.h.

unsigned int ompl_interface::PlanningContextManager::max_goal_sampling_attempts_
protected

maximum number of attempts to be made at sampling goals

Definition at line 216 of file planning_context_manager.h.

unsigned int ompl_interface::PlanningContextManager::max_planning_threads_
protected

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

Definition at line 219 of file planning_context_manager.h.

double ompl_interface::PlanningContextManager::max_solution_segment_length_
protected

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 223 of file planning_context_manager.h.

unsigned int ompl_interface::PlanningContextManager::max_state_sampling_attempts_
protected

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 213 of file planning_context_manager.h.

unsigned int ompl_interface::PlanningContextManager::minimum_waypoint_count_
protected

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

Definition at line 227 of file planning_context_manager.h.

planning_interface::PlannerConfigurationMap ompl_interface::PlanningContextManager::planner_configs_
protected

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 206 of file planning_context_manager.h.

std::map<std::string, ModelBasedStateSpaceFactoryPtr> ompl_interface::PlanningContextManager::state_space_factories_
protected

Definition at line 199 of file planning_context_manager.h.


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


ompl
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:01