moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ompl_interface::PlanningContextManager Class Reference

#include <planning_context_manager.h>

Collaboration diagram for ompl_interface::PlanningContextManager:
Collaboration graph
[legend]

Classes

struct  CachedContexts
 

Public Member Functions

 PlanningContextManager (moveit::core::RobotModelConstPtr robot_model, constraint_samplers::ConstraintSamplerManagerPtr csm)
 
 ~PlanningContextManager ()
 
void setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pconfig)
 Specify configurations for the planners. More...
 
const planning_interface::PlannerConfigurationMapgetPlannerConfigurations () const
 Return the previously set planner configurations. More...
 
unsigned int getMaximumStateSamplingAttempts () const
 
void setMaximumStateSamplingAttempts (unsigned int max_state_sampling_attempts)
 
unsigned int getMaximumGoalSamplingAttempts () const
 
void setMaximumGoalSamplingAttempts (unsigned int max_goal_sampling_attempts)
 
unsigned int getMaximumGoalSamples () const
 
void setMaximumGoalSamples (unsigned int max_goal_samples)
 
unsigned int getMaximumPlanningThreads () const
 
void setMaximumPlanningThreads (unsigned int max_planning_threads)
 
double getMaximumSolutionSegmentLength () const
 
void setMaximumSolutionSegmentLength (double mssl)
 
unsigned int getMinimumWaypointCount () const
 
void setMinimumWaypointCount (unsigned int mwc)
 Get the minimum number of waypoints along the solution path. More...
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
ModelBasedPlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code, const rclcpp::Node::SharedPtr &node, bool use_constraints_approximations) const
 Returns a planning context to OMPLInterface, which in turn passes it to OMPLPlannerManager. More...
 
void registerPlannerAllocator (const std::string &planner_id, const ConfiguredPlannerAllocator &pa)
 
void registerStateSpaceFactory (const ModelBasedStateSpaceFactoryPtr &factory)
 
const std::map< std::string, ConfiguredPlannerAllocator > & getRegisteredPlannerAllocators () const
 
const std::map< std::string, ModelBasedStateSpaceFactoryPtr > & getRegisteredStateSpaceFactories () const
 
ConfiguredPlannerSelector getPlannerSelector () const
 

Protected Member Functions

ConfiguredPlannerAllocator plannerSelector (const std::string &planner) const
 
void registerDefaultPlanners ()
 
void registerDefaultStateSpaces ()
 
template<typename T >
void registerPlannerAllocatorHelper (const std::string &planner_id)
 
ModelBasedPlanningContextPtr getPlanningContext (const planning_interface::PlannerConfigurationSettings &config, const ModelBasedStateSpaceFactoryPtr &factory, const moveit_msgs::msg::MotionPlanRequest &req) const
 This is the function that constructs new planning contexts if no previous ones exist that are suitable. More...
 
const ModelBasedStateSpaceFactoryPtr & getStateSpaceFactory (const std::string &factory_type) const
 
const ModelBasedStateSpaceFactoryPtr & getStateSpaceFactory (const std::string &group_name, const moveit_msgs::msg::MotionPlanRequest &req) const
 

Protected Attributes

moveit::core::RobotModelConstPtr robot_model_
 The kinematic model for which motion plans are computed. More...
 
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
 
std::map< std::string, ConfiguredPlannerAllocatorknown_planners_
 
std::map< std::string, ModelBasedStateSpaceFactoryPtr > state_space_factories_
 
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...
 
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_state_sampling_attempts_
 
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 minimum_waypoint_count_
 
MultiQueryPlannerAllocator planner_allocator_
 Multi-query planner allocator. More...
 

Detailed Description

Definition at line 79 of file planning_context_manager.h.

Constructor & Destructor Documentation

◆ PlanningContextManager()

ompl_interface::PlanningContextManager::PlanningContextManager ( moveit::core::RobotModelConstPtr  robot_model,
constraint_samplers::ConstraintSamplerManagerPtr  csm 
)

Definition at line 254 of file planning_context_manager.cpp.

Here is the call graph for this function:

◆ ~PlanningContextManager()

ompl_interface::PlanningContextManager::~PlanningContextManager ( )
default

Member Function Documentation

◆ getMaximumGoalSamples()

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

Definition at line 121 of file planning_context_manager.h.

◆ getMaximumGoalSamplingAttempts()

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

Definition at line 109 of file planning_context_manager.h.

◆ getMaximumPlanningThreads()

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

Definition at line 133 of file planning_context_manager.h.

◆ getMaximumSolutionSegmentLength()

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

Definition at line 145 of file planning_context_manager.h.

◆ getMaximumStateSamplingAttempts()

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

Definition at line 97 of file planning_context_manager.h.

◆ getMinimumWaypointCount()

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

Definition at line 156 of file planning_context_manager.h.

◆ getPlannerConfigurations()

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

Return the previously set planner configurations.

Definition at line 91 of file planning_context_manager.h.

Here is the caller graph for this function:

