Go to the documentation of this file.
44 #include <ompl/base/PlannerDataStorage.h>
51 class MultiQueryPlannerAllocator
58 ob::PlannerPtr
allocatePlanner(
const ob::SpaceInformationPtr& si,
const std::string& new_name,
59 const ModelBasedPlanningContextSpecification& spec);
63 ob::PlannerPtr
allocatePlannerImpl(
const ob::SpaceInformationPtr& si,
const std::string& new_name,
64 const ModelBasedPlanningContextSpecification& spec,
bool load_planner_data =
false,
65 bool store_planner_data =
false,
const std::string& file_path =
"");
71 std::map<std::string, ob::PlannerPtr>
planners_;
79 class PlanningContextManager
83 constraint_samplers::ConstraintSamplerManagerPtr csm);
167 const moveit::core::RobotModelConstPtr&
getRobotModel()
const
184 bool use_constraints_approximations)
const;
214 template <
typename T>
219 const ModelBasedStateSpaceFactoryPtr& factory)
const;
221 const ModelBasedStateSpaceFactoryPtr&
getStateSpaceFactory(
const std::string& factory_type)
const;
223 const moveit_msgs::MotionPlanRequest& req)
const;
void setMaximumSolutionSegmentLength(double mssl)
const std::map< std::string, ModelBasedStateSpaceFactoryPtr > & getRegisteredStateSpaceFactories() const
std::map< std::string, ob::PlannerPtr > planners_
unsigned int getMinimumWaypointCount() const
~MultiQueryPlannerAllocator()
const ModelBasedStateSpaceFactoryPtr & getStateSpaceFactory(const std::string &factory_type) const
std::map< std::string, ModelBasedStateSpaceFactoryPtr > state_space_factories_
const std::map< std::string, ConfiguredPlannerAllocator > & getRegisteredPlannerAllocators() const
void registerDefaultStateSpaces()
void setMaximumPlanningThreads(unsigned int max_planning_threads)
unsigned int max_goal_sampling_attempts_
maximum number of attempts to be made at sampling goals
ob::Planner * allocatePersistentPlanner(const ob::PlannerData &data)
moveit::core::RobotModelConstPtr robot_model_
The kinematic model for which motion plans are computed.
void registerPlannerAllocator(const std::string &planner_id, const ConfiguredPlannerAllocator &pa)
The MoveIt interface to OMPL.
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
planning_interface::PlannerConfigurationMap planner_configs_
All the existing planning configurations. The name of the configuration is the key of the map....
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
double getMaximumSolutionSegmentLength() const
CachedContextsPtr cached_contexts_
void setMinimumWaypointCount(unsigned int mwc)
Get the minimum number of waypoints along the solution path.
double max_solution_segment_length_
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
std::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
ob::PlannerPtr allocatePlanner(const ob::SpaceInformationPtr &si, const std::string &new_name, const ModelBasedPlanningContextSpecification &spec)
ob::PlannerPtr allocatePlannerImpl(const ob::SpaceInformationPtr &si, const std::string &new_name, const ModelBasedPlanningContextSpecification &spec, bool load_planner_data=false, bool store_planner_data=false, const std::string &file_path="")
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code, const ros::NodeHandle &nh, bool use_constraints_approximations) const
Returns a planning context to OMPLInterface, which in turn passes it to OMPLPlannerManager.
const moveit::core::RobotModelConstPtr & getRobotModel() const
unsigned int max_state_sampling_attempts_
unsigned int max_goal_samples_
maximum number of states to sample in the goal region for any planning request (when such sampling is...
unsigned int getMaximumGoalSamplingAttempts() const
unsigned int getMaximumPlanningThreads() const
~PlanningContextManager()
PlanningContextManager(moveit::core::RobotModelConstPtr robot_model, constraint_samplers::ConstraintSamplerManagerPtr csm)
MultiQueryPlannerAllocator planner_allocator_
Multi-query planner allocator.
moveit_msgs::MotionPlanRequest MotionPlanRequest
ConfiguredPlannerAllocator plannerSelector(const std::string &planner) const
void registerStateSpaceFactory(const ModelBasedStateSpaceFactoryPtr &factory)
ConfiguredPlannerSelector getPlannerSelector() const
std::map< std::string, ConfiguredPlannerAllocator > known_planners_
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time
MultiQueryPlannerAllocator()=default
std::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
unsigned int getMaximumGoalSamples() const
ob::PlannerDataStorage storage_
std::map< std::string, std::string > planner_data_storage_paths_
void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
unsigned int getMaximumStateSamplingAttempts() const
void registerDefaultPlanners()
unsigned int minimum_waypoint_count_
MOVEIT_STRUCT_FORWARD(CachedContexts)
void registerPlannerAllocatorHelper(const std::string &planner_id)
void setMaximumGoalSamples(unsigned int max_goal_samples)
ompl
Author(s): Ioan Sucan
autogenerated on Tue Dec 24 2024 03:28:10