#include <planning_context_manager.h>
Definition at line 79 of file planning_context_manager.h.
◆ PlanningContextManager()
ompl_interface::PlanningContextManager::PlanningContextManager |
( |
moveit::core::RobotModelConstPtr |
robot_model, |
|
|
constraint_samplers::ConstraintSamplerManagerPtr |
csm |
|
) |
| |
◆ ~PlanningContextManager()
ompl_interface::PlanningContextManager::~PlanningContextManager |
( |
| ) |
|
|
default |
◆ getMaximumGoalSamples()
unsigned int ompl_interface::PlanningContextManager::getMaximumGoalSamples |
( |
| ) |
const |
|
inline |
◆ getMaximumGoalSamplingAttempts()
unsigned int ompl_interface::PlanningContextManager::getMaximumGoalSamplingAttempts |
( |
| ) |
const |
|
inline |
◆ getMaximumPlanningThreads()
unsigned int ompl_interface::PlanningContextManager::getMaximumPlanningThreads |
( |
| ) |
const |
|
inline |
◆ getMaximumSolutionSegmentLength()
double ompl_interface::PlanningContextManager::getMaximumSolutionSegmentLength |
( |
| ) |
const |
|
inline |
◆ getMaximumStateSamplingAttempts()
unsigned int ompl_interface::PlanningContextManager::getMaximumStateSamplingAttempts |
( |
| ) |
const |
|
inline |
◆ getMinimumWaypointCount()
unsigned int ompl_interface::PlanningContextManager::getMinimumWaypointCount |
( |
| ) |
const |
|
inline |
◆ getPlannerConfigurations()
◆ getPlannerSelector()
◆ 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.
◆ 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.
◆ getRegisteredPlannerAllocators()
const std::map< std::string, ConfiguredPlannerAllocator > & ompl_interface::PlanningContextManager::getRegisteredPlannerAllocators |
( |
| ) |
const |
|
inline |
◆ getRegisteredStateSpaceFactories()
const std::map< std::string, ModelBasedStateSpaceFactoryPtr > & ompl_interface::PlanningContextManager::getRegisteredStateSpaceFactories |
( |
| ) |
const |
|
inline |
◆ getRobotModel()
const moveit::core::RobotModelConstPtr & ompl_interface::PlanningContextManager::getRobotModel |
( |
| ) |
const |
|
inline |
◆ getStateSpaceFactory() [1/2]
const ModelBasedStateSpaceFactoryPtr & ompl_interface::PlanningContextManager::getStateSpaceFactory |
( |
const std::string & |
factory_type | ) |
const |
|
protected |
◆ getStateSpaceFactory() [2/2]
const ModelBasedStateSpaceFactoryPtr & ompl_interface::PlanningContextManager::getStateSpaceFactory |
( |
const std::string & |
group_name, |
|
|
const moveit_msgs::msg::MotionPlanRequest & |
req |
|
) |
| const |
|
protected |
◆ plannerSelector()
◆ registerDefaultPlanners()
void ompl_interface::PlanningContextManager::registerDefaultPlanners |
( |
| ) |
|
|
protected |
◆ registerDefaultStateSpaces()
void ompl_interface::PlanningContextManager::registerDefaultStateSpaces |
( |
| ) |
|
|
protected |
◆ registerPlannerAllocator()
void ompl_interface::PlanningContextManager::registerPlannerAllocator |
( |
const std::string & |
planner_id, |
|
|
const ConfiguredPlannerAllocator & |
pa |
|
) |
| |
|
inline |
◆ registerPlannerAllocatorHelper()
template<typename T >
void ompl_interface::PlanningContextManager::registerPlannerAllocatorHelper |
( |
const std::string & |
planner_id | ) |
|
|
protected |
◆ registerStateSpaceFactory()
void ompl_interface::PlanningContextManager::registerStateSpaceFactory |
( |
const ModelBasedStateSpaceFactoryPtr & |
factory | ) |
|
|
inline |
◆ setMaximumGoalSamples()
void ompl_interface::PlanningContextManager::setMaximumGoalSamples |
( |
unsigned int |
max_goal_samples | ) |
|
|
inline |
◆ setMaximumGoalSamplingAttempts()
void ompl_interface::PlanningContextManager::setMaximumGoalSamplingAttempts |
( |
unsigned int |
max_goal_sampling_attempts | ) |
|
|
inline |
◆ setMaximumPlanningThreads()
void ompl_interface::PlanningContextManager::setMaximumPlanningThreads |
( |
unsigned int |
max_planning_threads | ) |
|
|
inline |
◆ setMaximumSolutionSegmentLength()
void ompl_interface::PlanningContextManager::setMaximumSolutionSegmentLength |
( |
double |
mssl | ) |
|
|
inline |
◆ setMaximumStateSamplingAttempts()
void ompl_interface::PlanningContextManager::setMaximumStateSamplingAttempts |
( |
unsigned int |
max_state_sampling_attempts | ) |
|
|
inline |
◆ setMinimumWaypointCount()
void ompl_interface::PlanningContextManager::setMinimumWaypointCount |
( |
unsigned int |
mwc | ) |
|
|
inline |
◆ setPlannerConfigurations()
Specify configurations for the planners.
- Parameters
-
pconfig | Configurations for the different planners |
Definition at line 336 of file planning_context_manager.cpp.
◆ constraint_sampler_manager_
constraint_samplers::ConstraintSamplerManagerPtr ompl_interface::PlanningContextManager::constraint_sampler_manager_ |
|
protected |
◆ known_planners_
◆ 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 |
◆ max_planning_threads_
unsigned int ompl_interface::PlanningContextManager::max_planning_threads_ |
|
protected |
◆ 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_
◆ 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.
Definition at line 240 of file planning_context_manager.h.
◆ robot_model_
moveit::core::RobotModelConstPtr ompl_interface::PlanningContextManager::robot_model_ |
|
protected |
◆ state_space_factories_
std::map<std::string, ModelBasedStateSpaceFactoryPtr> ompl_interface::PlanningContextManager::state_space_factories_ |
|
protected |
The documentation for this class was generated from the following files: