moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_context_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
39 
40 #include <utility>
41 
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>
69 
70 #include <ompl/base/ConstrainedSpaceInformation.h>
71 #include <ompl/base/spaces/constraint/ProjectedStateSpace.h>
72 
79 
80 using namespace std::placeholders;
81 
82 namespace ompl_interface
83 {
84 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.planning_context_manager");
85 
87 {
88  std::map<std::pair<std::string, std::string>, std::vector<ModelBasedPlanningContextPtr> > contexts_;
89  std::mutex lock_;
90 };
91 
92 MultiQueryPlannerAllocator::~MultiQueryPlannerAllocator()
93 {
94  // Store all planner data
95  for (const auto& entry : planner_data_storage_paths_)
96  {
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());
102  }
103 }
104 
105 template <typename T>
106 ompl::base::PlannerPtr MultiQueryPlannerAllocator::allocatePlanner(const ob::SpaceInformationPtr& si,
107  const std::string& new_name,
109 {
110  // Store planner instance if multi-query planning is enabled
111  auto cfg = spec.config_;
112  auto it = cfg.find("multi_query_planning_enabled");
113  bool multi_query_planning_enabled = false;
114  if (it != cfg.end())
115  {
116  multi_query_planning_enabled = boost::lexical_cast<bool>(it->second);
117  cfg.erase(it);
118  }
119  if (multi_query_planning_enabled)
120  {
121  // If we already have an instance, reuse it's planning data
122  // FIXME: make reusing PlannerPtr not crash, so that we don't have to reconstruct a PlannerPtr instance
123  auto planner_map_it = planners_.find(new_name);
124  if (planner_map_it != planners_.end())
125  {
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];
132  }
133 
134  // Certain multi-query planners allow loading and storing the generated planner data. This feature can be
135  // selectively enabled for loading and storing using the bool parameters 'load_planner_data' and
136  // 'store_planner_data'. The storage file path is set using the parameter 'planner_data_path'.
137  // File read and write access are handled by the PlannerDataStorage class. If the file path is invalid
138  // an error message is printed and the planner is constructed/destructed with default values.
139  it = cfg.find("load_planner_data");
140  bool load_planner_data = false;
141  if (it != cfg.end())
142  {
143  load_planner_data = boost::lexical_cast<bool>(it->second);
144  cfg.erase(it);
145  }
146  it = cfg.find("store_planner_data");
147  bool store_planner_data = false;
148  if (it != cfg.end())
149  {
150  store_planner_data = boost::lexical_cast<bool>(it->second);
151  cfg.erase(it);
152  }
153  it = cfg.find("planner_data_path");
154  std::string planner_data_path;
155  if (it != cfg.end())
156  {
157  planner_data_path = it->second;
158  cfg.erase(it);
159  }
160  // Store planner instance for multi-query use
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];
164  }
165  else
166  {
167  // Return single-shot planner instance
168  return allocatePlannerImpl<T>(si, new_name, spec);
169  }
170 }
171 
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)
178 {
179  ob::PlannerPtr planner;
180  // Try to initialize planner with loaded planner data
181  if (load_planner_data)
182  {
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) };
188  if (!planner)
189  {
190  RCLCPP_ERROR(LOGGER,
191  "Creating a '%s' planner from persistent data is not supported. Going to create a new instance.",
192  new_name.c_str());
193  }
194  }
195 
196  if (!planner)
197  {
198  planner = std::make_shared<T>(si);
199  }
200 
201  if (!new_name.empty())
202  {
203  planner->setName(new_name);
204  }
205 
206  planner->params().setParams(spec.config_, true);
207  // Remember which planner instances to store when the destructor is called
208  if (store_planner_data)
209  {
210  planner_data_storage_paths_[new_name] = file_path;
211  }
212 
213  return planner;
214 }
215 
216 // default implementation
217 template <typename T>
218 inline ompl::base::Planner* MultiQueryPlannerAllocator::allocatePersistentPlanner(const ob::PlannerData& /*data*/)
219 {
220  return nullptr;
221 };
222 template <>
223 inline ompl::base::Planner*
224 MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::PRM>(const ob::PlannerData& data)
225 {
226  return new og::PRM(data);
227 };
228 template <>
229 inline ompl::base::Planner*
230 MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::PRMstar>(const ob::PlannerData& data)
231 {
232  return new og::PRMstar(data);
233 };
234 template <>
235 inline ompl::base::Planner*
236 MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::LazyPRM>(const ob::PlannerData& data)
237 {
238  return new og::LazyPRM(data);
239 };
240 template <>
241 inline ompl::base::Planner*
242 MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::LazyPRMstar>(const ob::PlannerData& data)
243 {
244  return new og::LazyPRMstar(data);
245 };
246 
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)
257 {
258  cached_contexts_ = std::make_shared<CachedContexts>();
261 }
262 
264 
266 {
267  auto it = known_planners_.find(planner);
268  if (it != known_planners_.end())
269  {
270  return it->second;
271  }
272  else
273  {
274  RCLCPP_ERROR(LOGGER, "Unknown planner: '%s'", planner.c_str());
276  }
277 }
278 
279 template <typename T>
281 {
282  registerPlannerAllocator(planner_id, [&](const ob::SpaceInformationPtr& si, const std::string& new_name,
284  return planner_allocator_.allocatePlanner<T>(si, new_name, spec);
285  });
286 }
287 
289 {
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");
315 }
316 
318 {
319  registerStateSpaceFactory(std::make_shared<JointModelStateSpaceFactory>());
320  registerStateSpaceFactory(std::make_shared<PoseModelStateSpaceFactory>());
321  registerStateSpaceFactory(std::make_shared<ConstrainedPlanningStateSpaceFactory>());
322 }
323 
325 {
326  return [this](const std::string& planner) { return plannerSelector(planner); };
327 }
328 
330 {
331  planner_configs_ = pconfig;
332 }
333 
334 ModelBasedPlanningContextPtr
336  const ModelBasedStateSpaceFactoryPtr& factory,
337  const moveit_msgs::msg::MotionPlanRequest& req) const
338 {
339  // Check for a cached planning context
340  ModelBasedPlanningContextPtr context;
341 
342  {
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())
346  {
347  for (const ModelBasedPlanningContextPtr& cached_context : cached_contexts->second)
348  if (cached_context.unique())
349  {
350  RCLCPP_DEBUG(LOGGER, "Reusing cached planning context");
351  context = cached_context;
352  break;
353  }
354  }
355  }
356 
357  // Create a new planning context
358  if (!context)
359  {
362  context_spec.config_ = config.config;
363  context_spec.planner_selector_ = getPlannerSelector();
365  context_spec.state_space_ = factory->getNewStateSpace(space_spec);
366 
368  {
369  RCLCPP_DEBUG_STREAM(LOGGER, "planning_context_manager: Using OMPL's constrained state space for planning.");
370 
371  // Select the correct type of constraints based on the path constraints in the planning request.
372  ompl::base::ConstraintPtr ompl_constraint =
373  createOMPLConstraints(robot_model_, config.group, req.path_constraints);
374 
375  // Create a constrained state space of type "projected state space".
376  // Other types are available, so we probably should add another setting to ompl_planning.yaml
377  // to choose between them.
378  context_spec.constrained_state_space_ =
379  std::make_shared<ob::ProjectedStateSpace>(context_spec.state_space_, ompl_constraint);
380 
381  // Pass the constrained state space to ompl simple setup through the creation of a
382  // ConstrainedSpaceInformation object. This makes sure the state space is properly initialized.
383  context_spec.ompl_simple_setup_ = std::make_shared<ompl::geometric::SimpleSetup>(
384  std::make_shared<ob::ConstrainedSpaceInformation>(context_spec.constrained_state_space_));
385  }
386  else
387  {
388  // Choose the correct simple setup type to load
389  context_spec.ompl_simple_setup_ = std::make_shared<ompl::geometric::SimpleSetup>(context_spec.state_space_);
390  }
391 
392  RCLCPP_DEBUG(LOGGER, "Creating new planning context");
393  context = std::make_shared<ModelBasedPlanningContext>(config.name, context_spec);
394 
395  // Do not cache a constrained planning context, as the constraints could be changed
396  // and need to be parsed again.
398  {
399  {
400  std::lock_guard<std::mutex> slock(cached_contexts_->lock_);
401  cached_contexts_->contexts_[std::make_pair(config.name, factory->getType())].push_back(context);
402  }
403  }
404  }
405 
406  context->setMaximumPlanningThreads(max_planning_threads_);
407  context->setMaximumGoalSamples(max_goal_samples_);
408  context->setMaximumStateSamplingAttempts(max_state_sampling_attempts_);
409  context->setMaximumGoalSamplingAttempts(max_goal_sampling_attempts_);
410 
411  if (max_solution_segment_length_ > std::numeric_limits<double>::epsilon())
412  {
413  context->setMaximumSolutionSegmentLength(max_solution_segment_length_);
414  }
415 
416  context->setMinimumWaypointCount(minimum_waypoint_count_);
417  context->setSpecificationConfig(config.config);
418 
419  return context;
420 }
421 
422 const ModelBasedStateSpaceFactoryPtr& PlanningContextManager::getStateSpaceFactory(const std::string& factory_type) const
423 {
424  auto f = factory_type.empty() ? state_space_factories_.begin() : state_space_factories_.find(factory_type);
425  if (f != state_space_factories_.end())
426  {
427  RCLCPP_DEBUG(LOGGER, "Using '%s' parameterization for solving problem", factory_type.c_str());
428  return f->second;
429  }
430  else
431  {
432  RCLCPP_ERROR(LOGGER, "Factory of type '%s' was not found", factory_type.c_str());
433  static const ModelBasedStateSpaceFactoryPtr EMPTY;
434  return EMPTY;
435  }
436 }
437 
438 const ModelBasedStateSpaceFactoryPtr&
440  const moveit_msgs::msg::MotionPlanRequest& req) const
441 {
442  // find the problem representation to use
443  auto best = state_space_factories_.end();
444  int prev_priority = 0;
445  for (auto it = state_space_factories_.begin(); it != state_space_factories_.end(); ++it)
446  {
447  int priority = it->second->canRepresentProblem(group, req, robot_model_);
448  if (priority > prev_priority)
449  {
450  best = it;
451  prev_priority = priority;
452  }
453  }
454 
455  if (best == state_space_factories_.end())
456  {
457  RCLCPP_ERROR(LOGGER, "There are no known state spaces that can represent the given planning "
458  "problem");
459  static const ModelBasedStateSpaceFactoryPtr EMPTY;
460  return EMPTY;
461  }
462  else
463  {
464  RCLCPP_DEBUG(LOGGER, "Using '%s' parameterization for solving problem", best->first.c_str());
465  return best->second;
466  }
467 }
468 
469 ModelBasedPlanningContextPtr PlanningContextManager::getPlanningContext(
470  const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit_msgs::msg::MotionPlanRequest& req,
471  moveit_msgs::msg::MoveItErrorCodes& error_code, const rclcpp::Node::SharedPtr& node,
472  bool use_constraints_approximation) const
473 {
474  if (req.group_name.empty())
475  {
476  RCLCPP_ERROR(LOGGER, "No group specified to plan for");
477  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
478  return ModelBasedPlanningContextPtr();
479  }
480 
481  error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
482 
483  if (!planning_scene)
484  {
485  RCLCPP_ERROR(LOGGER, "No planning scene supplied as input");
486  return ModelBasedPlanningContextPtr();
487  }
488 
489  // identify the correct planning configuration
490  auto pc = planner_configs_.end();
491  if (!req.planner_id.empty())
492  {
493  pc = planner_configs_.find(req.planner_id.find(req.group_name) == std::string::npos ?
494  req.group_name + "[" + req.planner_id + "]" :
495  req.planner_id);
496  if (pc == planner_configs_.end())
497  {
498  RCLCPP_WARN(LOGGER,
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());
501  }
502  }
503 
504  if (pc == planner_configs_.end())
505  {
506  pc = planner_configs_.find(req.group_name);
507  if (pc == planner_configs_.end())
508  {
509  RCLCPP_ERROR(LOGGER, "Cannot find planning configuration for group '%s'", req.group_name.c_str());
510  return ModelBasedPlanningContextPtr();
511  }
512  }
513 
514  // State space selection process
515  // ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
516  // There are 3 options for the factory_selector
517  // 1) enforce_constrained_state_space = true AND there are path constraints in the planning request
518  // Overrides all other settings and selects a ConstrainedPlanningStateSpace factory
519  // 2) enforce_joint_model_state_space = true
520  // If 1) is false, then this one overrides the remaining settings and returns a JointModelStateSpace factory
521  // 3) Not 1) or 2), then the factory is selected based on the priority that each one returns.
522  // See PoseModelStateSpaceFactory::canRepresentProblem for details on the selection process.
523  // In short, it returns a PoseModelStateSpace if there is an IK solver and a path constraint.
524  //
525  // enforce_constrained_state_space
526  // ****************************************
527  // Check if the user wants to use an OMPL ConstrainedStateSpace for planning.
528  // This is done by setting 'enforce_constrained_state_space' to 'true' for the desired group in ompl_planing.yaml.
529  // If there are no path constraints in the planning request, this option is ignored, as the constrained state space is
530  // only useful for paths constraints. (And at the moment only a single position constraint is supported, hence:
531  // req.path_constraints.position_constraints.size() == 1
532  // is used in the selection process below.)
533  //
534  // enforce_joint_model_state_space
535  // *******************************
536  // Check if sampling in JointModelStateSpace is enforced for this group by user.
537  // This is done by setting 'enforce_joint_model_state_space' to 'true' for the desired group in ompl_planning.yaml.
538  //
539  // Some planning problems like orientation path constraints are represented in PoseModelStateSpace and sampled via IK.
540  // However consecutive IK solutions are not checked for proximity at the moment and sometimes happen to be flipped,
541  // leading to invalid trajectories. This workaround lets the user prevent this problem by forcing rejection sampling
542  // in JointModelStateSpace.
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");
546 
547  // Use ConstrainedPlanningStateSpace if there is exactly one position constraint and/or one orientation constraint
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)))
552  {
554  }
555  else if (joint_space_planning_iterator != pc->second.config.end() &&
556  boost::lexical_cast<bool>(joint_space_planning_iterator->second))
557  {
559  }
560  else
561  {
562  factory = getStateSpaceFactory(pc->second.group, req);
563  }
564 
565  ModelBasedPlanningContextPtr context = getPlanningContext(pc->second, factory, req);
566 
567  if (context)
568  {
569  context->clear();
570 
571  moveit::core::RobotStatePtr start_state = planning_scene->getCurrentStateUpdated(req.start_state);
572 
573  // Setup the context
574  context->setPlanningScene(planning_scene);
575  context->setMotionPlanRequest(req);
576  context->setCompleteInitialState(*start_state);
577 
578  context->setPlanningVolume(req.workspace_parameters);
579  if (!context->setPathConstraints(req.path_constraints, &error_code))
580  {
581  return ModelBasedPlanningContextPtr();
582  }
583 
584  if (!context->setGoalConstraints(req.goal_constraints, req.path_constraints, &error_code))
585  {
586  return ModelBasedPlanningContextPtr();
587  }
588 
589  try
590  {
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;
594  }
595  catch (ompl::Exception& ex)
596  {
597  RCLCPP_ERROR(LOGGER, "OMPL encountered an error: %s", ex.what());
598  context.reset();
599  }
600  }
601 
602  return context;
603 }
604 } // namespace ompl_interface
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
std::map< std::string, ConfiguredPlannerAllocator > known_planners_
void registerPlannerAllocator(const std::string &planner_id, const ConfiguredPlannerAllocator &pa)
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...
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.
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.
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ob::ConstrainedStateSpacePtr constrained_state_space_
OMPL constrained state space to handle path constraints.
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.