42 #include <ompl/geometric/planners/AnytimePathShortening.h>
43 #include <ompl/geometric/planners/rrt/RRT.h>
44 #include <ompl/geometric/planners/rrt/pRRT.h>
45 #include <ompl/geometric/planners/rrt/RRTConnect.h>
46 #include <ompl/geometric/planners/rrt/TRRT.h>
47 #include <ompl/geometric/planners/rrt/LazyRRT.h>
48 #include <ompl/geometric/planners/est/EST.h>
49 #include <ompl/geometric/planners/sbl/SBL.h>
50 #include <ompl/geometric/planners/sbl/pSBL.h>
51 #include <ompl/geometric/planners/kpiece/KPIECE1.h>
52 #include <ompl/geometric/planners/kpiece/BKPIECE1.h>
53 #include <ompl/geometric/planners/kpiece/LBKPIECE1.h>
54 #include <ompl/geometric/planners/rrt/RRTstar.h>
55 #include <ompl/geometric/planners/prm/PRM.h>
56 #include <ompl/geometric/planners/prm/PRMstar.h>
57 #include <ompl/geometric/planners/fmt/FMT.h>
58 #include <ompl/geometric/planners/fmt/BFMT.h>
59 #include <ompl/geometric/planners/pdst/PDST.h>
60 #include <ompl/geometric/planners/stride/STRIDE.h>
61 #include <ompl/geometric/planners/rrt/BiTRRT.h>
62 #include <ompl/geometric/planners/rrt/LBTRRT.h>
63 #include <ompl/geometric/planners/est/BiEST.h>
64 #include <ompl/geometric/planners/est/ProjEST.h>
65 #include <ompl/geometric/planners/prm/LazyPRM.h>
66 #include <ompl/geometric/planners/prm/LazyPRMstar.h>
67 #include <ompl/geometric/planners/prm/SPARS.h>
68 #include <ompl/geometric/planners/prm/SPARStwo.h>
70 #include <ompl/base/ConstrainedSpaceInformation.h>
71 #include <ompl/base/spaces/constraint/ProjectedStateSpace.h>
80 using namespace std::placeholders;
84 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.ompl_planning.planning_context_manager");
88 std::map<std::pair<std::string, std::string>, std::vector<ModelBasedPlanningContextPtr> >
contexts_;
92 MultiQueryPlannerAllocator::~MultiQueryPlannerAllocator()
95 for (
const auto& entry : planner_data_storage_paths_)
97 ob::PlannerData data(planners_[entry.first]->getSpaceInformation());
98 planners_[entry.first]->getPlannerData(data);
99 RCLCPP_INFO_STREAM(LOGGER,
"Storing planner data. NumEdges: " << data.numEdges()
100 <<
", NumVertices: " << data.numVertices());
101 storage_.store(data, entry.second.c_str());
105 template <
typename T>
106 ompl::base::PlannerPtr MultiQueryPlannerAllocator::allocatePlanner(
const ob::SpaceInformationPtr& si,
107 const std::string& new_name,
112 auto it = cfg.find(
"multi_query_planning_enabled");
113 bool multi_query_planning_enabled =
false;
116 multi_query_planning_enabled = boost::lexical_cast<bool>(it->second);
119 if (multi_query_planning_enabled)
123 auto planner_map_it = planners_.find(new_name);
124 if (planner_map_it != planners_.end())
126 ob::PlannerData data(si);
127 planner_map_it->second->getPlannerData(data);
128 RCLCPP_INFO_STREAM(LOGGER,
"Reusing planner data. NumEdges: " << data.numEdges()
129 <<
", NumVertices: " << data.numVertices());
130 planners_[planner_map_it->first] = std::shared_ptr<ob::Planner>{ allocatePersistentPlanner<T>(data) };
131 return planners_[planner_map_it->first];
139 it = cfg.find(
"load_planner_data");
140 bool load_planner_data =
false;
143 load_planner_data = boost::lexical_cast<bool>(it->second);
146 it = cfg.find(
"store_planner_data");
147 bool store_planner_data =
false;
150 store_planner_data = boost::lexical_cast<bool>(it->second);
153 it = cfg.find(
"planner_data_path");
154 std::string planner_data_path;
157 planner_data_path = it->second;
161 planners_[new_name] =
162 allocatePlannerImpl<T>(si, new_name, spec, load_planner_data, store_planner_data, planner_data_path);
163 return planners_[new_name];
168 return allocatePlannerImpl<T>(si, new_name, spec);
172 template <
typename T>
173 ompl::base::PlannerPtr
174 MultiQueryPlannerAllocator::allocatePlannerImpl(
const ob::SpaceInformationPtr& si,
const std::string& new_name,
176 bool load_planner_data,
bool store_planner_data,
177 const std::string& file_path)
179 ob::PlannerPtr planner;
181 if (load_planner_data)
183 ob::PlannerData data(si);
184 storage_.load(file_path.c_str(), data);
185 RCLCPP_INFO_STREAM(LOGGER,
"Loading planner data. NumEdges: " << data.numEdges()
186 <<
", NumVertices: " << data.numVertices());
187 planner = std::shared_ptr<ob::Planner>{ allocatePersistentPlanner<T>(data) };
191 "Creating a '%s' planner from persistent data is not supported. Going to create a new instance.",
198 planner = std::make_shared<T>(si);
201 if (!new_name.empty())
203 planner->setName(new_name);
206 planner->params().setParams(spec.
config_,
true);
208 if (store_planner_data)
210 planner_data_storage_paths_[new_name] = file_path;
217 template <
typename T>
218 inline ompl::base::Planner* MultiQueryPlannerAllocator::allocatePersistentPlanner(
const ob::PlannerData& )
223 inline ompl::base::Planner*
224 MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::PRM>(
const ob::PlannerData& data)
226 return new og::PRM(data);
229 inline ompl::base::Planner*
230 MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::PRMstar>(
const ob::PlannerData& data)
232 return new og::PRMstar(data);
235 inline ompl::base::Planner*
236 MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::LazyPRM>(
const ob::PlannerData& data)
238 return new og::LazyPRM(data);
241 inline ompl::base::Planner*
242 MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::LazyPRMstar>(
const ob::PlannerData& data)
244 return new og::LazyPRMstar(data);
247 PlanningContextManager::PlanningContextManager(moveit::core::RobotModelConstPtr robot_model,
248 constraint_samplers::ConstraintSamplerManagerPtr csm)
249 : robot_model_(std::move(robot_model))
250 , constraint_sampler_manager_(std::move(csm))
251 , max_goal_samples_(10)
252 , max_state_sampling_attempts_(4)
253 , max_goal_sampling_attempts_(1000)
254 , max_planning_threads_(4)
255 , max_solution_segment_length_(0.0)
256 , minimum_waypoint_count_(2)
258 cached_contexts_ = std::make_shared<CachedContexts>();
274 RCLCPP_ERROR(LOGGER,
"Unknown planner: '%s'", planner.c_str());
279 template <
typename T>
290 registerPlannerAllocatorHelper<og::AnytimePathShortening>(
"geometric::AnytimePathShortening");
291 registerPlannerAllocatorHelper<og::BFMT>(
"geometric::BFMT");
292 registerPlannerAllocatorHelper<og::BiEST>(
"geometric::BiEST");
293 registerPlannerAllocatorHelper<og::BiTRRT>(
"geometric::BiTRRT");
294 registerPlannerAllocatorHelper<og::BKPIECE1>(
"geometric::BKPIECE");
295 registerPlannerAllocatorHelper<og::EST>(
"geometric::EST");
296 registerPlannerAllocatorHelper<og::FMT>(
"geometric::FMT");
297 registerPlannerAllocatorHelper<og::KPIECE1>(
"geometric::KPIECE");
298 registerPlannerAllocatorHelper<og::LazyPRM>(
"geometric::LazyPRM");
299 registerPlannerAllocatorHelper<og::LazyPRMstar>(
"geometric::LazyPRMstar");
300 registerPlannerAllocatorHelper<og::LazyRRT>(
"geometric::LazyRRT");
301 registerPlannerAllocatorHelper<og::LBKPIECE1>(
"geometric::LBKPIECE");
302 registerPlannerAllocatorHelper<og::LBTRRT>(
"geometric::LBTRRT");
303 registerPlannerAllocatorHelper<og::PDST>(
"geometric::PDST");
304 registerPlannerAllocatorHelper<og::PRM>(
"geometric::PRM");
305 registerPlannerAllocatorHelper<og::PRMstar>(
"geometric::PRMstar");
306 registerPlannerAllocatorHelper<og::ProjEST>(
"geometric::ProjEST");
307 registerPlannerAllocatorHelper<og::RRT>(
"geometric::RRT");
308 registerPlannerAllocatorHelper<og::RRTConnect>(
"geometric::RRTConnect");
309 registerPlannerAllocatorHelper<og::RRTstar>(
"geometric::RRTstar");
310 registerPlannerAllocatorHelper<og::SBL>(
"geometric::SBL");
311 registerPlannerAllocatorHelper<og::SPARS>(
"geometric::SPARS");
312 registerPlannerAllocatorHelper<og::SPARStwo>(
"geometric::SPARStwo");
313 registerPlannerAllocatorHelper<og::STRIDE>(
"geometric::STRIDE");
314 registerPlannerAllocatorHelper<og::TRRT>(
"geometric::TRRT");
326 return [
this](
const std::string& planner) {
return plannerSelector(planner); };
334 ModelBasedPlanningContextPtr
336 const ModelBasedStateSpaceFactoryPtr& factory,
340 ModelBasedPlanningContextPtr context;
343 std::unique_lock<std::mutex> slock(cached_contexts_->lock_);
344 auto cached_contexts = cached_contexts_->contexts_.find(std::make_pair(config.
name, factory->getType()));
345 if (cached_contexts != cached_contexts_->contexts_.end())
347 for (
const ModelBasedPlanningContextPtr& cached_context : cached_contexts->second)
348 if (cached_context.unique())
350 RCLCPP_DEBUG(LOGGER,
"Reusing cached planning context");
351 context = cached_context;
365 context_spec.
state_space_ = factory->getNewStateSpace(space_spec);
369 RCLCPP_DEBUG_STREAM(LOGGER,
"planning_context_manager: Using OMPL's constrained state space for planning.");
372 ompl::base::ConstraintPtr ompl_constraint =
379 std::make_shared<ob::ProjectedStateSpace>(context_spec.
state_space_, ompl_constraint);
392 RCLCPP_DEBUG(LOGGER,
"Creating new planning context");
393 context = std::make_shared<ModelBasedPlanningContext>(config.
name, context_spec);
400 std::lock_guard<std::mutex> slock(cached_contexts_->lock_);
401 cached_contexts_->contexts_[std::make_pair(config.
name, factory->getType())].push_back(context);
417 context->setSpecificationConfig(config.
config);
427 RCLCPP_DEBUG(LOGGER,
"Using '%s' parameterization for solving problem", factory_type.c_str());
432 RCLCPP_ERROR(LOGGER,
"Factory of type '%s' was not found", factory_type.c_str());
433 static const ModelBasedStateSpaceFactoryPtr EMPTY;
438 const ModelBasedStateSpaceFactoryPtr&
444 int prev_priority = 0;
448 if (priority > prev_priority)
451 prev_priority = priority;
457 RCLCPP_ERROR(LOGGER,
"There are no known state spaces that can represent the given planning "
459 static const ModelBasedStateSpaceFactoryPtr EMPTY;
464 RCLCPP_DEBUG(LOGGER,
"Using '%s' parameterization for solving problem", best->first.c_str());
471 moveit_msgs::msg::MoveItErrorCodes& error_code,
const rclcpp::Node::SharedPtr& node,
472 bool use_constraints_approximation)
const
474 if (req.group_name.empty())
476 RCLCPP_ERROR(LOGGER,
"No group specified to plan for");
477 error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
478 return ModelBasedPlanningContextPtr();
481 error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
485 RCLCPP_ERROR(LOGGER,
"No planning scene supplied as input");
486 return ModelBasedPlanningContextPtr();
491 if (!req.planner_id.empty())
493 pc =
planner_configs_.find(req.planner_id.find(req.group_name) == std::string::npos ?
494 req.group_name +
"[" + req.planner_id +
"]" :
499 "Cannot find planning configuration for group '%s' using planner '%s'. Will use defaults instead.",
500 req.group_name.c_str(), req.planner_id.c_str());
509 RCLCPP_ERROR(LOGGER,
"Cannot find planning configuration for group '%s'", req.group_name.c_str());
510 return ModelBasedPlanningContextPtr();
543 ModelBasedStateSpaceFactoryPtr factory;
544 auto constrained_planning_iterator = pc->second.config.find(
"enforce_constrained_state_space");
545 auto joint_space_planning_iterator = pc->second.config.find(
"enforce_joint_model_state_space");
548 if (constrained_planning_iterator != pc->second.config.end() &&
549 boost::lexical_cast<bool>(constrained_planning_iterator->second) &&
550 ((req.path_constraints.position_constraints.size() == 1) ||
551 (req.path_constraints.orientation_constraints.size() == 1)))
555 else if (joint_space_planning_iterator != pc->second.config.end() &&
556 boost::lexical_cast<bool>(joint_space_planning_iterator->second))
571 moveit::core::RobotStatePtr start_state =
planning_scene->getCurrentStateUpdated(req.start_state);
575 context->setMotionPlanRequest(req);
576 context->setCompleteInitialState(*start_state);
578 context->setPlanningVolume(req.workspace_parameters);
579 if (!context->setPathConstraints(req.path_constraints, &error_code))
581 return ModelBasedPlanningContextPtr();
584 if (!context->setGoalConstraints(req.goal_constraints, req.path_constraints, &error_code))
586 return ModelBasedPlanningContextPtr();
591 context->configure(node, use_constraints_approximation);
592 RCLCPP_DEBUG(LOGGER,
"%s: New planning context is set.", context->getName().c_str());
593 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
595 catch (ompl::Exception& ex)
597 RCLCPP_ERROR(LOGGER,
"OMPL encountered an error: %s", ex.what());
static const std::string PARAMETERIZATION_TYPE
static const std::string PARAMETERIZATION_TYPE
ob::PlannerPtr allocatePlanner(const ob::SpaceInformationPtr &si, const std::string &new_name, const ModelBasedPlanningContextSpecification &spec)
planning_interface::PlannerConfigurationMap planner_configs_
All the existing planning configurations. The name of the configuration is the key of the map....
const ModelBasedStateSpaceFactoryPtr & getStateSpaceFactory(const std::string &factory_type) const
unsigned int max_goal_sampling_attempts_
maximum number of attempts to be made at sampling goals
void registerDefaultStateSpaces()
std::map< std::string, ConfiguredPlannerAllocator > known_planners_
~PlanningContextManager()
void registerPlannerAllocator(const std::string &planner_id, const ConfiguredPlannerAllocator &pa)
double max_solution_segment_length_
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.
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time
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 minimum_waypoint_count_
moveit::core::RobotModelConstPtr robot_model_
The kinematic model for which motion plans are computed.
ConfiguredPlannerSelector getPlannerSelector() const
std::map< std::string, ModelBasedStateSpaceFactoryPtr > state_space_factories_
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
void registerDefaultPlanners()
unsigned int max_state_sampling_attempts_
ConfiguredPlannerAllocator plannerSelector(const std::string &planner) const
void registerPlannerAllocatorHelper(const std::string &planner_id)
MultiQueryPlannerAllocator planner_allocator_
Multi-query planner allocator.
void registerStateSpaceFactory(const ModelBasedStateSpaceFactoryPtr &factory)
The MoveIt interface to OMPL.
std::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
ompl::base::ConstraintPtr createOMPLConstraints(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group, const moveit_msgs::msg::Constraints &constraints)
Factory to create constraints based on what is in the MoveIt constraint message.
std::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
ModelBasedStateSpacePtr state_space_
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ob::ConstrainedStateSpacePtr constrained_state_space_
OMPL constrained state space to handle path constraints.
std::map< std::string, std::string > config_
ConfiguredPlannerSelector planner_selector_
og::SimpleSetupPtr ompl_simple_setup_
std::map< std::pair< std::string, std::string >, std::vector< ModelBasedPlanningContextPtr > > contexts_
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...
std::map< std::string, std::string > config
Key-value pairs of settings that get passed to the planning algorithm.
std::string group
The group (as defined in the SRDF) this configuration is meant for.