◆ getPlannerSelector()

ConfiguredPlannerSelector ompl_interface::PlanningContextManager::getPlannerSelector ( ) const

Definition at line 331 of file planning_context_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPlanningContext() [1/2]

ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getPlanningContext ( const planning_interface::PlannerConfigurationSettings config,
const ModelBasedStateSpaceFactoryPtr &  factory,
const moveit_msgs::msg::MotionPlanRequest &  req 
) const
protected

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

Definition at line 342 of file planning_context_manager.cpp.

Here is the call graph for this function:

◆ getPlanningContext() [2/2]

ModelBasedPlanningContextPtr ompl_interface::PlanningContextManager::getPlanningContext ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const rclcpp::Node::SharedPtr &  node,
bool  use_constraints_approximations 
) const

Returns a planning context to OMPLInterface, which in turn passes it to OMPLPlannerManager.

This function checks the input and reads planner specific configurations. Then it creates the planning context with PlanningContextManager::createPlanningContext. Finally, it puts the context into a state appropriate for planning. This last step involves setting the start, goal, and state validity checker using the method ModelBasedPlanningContext::configure.

Definition at line 484 of file planning_context_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getRegisteredPlannerAllocators()

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

Definition at line 197 of file planning_context_manager.h.

◆ getRegisteredStateSpaceFactories()

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

Definition at line 202 of file planning_context_manager.h.

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& ompl_interface::PlanningContextManager::getRobotModel ( ) const
inline

Definition at line 167 of file planning_context_manager.h.

◆ getStateSpaceFactory() [1/2]

const ModelBasedStateSpaceFactoryPtr & ompl_interface::PlanningContextManager::getStateSpaceFactory ( const std::string &  factory_type) const
protected

Definition at line 437 of file planning_context_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getStateSpaceFactory() [2/2]

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

Definition at line 454 of file planning_context_manager.cpp.

Here is the call graph for this function:

◆ plannerSelector()

ConfiguredPlannerAllocator ompl_interface::PlanningContextManager::plannerSelector ( const std::string &  planner) const
protected

Definition at line 272 of file planning_context_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ registerDefaultPlanners()

void ompl_interface::PlanningContextManager::registerDefaultPlanners ( )
protected

Definition at line 295 of file planning_context_manager.cpp.

Here is the caller graph for this function:

◆ registerDefaultStateSpaces()

void ompl_interface::PlanningContextManager::registerDefaultStateSpaces ( )
protected

Definition at line 324 of file planning_context_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ registerPlannerAllocator()

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

Definition at line 187 of file planning_context_manager.h.

Here is the caller graph for this function:

◆ registerPlannerAllocatorHelper()

template<typename T >
void ompl_interface::PlanningContextManager::registerPlannerAllocatorHelper ( const std::string &  planner_id)
protected

Definition at line 287 of file planning_context_manager.cpp.

Here is the call graph for this function:

◆ registerStateSpaceFactory()

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

Definition at line 192 of file planning_context_manager.h.

Here is the caller graph for this function:

◆ setMaximumGoalSamples()

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

Definition at line 127 of file planning_context_manager.h.

◆ setMaximumGoalSamplingAttempts()

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

Definition at line 115 of file planning_context_manager.h.

◆ setMaximumPlanningThreads()

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

Definition at line 139 of file planning_context_manager.h.

◆ setMaximumSolutionSegmentLength()

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

Definition at line 151 of file planning_context_manager.h.

◆ setMaximumStateSamplingAttempts()

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

Definition at line 103 of file planning_context_manager.h.

◆ setMinimumWaypointCount()

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

Get the minimum number of waypoints along the solution path.

Definition at line 162 of file planning_context_manager.h.

◆ setPlannerConfigurations()

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

Specify configurations for the planners.

Parameters
pconfigConfigurations for the different planners

Definition at line 336 of file planning_context_manager.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ constraint_sampler_manager_

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

Definition at line 230 of file planning_context_manager.h.

◆ known_planners_

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

Definition at line 232 of file planning_context_manager.h.

◆ max_goal_samples_

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

◆ max_goal_sampling_attempts_

unsigned int ompl_interface::PlanningContextManager::max_goal_sampling_attempts_
protected

maximum number of attempts to be made at sampling goals

Definition at line 250 of file planning_context_manager.h.

◆ max_planning_threads_

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

◆ max_solution_segment_length_

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

◆ max_state_sampling_attempts_

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

◆ minimum_waypoint_count_

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

◆ planner_allocator_

MultiQueryPlannerAllocator ompl_interface::PlanningContextManager::planner_allocator_
protected

Multi-query planner allocator.

Definition at line 264 of file planning_context_manager.h.

◆ planner_configs_

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

◆ robot_model_

moveit::core::RobotModelConstPtr ompl_interface::PlanningContextManager::robot_model_
protected

The kinematic model for which motion plans are computed.

Definition at line 228 of file planning_context_manager.h.

◆ state_space_factories_

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

Definition at line 233 of file planning_context_manager.h.


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