43#include <ompl/geometric/planners/AnytimePathShortening.h>
44#include <ompl/geometric/planners/rrt/RRT.h>
45#include <ompl/geometric/planners/rrt/pRRT.h>
46#include <ompl/geometric/planners/rrt/RRTConnect.h>
47#include <ompl/geometric/planners/rrt/TRRT.h>
48#include <ompl/geometric/planners/rrt/LazyRRT.h>
49#include <ompl/geometric/planners/est/EST.h>
50#include <ompl/geometric/planners/sbl/SBL.h>
51#include <ompl/geometric/planners/sbl/pSBL.h>
52#include <ompl/geometric/planners/kpiece/KPIECE1.h>
53#include <ompl/geometric/planners/kpiece/BKPIECE1.h>
54#include <ompl/geometric/planners/kpiece/LBKPIECE1.h>
55#include <ompl/geometric/planners/rrt/RRTstar.h>
56#include <ompl/geometric/planners/prm/PRM.h>
57#include <ompl/geometric/planners/prm/PRMstar.h>
58#include <ompl/geometric/planners/fmt/FMT.h>
59#include <ompl/geometric/planners/fmt/BFMT.h>
60#include <ompl/geometric/planners/pdst/PDST.h>
61#include <ompl/geometric/planners/stride/STRIDE.h>
62#include <ompl/geometric/planners/rrt/BiTRRT.h>
63#include <ompl/geometric/planners/rrt/LBTRRT.h>
64#include <ompl/geometric/planners/est/BiEST.h>
65#include <ompl/geometric/planners/est/ProjEST.h>
66#include <ompl/geometric/planners/prm/LazyPRM.h>
67#include <ompl/geometric/planners/prm/LazyPRMstar.h>
68#include <ompl/geometric/planners/prm/SPARS.h>
69#include <ompl/geometric/planners/prm/SPARStwo.h>
71#include <ompl/base/ConstrainedSpaceInformation.h>
72#include <ompl/base/spaces/constraint/ProjectedStateSpace.h>
81using namespace std::placeholders;
95 std::map<std::pair<std::string, std::string>, std::vector<ModelBasedPlanningContextPtr> >
contexts_;
102 for (
const auto& entry : planner_data_storage_paths_)
104 ob::PlannerData data(planners_[entry.first]->getSpaceInformation());
105 planners_[entry.first]->getPlannerData(data);
106 RCLCPP_INFO_STREAM(getLogger(),
"Storing planner data. NumEdges: " << data.numEdges()
107 <<
", NumVertices: " << data.numVertices());
108 storage_.store(data, entry.second.c_str());
114 const std::string& new_name,
119 auto it = cfg.find(
"multi_query_planning_enabled");
120 bool multi_query_planning_enabled =
false;
123 multi_query_planning_enabled = boost::lexical_cast<bool>(it->second);
126 if (multi_query_planning_enabled)
130 auto planner_map_it = planners_.find(new_name);
131 if (planner_map_it != planners_.end())
133 ob::PlannerData data(si);
134 planner_map_it->second->getPlannerData(data);
135 RCLCPP_INFO_STREAM(getLogger(),
"Reusing planner data. NumEdges: " << data.numEdges()
136 <<
", NumVertices: " << data.numVertices());
137 planners_[planner_map_it->first] = std::shared_ptr<ob::Planner>{ allocatePersistentPlanner<T>(data) };
138 return planners_[planner_map_it->first];
146 it = cfg.find(
"load_planner_data");
147 bool load_planner_data =
false;
150 load_planner_data = boost::lexical_cast<bool>(it->second);
153 it = cfg.find(
"store_planner_data");
154 bool store_planner_data =
false;
157 store_planner_data = boost::lexical_cast<bool>(it->second);
160 it = cfg.find(
"planner_data_path");
161 std::string planner_data_path;
164 planner_data_path = it->second;
168 planners_[new_name] =
169 allocatePlannerImpl<T>(si, new_name, spec, load_planner_data, store_planner_data, planner_data_path);
170 return planners_[new_name];
175 return allocatePlannerImpl<T>(si, new_name, spec);
180ompl::base::PlannerPtr
181MultiQueryPlannerAllocator::allocatePlannerImpl(
const ob::SpaceInformationPtr& si,
const std::string& new_name,
183 bool load_planner_data,
bool store_planner_data,
184 const std::string& file_path)
186 ob::PlannerPtr planner;
188 if (load_planner_data)
190 ob::PlannerData data(si);
191 storage_.load(file_path.c_str(), data);
192 RCLCPP_INFO_STREAM(getLogger(),
"Loading planner data. NumEdges: " << data.numEdges()
193 <<
", NumVertices: " << data.numVertices());
194 planner = std::shared_ptr<ob::Planner>{ allocatePersistentPlanner<T>(data) };
197 RCLCPP_ERROR(getLogger(),
198 "Creating a '%s' planner from persistent data is not supported. Going to create a new instance.",
205 planner = std::make_shared<T>(si);
208 if (!new_name.empty())
210 planner->setName(new_name);
213 planner->params().setParams(spec.
config_,
true);
215 if (store_planner_data)
217 planner_data_storage_paths_[new_name] = file_path;
225inline ompl::base::Planner* MultiQueryPlannerAllocator::allocatePersistentPlanner(
const ob::PlannerData& )
230inline ompl::base::Planner*
231MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::PRM>(
const ob::PlannerData& data)
233 return new og::PRM(data);
236inline ompl::base::Planner*
237MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::PRMstar>(
const ob::PlannerData& data)
239 return new og::PRMstar(data);
242inline ompl::base::Planner*
243MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::LazyPRM>(
const ob::PlannerData& data)
245 return new og::LazyPRM(data);
248inline ompl::base::Planner*
249MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::LazyPRMstar>(
const ob::PlannerData& data)
251 return new og::LazyPRMstar(data);
255 constraint_samplers::ConstraintSamplerManagerPtr csm)
256 : robot_model_(std::move(robot_model))
257 , constraint_sampler_manager_(std::move(csm))
258 , max_goal_samples_(10)
259 , max_state_sampling_attempts_(4)
260 , max_goal_sampling_attempts_(1000)
261 , max_planning_threads_(4)
262 , max_solution_segment_length_(0.0)
263 , minimum_waypoint_count_(2)
265 cached_contexts_ = std::make_shared<CachedContexts>();
281 RCLCPP_ERROR(getLogger(),
"Unknown planner: '%s'", planner.c_str());
297 registerPlannerAllocatorHelper<og::AnytimePathShortening>(
"geometric::AnytimePathShortening");
298 registerPlannerAllocatorHelper<og::BFMT>(
"geometric::BFMT");
299 registerPlannerAllocatorHelper<og::BiEST>(
"geometric::BiEST");
300 registerPlannerAllocatorHelper<og::BiTRRT>(
"geometric::BiTRRT");
301 registerPlannerAllocatorHelper<og::BKPIECE1>(
"geometric::BKPIECE");
302 registerPlannerAllocatorHelper<og::EST>(
"geometric::EST");
303 registerPlannerAllocatorHelper<og::FMT>(
"geometric::FMT");
304 registerPlannerAllocatorHelper<og::KPIECE1>(
"geometric::KPIECE");
305 registerPlannerAllocatorHelper<og::LazyPRM>(
"geometric::LazyPRM");
306 registerPlannerAllocatorHelper<og::LazyPRMstar>(
"geometric::LazyPRMstar");
307 registerPlannerAllocatorHelper<og::LazyRRT>(
"geometric::LazyRRT");
308 registerPlannerAllocatorHelper<og::LBKPIECE1>(
"geometric::LBKPIECE");
309 registerPlannerAllocatorHelper<og::LBTRRT>(
"geometric::LBTRRT");
310 registerPlannerAllocatorHelper<og::PDST>(
"geometric::PDST");
311 registerPlannerAllocatorHelper<og::PRM>(
"geometric::PRM");
312 registerPlannerAllocatorHelper<og::PRMstar>(
"geometric::PRMstar");
313 registerPlannerAllocatorHelper<og::ProjEST>(
"geometric::ProjEST");
314 registerPlannerAllocatorHelper<og::RRT>(
"geometric::RRT");
315 registerPlannerAllocatorHelper<og::RRTConnect>(
"geometric::RRTConnect");
316 registerPlannerAllocatorHelper<og::RRTstar>(
"geometric::RRTstar");
317 registerPlannerAllocatorHelper<og::SBL>(
"geometric::SBL");
318 registerPlannerAllocatorHelper<og::SPARS>(
"geometric::SPARS");
319 registerPlannerAllocatorHelper<og::SPARStwo>(
"geometric::SPARStwo");
320 registerPlannerAllocatorHelper<og::STRIDE>(
"geometric::STRIDE");
321 registerPlannerAllocatorHelper<og::TRRT>(
"geometric::TRRT");
333 return [
this](
const std::string& planner) {
return plannerSelector(planner); };
341ModelBasedPlanningContextPtr
343 const ModelBasedStateSpaceFactoryPtr& factory,
344 const moveit_msgs::msg::MotionPlanRequest& req)
const
347 ModelBasedPlanningContextPtr context;
350 std::unique_lock<std::mutex> slock(cached_contexts_->lock_);
351 auto cached_contexts = cached_contexts_->contexts_.find(std::make_pair(config.
name, factory->getType()));
352 if (cached_contexts != cached_contexts_->contexts_.end())
354 for (
const ModelBasedPlanningContextPtr& cached_context : cached_contexts->second)
356 if (cached_context.unique())
358 RCLCPP_DEBUG(getLogger(),
"Reusing cached planning context");
359 context = cached_context;
374 context_spec.
state_space_ = factory->getNewStateSpace(space_spec);
378 RCLCPP_DEBUG_STREAM(getLogger(),
"planning_context_manager: Using OMPL's constrained state space for planning.");
381 ompl::base::ConstraintPtr ompl_constraint =
385 if (!ompl_constraint)
387 return ModelBasedPlanningContextPtr();
394 std::make_shared<ob::ProjectedStateSpace>(context_spec.
state_space_, ompl_constraint);
407 RCLCPP_DEBUG(getLogger(),
"Creating new planning context");
408 context = std::make_shared<ModelBasedPlanningContext>(config.
name, context_spec);
415 std::lock_guard<std::mutex> slock(cached_contexts_->lock_);
416 cached_contexts_->contexts_[std::make_pair(config.
name, factory->getType())].push_back(context);
432 context->setSpecificationConfig(config.
config);
442 RCLCPP_DEBUG(getLogger(),
"Using '%s' parameterization for solving problem", factory_type.c_str());
447 RCLCPP_ERROR(getLogger(),
"Factory of type '%s' was not found", factory_type.c_str());
448 static const ModelBasedStateSpaceFactoryPtr EMPTY;
453const ModelBasedStateSpaceFactoryPtr&
455 const moveit_msgs::msg::MotionPlanRequest& req)
const
459 int prev_priority = 0;
462 int priority = it->second->canRepresentProblem(group, req,
robot_model_);
463 if (priority > prev_priority)
466 prev_priority = priority;
472 RCLCPP_ERROR(getLogger(),
"There are no known state spaces that can represent the given planning "
474 static const ModelBasedStateSpaceFactoryPtr EMPTY;
479 RCLCPP_DEBUG(getLogger(),
"Using '%s' parameterization for solving problem", best->first.c_str());
485 const planning_scene::PlanningSceneConstPtr&
planning_scene,
const moveit_msgs::msg::MotionPlanRequest& req,
486 moveit_msgs::msg::MoveItErrorCodes& error_code,
const rclcpp::Node::SharedPtr& node,
487 bool use_constraints_approximation)
const
489 if (req.group_name.empty())
491 RCLCPP_ERROR(getLogger(),
"No group specified to plan for");
492 error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
493 return ModelBasedPlanningContextPtr();
496 error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
500 RCLCPP_ERROR(getLogger(),
"No planning scene supplied as input");
501 return ModelBasedPlanningContextPtr();
506 if (!req.planner_id.empty())
508 pc =
planner_configs_.find(req.planner_id.find(req.group_name) == std::string::npos ?
509 req.group_name +
"[" + req.planner_id +
"]" :
513 RCLCPP_WARN(getLogger(),
514 "Cannot find planning configuration for group '%s' using planner '%s'. Will use defaults instead.",
515 req.group_name.c_str(), req.planner_id.c_str());
524 RCLCPP_ERROR(getLogger(),
"Cannot find planning configuration for group '%s'", req.group_name.c_str());
525 return ModelBasedPlanningContextPtr();
558 ModelBasedStateSpaceFactoryPtr factory;
559 auto constrained_planning_iterator = pc->second.config.find(
"enforce_constrained_state_space");
560 auto joint_space_planning_iterator = pc->second.config.find(
"enforce_joint_model_state_space");
563 if (constrained_planning_iterator != pc->second.config.end() &&
564 boost::lexical_cast<bool>(constrained_planning_iterator->second) &&
565 ((req.path_constraints.position_constraints.size() == 1) ||
566 (req.path_constraints.orientation_constraints.size() == 1)))
570 else if (joint_space_planning_iterator != pc->second.config.end() &&
571 boost::lexical_cast<bool>(joint_space_planning_iterator->second))
586 moveit::core::RobotStatePtr start_state =
planning_scene->getCurrentStateUpdated(req.start_state);
590 context->setMotionPlanRequest(req);
591 context->setCompleteInitialState(*start_state);
593 context->setPlanningVolume(req.workspace_parameters);
594 if (!context->setPathConstraints(req.path_constraints, &error_code))
596 return ModelBasedPlanningContextPtr();
599 if (!context->setGoalConstraints(req.goal_constraints, req.path_constraints, &error_code))
601 return ModelBasedPlanningContextPtr();
606 context->configure(node, use_constraints_approximation);
607 RCLCPP_DEBUG(getLogger(),
"%s: New planning context is set.", context->getName().c_str());
608 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
610 catch (ompl::Exception& ex)
612 RCLCPP_ERROR(getLogger(),
"OMPL encountered an error: %s", ex.what());
static const std::string PARAMETERIZATION_TYPE
static const std::string PARAMETERIZATION_TYPE
~MultiQueryPlannerAllocator()
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
PlanningContextManager(moveit::core::RobotModelConstPtr robot_model, constraint_samplers::ConstraintSamplerManagerPtr csm)
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)
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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.
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.