moveit2
The MoveIt Motion Planning Framework for ROS 2.
model_based_planning_context.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 
37 #include <boost/algorithm/string/trim.hpp>
38 #include <boost/algorithm/string/split.hpp>
39 #include <boost/algorithm/string/replace.hpp>
40 #include <boost/lexical_cast.hpp>
41 
49 
51 
53 
54 #include <ompl/config.h>
55 #include <ompl/base/samplers/UniformValidStateSampler.h>
56 #include <ompl/base/goals/GoalLazySamples.h>
57 #include <ompl/tools/config/SelfConfig.h>
58 #include <ompl/base/spaces/SE3StateSpace.h>
59 #include <ompl/datastructures/PDF.h>
60 #include <ompl/base/terminationconditions/IterationTerminationCondition.h>
61 #include <ompl/base/terminationconditions/CostConvergenceTerminationCondition.h>
62 
63 #include <ompl/base/objectives/PathLengthOptimizationObjective.h>
64 #include <ompl/base/objectives/MechanicalWorkOptimizationObjective.h>
65 #include <ompl/base/objectives/MinimaxObjective.h>
66 #include <ompl/base/objectives/StateCostIntegralObjective.h>
67 #include <ompl/base/objectives/MaximizeMinClearanceObjective.h>
68 #include <ompl/geometric/planners/prm/LazyPRM.h>
69 
70 namespace ompl_interface
71 {
72 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.model_based_planning_context");
73 } // namespace ompl_interface
74 
77  : planning_interface::PlanningContext(name, spec.state_space_->getJointModelGroup()->getName())
78  , spec_(spec)
79  , complete_initial_robot_state_(spec.state_space_->getRobotModel())
80  , ompl_simple_setup_(spec.ompl_simple_setup_)
81  , ompl_benchmark_(*ompl_simple_setup_)
82  , ompl_parallel_plan_(ompl_simple_setup_->getProblemDefinition())
83  , ptc_(nullptr)
84  , last_plan_time_(0.0)
85  , last_simplify_time_(0.0)
86  , max_goal_samples_(0)
87  , max_state_sampling_attempts_(0)
88  , max_goal_sampling_attempts_(0)
89  , max_planning_threads_(0)
90  , max_solution_segment_length_(0.0)
91  , minimum_waypoint_count_(0)
92  , multi_query_planning_enabled_(false) // maintain "old" behavior by default
93  , simplify_solutions_(true)
94  , interpolate_(true)
95  , hybridize_(true)
96 {
97  complete_initial_robot_state_.setToDefaultValues(); // avoid uninitialized memory
99 
100  constraints_library_ = std::make_shared<ConstraintsLibrary>(this);
101 }
102 
103 void ompl_interface::ModelBasedPlanningContext::configure(const rclcpp::Node::SharedPtr& node,
104  bool use_constraints_approximations)
105 {
106  loadConstraintApproximations(node);
107  if (!use_constraints_approximations)
108  {
109  setConstraintsApproximations(ConstraintsLibraryPtr());
110  }
111  complete_initial_robot_state_.update();
112  ompl_simple_setup_->getStateSpace()->computeSignature(space_signature_);
113  ompl_simple_setup_->getStateSpace()->setStateSamplerAllocator(
114  [this](const ompl::base::StateSpace* ss) { return allocPathConstrainedSampler(ss); });
115 
116  if (spec_.constrained_state_space_)
117  {
118  // convert the input state to the corresponding OMPL state
119  ompl::base::ScopedState<> ompl_start_state(spec_.constrained_state_space_);
120  spec_.state_space_->copyToOMPLState(ompl_start_state.get(), getCompleteInitialRobotState());
121  ompl_simple_setup_->setStartState(ompl_start_state);
122  ompl_simple_setup_->setStateValidityChecker(std::make_shared<ConstrainedPlanningStateValidityChecker>(this));
123  }
124  else
125  {
126  // convert the input state to the corresponding OMPL state
127  ompl::base::ScopedState<> ompl_start_state(spec_.state_space_);
128  spec_.state_space_->copyToOMPLState(ompl_start_state.get(), getCompleteInitialRobotState());
129  ompl_simple_setup_->setStartState(ompl_start_state);
130  ompl_simple_setup_->setStateValidityChecker(std::make_shared<StateValidityChecker>(this));
131  }
132 
133  if (path_constraints_ && constraints_library_)
134  {
135  const ConstraintApproximationPtr& constraint_approx =
136  constraints_library_->getConstraintApproximation(path_constraints_msg_);
137  if (constraint_approx)
138  {
139  getOMPLStateSpace()->setInterpolationFunction(constraint_approx->getInterpolationFunction());
140  RCLCPP_INFO(LOGGER, "Using precomputed interpolation states");
141  }
142  }
143 
144  useConfig();
145  if (ompl_simple_setup_->getGoal())
146  ompl_simple_setup_->setup();
147 }
148 
150 {
151  if (!spec_.state_space_)
152  {
153  RCLCPP_ERROR(LOGGER, "No state space is configured yet");
154  return;
155  }
156  ob::ProjectionEvaluatorPtr projection_eval = getProjectionEvaluator(peval);
157  if (projection_eval)
158  spec_.state_space_->registerDefaultProjection(projection_eval);
159 }
160 
161 ompl::base::ProjectionEvaluatorPtr
163 {
164  if (peval.find_first_of("link(") == 0 && peval[peval.length() - 1] == ')')
165  {
166  std::string link_name = peval.substr(5, peval.length() - 6);
167  if (getRobotModel()->hasLinkModel(link_name))
168  {
169  return std::make_shared<ProjectionEvaluatorLinkPose>(this, link_name);
170  }
171  else
172  {
173  RCLCPP_ERROR(LOGGER,
174  "Attempted to set projection evaluator with respect to position of link '%s', "
175  "but that link is not known to the kinematic model.",
176  link_name.c_str());
177  }
178  }
179  else if (peval.find_first_of("joints(") == 0 && peval[peval.length() - 1] == ')')
180  {
181  std::string joints = peval.substr(7, peval.length() - 8);
182  boost::replace_all(joints, ",", " ");
183  std::vector<unsigned int> j;
184  std::stringstream ss(joints);
185  while (ss.good() && !ss.eof())
186  {
187  std::string joint;
188  ss >> joint >> std::ws;
189  if (getJointModelGroup()->hasJointModel(joint))
190  {
191  unsigned int variable_count = getJointModelGroup()->getJointModel(joint)->getVariableCount();
192  if (variable_count > 0)
193  {
194  int idx = getJointModelGroup()->getVariableGroupIndex(joint);
195  for (unsigned int q = 0; q < variable_count; ++q)
196  {
197  j.push_back(idx + q);
198  }
199  }
200  else
201  {
202  RCLCPP_WARN(LOGGER, "%s: Ignoring joint '%s' in projection since it has 0 DOF", name_.c_str(), joint.c_str());
203  }
204  }
205  else
206  {
207  RCLCPP_ERROR(LOGGER,
208  "%s: Attempted to set projection evaluator with respect to value of joint "
209  "'%s', but that joint is not known to the group '%s'.",
210  name_.c_str(), joint.c_str(), getGroupName().c_str());
211  }
212  }
213  if (j.empty())
214  {
215  RCLCPP_ERROR(LOGGER, "%s: No valid joints specified for joint projection", name_.c_str());
216  }
217  else
218  {
219  return std::make_shared<ProjectionEvaluatorJointValue>(this, j);
220  }
221  }
222  else
223  {
224  RCLCPP_ERROR(LOGGER, "Unable to allocate projection evaluator based on description: '%s'", peval.c_str());
225  }
226  return ob::ProjectionEvaluatorPtr();
227 }
228 
229 ompl::base::StateSamplerPtr
230 ompl_interface::ModelBasedPlanningContext::allocPathConstrainedSampler(const ompl::base::StateSpace* state_space) const
231 {
232  if (spec_.state_space_.get() != state_space)
233  {
234  RCLCPP_ERROR(LOGGER, "%s: Attempted to allocate a state sampler for an unknown state space", name_.c_str());
235  return ompl::base::StateSamplerPtr();
236  }
237 
238  RCLCPP_DEBUG(LOGGER, "%s: Allocating a new state sampler (attempts to use path constraints)", name_.c_str());
239 
240  if (path_constraints_)
241  {
242  if (constraints_library_)
243  {
244  const ConstraintApproximationPtr& constraint_approx =
245  constraints_library_->getConstraintApproximation(path_constraints_msg_);
246  if (constraint_approx)
247  {
248  ompl::base::StateSamplerAllocator state_sampler_allocator =
249  constraint_approx->getStateSamplerAllocator(path_constraints_msg_);
250  if (state_sampler_allocator)
251  {
252  ompl::base::StateSamplerPtr state_sampler = state_sampler_allocator(state_space);
253  if (state_sampler)
254  {
255  RCLCPP_INFO(LOGGER,
256  "%s: Using precomputed state sampler (approximated constraint space) for constraint '%s'",
257  name_.c_str(), path_constraints_msg_.name.c_str());
258  return state_sampler;
259  }
260  }
261  }
262  }
263 
264  constraint_samplers::ConstraintSamplerPtr constraint_sampler;
265  if (spec_.constraint_sampler_manager_)
266  {
267  constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
268  path_constraints_->getAllConstraints());
269  }
270 
271  if (constraint_sampler)
272  {
273  RCLCPP_INFO(LOGGER, "%s: Allocating specialized state sampler for state space", name_.c_str());
274  return std::make_shared<ConstrainedSampler>(this, constraint_sampler);
275  }
276  }
277  RCLCPP_DEBUG(LOGGER, "%s: Allocating default state sampler for state space", name_.c_str());
278  return state_space->allocDefaultStateSampler();
279 }
280 
282 {
283  const std::map<std::string, std::string>& config = spec_.config_;
284  if (config.empty())
285  return;
286  std::map<std::string, std::string> cfg = config;
287 
288  // set the distance between waypoints when interpolating and collision checking.
289  auto it = cfg.find("longest_valid_segment_fraction");
290  // If one of the two variables is set.
291  if (it != cfg.end() || max_solution_segment_length_ != 0.0)
292  {
293  // clang-format off
294  double longest_valid_segment_fraction_config = (it != cfg.end())
295  ? moveit::core::toDouble(it->second) // value from config file if there
296  : 0.01; // default value in OMPL.
297  double longest_valid_segment_fraction_final = longest_valid_segment_fraction_config;
298  if (max_solution_segment_length_ > 0.0)
299  {
300  // If this parameter is specified too, take the most conservative of the two variables,
301  // i.e. the one that uses the shorter segment length.
302  longest_valid_segment_fraction_final = std::min(
303  longest_valid_segment_fraction_config,
304  max_solution_segment_length_ / spec_.state_space_->getMaximumExtent()
305  );
306  }
307  // clang-format on
308 
309  // convert to string using no locale
310  cfg["longest_valid_segment_fraction"] = moveit::core::toString(longest_valid_segment_fraction_final);
311  }
312 
313  // set the projection evaluator
314  it = cfg.find("projection_evaluator");
315  if (it != cfg.end())
316  {
317  setProjectionEvaluator(boost::trim_copy(it->second));
318  cfg.erase(it);
319  }
320 
321  if (cfg.empty())
322  {
323  return;
324  }
325 
326  std::string optimizer;
327  ompl::base::OptimizationObjectivePtr objective;
328  it = cfg.find("optimization_objective");
329  if (it != cfg.end())
330  {
331  optimizer = it->second;
332  cfg.erase(it);
333 
334  if (optimizer == "PathLengthOptimizationObjective")
335  {
336  objective =
337  std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
338  }
339  else if (optimizer == "MinimaxObjective")
340  {
341  objective = std::make_shared<ompl::base::MinimaxObjective>(ompl_simple_setup_->getSpaceInformation());
342  }
343  else if (optimizer == "StateCostIntegralObjective")
344  {
345  objective = std::make_shared<ompl::base::StateCostIntegralObjective>(ompl_simple_setup_->getSpaceInformation());
346  }
347  else if (optimizer == "MechanicalWorkOptimizationObjective")
348  {
349  objective =
350  std::make_shared<ompl::base::MechanicalWorkOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
351  }
352  else if (optimizer == "MaximizeMinClearanceObjective")
353  {
354  objective =
355  std::make_shared<ompl::base::MaximizeMinClearanceObjective>(ompl_simple_setup_->getSpaceInformation());
356  }
357  else
358  {
359  RCLCPP_WARN(LOGGER,
360  "Optimization objective %s is invalid or not defined, using PathLengthOptimizationObjective instead",
361  optimizer.c_str());
362  objective =
363  std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
364  }
365 
366  ompl_simple_setup_->setOptimizationObjective(objective);
367  }
368 
369  // Don't clear planner data if multi-query planning is enabled
370  it = cfg.find("multi_query_planning_enabled");
371  if (it != cfg.end())
372  {
373  multi_query_planning_enabled_ = boost::lexical_cast<bool>(it->second);
374  }
375 
376  // check whether the path returned by the planner should be interpolated
377  it = cfg.find("interpolate");
378  if (it != cfg.end())
379  {
380  interpolate_ = boost::lexical_cast<bool>(it->second);
381  cfg.erase(it);
382  }
383 
384  // check whether the path returned by the planner should be simplified
385  it = cfg.find("simplify_solutions");
386  if (it != cfg.end())
387  {
388  simplify_solutions_ = boost::lexical_cast<bool>(it->second);
389  cfg.erase(it);
390  }
391 
392  // check whether solution paths from parallel planning should be hybridized
393  it = cfg.find("hybridize");
394  if (it != cfg.end())
395  {
396  hybridize_ = boost::lexical_cast<bool>(it->second);
397  cfg.erase(it);
398  }
399 
400  // remove the 'type' parameter; the rest are parameters for the planner itself
401  it = cfg.find("type");
402  if (it == cfg.end())
403  {
404  if (name_ != getGroupName())
405  RCLCPP_WARN(LOGGER, "%s: Attribute 'type' not specified in planner configuration", name_.c_str());
406  }
407  else
408  {
409  std::string type = it->second;
410  cfg.erase(it);
411  const std::string planner_name = getGroupName() + "/" + name_;
412  ompl_simple_setup_->setPlannerAllocator(
413  [planner_name, &spec = spec_, allocator = spec_.planner_selector_(type)](
414  const ompl::base::SpaceInformationPtr& si) { return allocator(si, planner_name, spec); });
415  RCLCPP_INFO(LOGGER,
416  "Planner configuration '%s' will use planner '%s'. "
417  "Additional configuration parameters will be set when the planner is constructed.",
418  name_.c_str(), type.c_str());
419  }
420 
421  // call the setParams() after setup(), so we know what the params are
422  ompl_simple_setup_->getSpaceInformation()->setup();
423  ompl_simple_setup_->getSpaceInformation()->params().setParams(cfg, true);
424  // call setup() again for possibly new param values
425  ompl_simple_setup_->getSpaceInformation()->setup();
426 }
427 
428 void ompl_interface::ModelBasedPlanningContext::setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters& wparams)
429 {
430  if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
431  wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
432  wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
433  {
434  RCLCPP_WARN(LOGGER, "It looks like the planning volume was not specified.");
435  }
436 
437  RCLCPP_DEBUG(LOGGER,
438  "%s: Setting planning volume (affects SE2 & SE3 joints only) to x = [%f, %f], y = "
439  "[%f, %f], z = [%f, %f]",
440  name_.c_str(), wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y, wparams.max_corner.y,
441  wparams.min_corner.z, wparams.max_corner.z);
442 
443  spec_.state_space_->setPlanningVolume(wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y,
444  wparams.max_corner.y, wparams.min_corner.z, wparams.max_corner.z);
445 }
446 
448 {
449  ompl::time::point start = ompl::time::now();
450  ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
451  registerTerminationCondition(ptc);
452  ompl_simple_setup_->simplifySolution(ptc);
453  last_simplify_time_ = ompl_simple_setup_->getLastSimplificationTime();
454  unregisterTerminationCondition();
455 }
456 
458 {
459  if (ompl_simple_setup_->haveSolutionPath())
460  {
461  og::PathGeometric& pg = ompl_simple_setup_->getSolutionPath();
462 
463  // Find the number of states that will be in the interpolated solution.
464  // This is what interpolate() does internally.
465  unsigned int eventual_states = 1;
466  std::vector<ompl::base::State*> states = pg.getStates();
467  for (size_t i = 0; i < states.size() - 1; ++i)
468  {
469  eventual_states += ompl_simple_setup_->getStateSpace()->validSegmentCount(states[i], states[i + 1]);
470  }
471 
472  if (eventual_states < minimum_waypoint_count_)
473  {
474  // If that's not enough states, use the minimum amount instead.
475  pg.interpolate(minimum_waypoint_count_);
476  }
477  else
478  {
479  // Interpolate the path to have as the exact states that are checked when validating motions.
480  pg.interpolate();
481  }
482  }
483 }
484 
485 void ompl_interface::ModelBasedPlanningContext::convertPath(const ompl::geometric::PathGeometric& pg,
487 {
488  moveit::core::RobotState ks = complete_initial_robot_state_;
489  for (std::size_t i = 0; i < pg.getStateCount(); ++i)
490  {
491  spec_.state_space_->copyToRobotState(ks, pg.getState(i));
492  traj.addSuffixWayPoint(ks, 0.0);
493  }
494 }
495 
497 {
498  traj.clear();
499  if (ompl_simple_setup_->haveSolutionPath())
500  {
501  convertPath(ompl_simple_setup_->getSolutionPath(), traj);
502  }
503  return ompl_simple_setup_->haveSolutionPath();
504 }
505 
507 {
508  if (ompl_simple_setup_->getStateValidityChecker())
509  {
510  static_cast<StateValidityChecker*>(ompl_simple_setup_->getStateValidityChecker().get())->setVerbose(flag);
511  }
512 }
513 
515 {
516  // ******************* set up the goal representation, based on goal constraints
517 
518  std::vector<ob::GoalPtr> goals;
519  for (kinematic_constraints::KinematicConstraintSetPtr& goal_constraint : goal_constraints_)
520  {
521  constraint_samplers::ConstraintSamplerPtr constraint_sampler;
522  if (spec_.constraint_sampler_manager_)
523  {
524  constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
525  goal_constraint->getAllConstraints());
526  }
527 
528  if (constraint_sampler)
529  {
530  ob::GoalPtr goal = std::make_shared<ConstrainedGoalSampler>(this, goal_constraint, constraint_sampler);
531  goals.push_back(goal);
532  }
533  }
534 
535  if (!goals.empty())
536  {
537  return goals.size() == 1 ? goals[0] : std::make_shared<GoalSampleableRegionMux>(goals);
538  }
539  else
540  {
541  RCLCPP_ERROR(LOGGER, "Unable to construct goal representation");
542  }
543 
544  return ob::GoalPtr();
545 }
546 
547 ompl::base::PlannerTerminationCondition
549  const ompl::time::point& start)
550 {
551  auto it = spec_.config_.find("termination_condition");
552  if (it == spec_.config_.end())
553  {
554  return ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
555  }
556 
557  std::string termination_string = it->second;
558  std::vector<std::string> termination_and_params;
559  boost::split(termination_and_params, termination_string, boost::is_any_of("[ ,]"));
560 
561  if (termination_and_params.empty())
562  {
563  RCLCPP_ERROR(LOGGER, "Termination condition not specified");
564  }
565 
566  // Terminate if a maximum number of iterations is exceeded or a timeout occurs.
567  // The semantics of "iterations" are planner-specific, but typically it corresponds to the number of times
568  // an attempt was made to grow a roadmap/tree.
569  else if (termination_and_params[0] == "Iteration")
570  {
571  if (termination_and_params.size() > 1)
572  {
573  return ob::plannerOrTerminationCondition(
574  ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
575  ob::IterationTerminationCondition(std::stoul(termination_and_params[1])));
576  }
577  else
578  {
579  RCLCPP_ERROR(LOGGER, "Missing argument to Iteration termination condition");
580  }
581  }
582  // Terminate if the cost has converged or a timeout occurs.
583  // Only useful for anytime/optimizing planners.
584  else if (termination_and_params[0] == "CostConvergence")
585  {
586  std::size_t solutions_window = 10u;
587  double epsilon = 0.1;
588  if (termination_and_params.size() > 1)
589  {
590  solutions_window = std::stoul(termination_and_params[1]);
591  if (termination_and_params.size() > 2)
592  {
593  epsilon = moveit::core::toDouble(termination_and_params[2]);
594  }
595  }
596  return ob::plannerOrTerminationCondition(
597  ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
598  ob::CostConvergenceTerminationCondition(ompl_simple_setup_->getProblemDefinition(), solutions_window, epsilon));
599  }
600  // Terminate as soon as an exact solution is found or a timeout occurs.
601  // This modifies the behavior of anytime/optimizing planners to terminate upon discovering
602  // the first feasible solution.
603  else if (termination_and_params[0] == "ExactSolution")
604  {
605  return ob::plannerOrTerminationCondition(
606  ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
607  ob::exactSolnPlannerTerminationCondition(ompl_simple_setup_->getProblemDefinition()));
608  }
609  else
610  {
611  RCLCPP_ERROR(LOGGER, "Unknown planner termination condition");
612  }
613  // return a planner termination condition to suppress compiler warning
614  return ob::plannerAlwaysTerminatingCondition();
615 }
616 
618  const moveit::core::RobotState& complete_initial_robot_state)
619 {
620  complete_initial_robot_state_ = complete_initial_robot_state;
621  complete_initial_robot_state_.update();
622 }
623 
625 {
626  if (!multi_query_planning_enabled_)
627  {
628  ompl_simple_setup_->clear();
629  }
630  else
631  {
632  // For LazyPRM and LazyPRMstar we assume that the environment *could* have changed
633  // This means that we need to reset the validity flags for every node and edge in
634  // the roadmap. For PRM and PRMstar we assume that the environment is static. If
635  // this is not the case, then multi-query planning should not be enabled.
636  auto planner = dynamic_cast<ompl::geometric::LazyPRM*>(ompl_simple_setup_->getPlanner().get());
637  if (planner != nullptr)
638  {
639  planner->clearValidity();
640  }
641  }
642  ompl_simple_setup_->clearStartStates();
643  ompl_simple_setup_->setGoal(ob::GoalPtr());
644  ompl_simple_setup_->setStateValidityChecker(ob::StateValidityCheckerPtr());
645  path_constraints_.reset();
646  goal_constraints_.clear();
647  getOMPLStateSpace()->setInterpolationFunction(InterpolationFunction());
648 }
649 
650 bool ompl_interface::ModelBasedPlanningContext::setPathConstraints(const moveit_msgs::msg::Constraints& path_constraints,
651  moveit_msgs::msg::MoveItErrorCodes* /*error*/)
652 {
653  // ******************* set the path constraints to use
654  path_constraints_ = std::make_shared<kinematic_constraints::KinematicConstraintSet>(getRobotModel());
655  path_constraints_->add(path_constraints, getPlanningScene()->getTransforms());
656  path_constraints_msg_ = path_constraints;
657 
658  return true;
659 }
660 
662  const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
663  const moveit_msgs::msg::Constraints& path_constraints, moveit_msgs::msg::MoveItErrorCodes* error)
664 {
665  // ******************* check if the input is correct
666  goal_constraints_.clear();
667  for (const moveit_msgs::msg::Constraints& goal_constraint : goal_constraints)
668  {
669  moveit_msgs::msg::Constraints constr = kinematic_constraints::mergeConstraints(goal_constraint, path_constraints);
670  kinematic_constraints::KinematicConstraintSetPtr kset(
671  new kinematic_constraints::KinematicConstraintSet(getRobotModel()));
672  kset->add(constr, getPlanningScene()->getTransforms());
673  if (!kset->empty())
674  {
675  goal_constraints_.push_back(kset);
676  }
677  }
678 
679  if (goal_constraints_.empty())
680  {
681  RCLCPP_WARN(LOGGER, "%s: No goal constraints specified. There is no problem to solve.", name_.c_str());
682  if (error)
683  {
684  error->val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
685  }
686  return false;
687  }
688 
689  ob::GoalPtr goal = constructGoal();
690  ompl_simple_setup_->setGoal(goal);
691  return static_cast<bool>(goal);
692 }
693 
694 bool ompl_interface::ModelBasedPlanningContext::benchmark(double timeout, unsigned int count,
695  const std::string& filename)
696 {
697  ompl_benchmark_.clearPlanners();
698  ompl_simple_setup_->setup();
699  ompl_benchmark_.addPlanner(ompl_simple_setup_->getPlanner());
700  ompl_benchmark_.setExperimentName(getRobotModel()->getName() + "_" + getGroupName() + "_" +
701  getPlanningScene()->getName() + "_" + name_);
702 
703  ot::Benchmark::Request req;
704  req.maxTime = timeout;
705  req.runCount = count;
706  req.displayProgress = true;
707  req.saveConsoleOutput = false;
708  ompl_benchmark_.benchmark(req);
709  return filename.empty() ? ompl_benchmark_.saveResultsToFile() : ompl_benchmark_.saveResultsToFile(filename.c_str());
710 }
711 
713 {
714  bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
715  if (gls)
716  {
717  static_cast<ob::GoalLazySamples*>(ompl_simple_setup_->getGoal().get())->startSampling();
718  }
719  else
720  {
721  // we know this is a GoalSampleableMux by elimination
722  static_cast<GoalSampleableRegionMux*>(ompl_simple_setup_->getGoal().get())->startSampling();
723  }
724 }
725 
727 {
728  bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
729  if (gls)
730  {
731  static_cast<ob::GoalLazySamples*>(ompl_simple_setup_->getGoal().get())->stopSampling();
732  }
733  else
734  {
735  // we know this is a GoalSampleableMux by elimination
736  static_cast<GoalSampleableRegionMux*>(ompl_simple_setup_->getGoal().get())->stopSampling();
737  }
738 }
739 
741 {
742  // clear previously computed solutions
743  ompl_simple_setup_->getProblemDefinition()->clearSolutionPaths();
744  const ob::PlannerPtr planner = ompl_simple_setup_->getPlanner();
745  if (planner && !multi_query_planning_enabled_)
746  {
747  planner->clear();
748  }
749  startSampling();
750  ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
751 }
752 
754 {
755  stopSampling();
756  int v = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getValidMotionCount();
757  int iv = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getInvalidMotionCount();
758  RCLCPP_DEBUG(LOGGER, "There were %d valid motions and %d invalid motions.", v, iv);
759 
760  // Debug OMPL setup and solution
761  std::stringstream debug_out;
762  ompl_simple_setup_->print(debug_out);
763  RCLCPP_DEBUG(LOGGER, "%s", rclcpp::get_c_string(debug_out.str()));
764 }
765 
767 {
768  res.error_code = solve(request_.allowed_planning_time, request_.num_planning_attempts);
769  if (res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
770  {
771  double ptime = getLastPlanTime();
772  if (simplify_solutions_)
773  {
774  simplifySolution(request_.allowed_planning_time - ptime);
775  ptime += getLastSimplifyTime();
776  }
777 
778  if (interpolate_)
779  {
780  interpolateSolution();
781  }
782 
783  // fill the response
784  RCLCPP_DEBUG(LOGGER, "%s: Returning successful solution with %lu states", getName().c_str(),
785  getOMPLSimpleSetup()->getSolutionPath().getStateCount());
786 
787  res.trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
788  getSolutionPath(*res.trajectory);
789  res.planning_time = ptime;
790  return true;
791  }
792  else
793  {
794  RCLCPP_INFO(LOGGER, "Unable to solve the planning problem");
795  return false;
796  }
797 }
798 
800 {
801  moveit_msgs::msg::MoveItErrorCodes moveit_result =
802  solve(request_.allowed_planning_time, request_.num_planning_attempts);
803  if (moveit_result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
804  {
805  res.trajectory.reserve(3);
806 
807  // add info about planned solution
808  double ptime = getLastPlanTime();
809  res.processing_time.push_back(ptime);
810  res.description.emplace_back("plan");
811  res.trajectory.resize(res.trajectory.size() + 1);
812  res.trajectory.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
813  getSolutionPath(*res.trajectory.back());
814 
815  // simplify solution if time remains
816  if (simplify_solutions_)
817  {
818  simplifySolution(request_.allowed_planning_time - ptime);
819  res.processing_time.push_back(getLastSimplifyTime());
820  res.description.emplace_back("simplify");
821  res.trajectory.resize(res.trajectory.size() + 1);
822  res.trajectory.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
823  getSolutionPath(*res.trajectory.back());
824  }
825 
826  if (interpolate_)
827  {
828  ompl::time::point start_interpolate = ompl::time::now();
829  interpolateSolution();
830  res.processing_time.push_back(ompl::time::seconds(ompl::time::now() - start_interpolate));
831  res.description.emplace_back("interpolate");
832  res.trajectory.resize(res.trajectory.size() + 1);
833  res.trajectory.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
834  getSolutionPath(*res.trajectory.back());
835  }
836 
837  RCLCPP_DEBUG(LOGGER, "%s: Returning successful solution with %lu states", getName().c_str(),
838  getOMPLSimpleSetup()->getSolutionPath().getStateCount());
839  res.error_code.val = moveit_result.val;
840  return true;
841  }
842  else
843  {
844  RCLCPP_INFO(LOGGER, "Unable to solve the planning problem");
845  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
846  return false;
847  }
848 }
849 
850 const moveit_msgs::msg::MoveItErrorCodes ompl_interface::ModelBasedPlanningContext::solve(double timeout,
851  unsigned int count)
852 {
853  ompl::time::point start = ompl::time::now();
854  preSolve();
855 
856  moveit_msgs::msg::MoveItErrorCodes result;
857  result.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
858  if (count <= 1 || multi_query_planning_enabled_) // multi-query planners should always run in single instances
859  {
860  RCLCPP_DEBUG(LOGGER, "%s: Solving the planning problem once...", name_.c_str());
861  ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
862  registerTerminationCondition(ptc);
863  std::ignore = ompl_simple_setup_->solve(ptc);
864  last_plan_time_ = ompl_simple_setup_->getLastPlanComputationTime();
865  unregisterTerminationCondition();
866  // fill the result status code
867  result.val = logPlannerStatus(ompl_simple_setup_);
868  }
869  else
870  {
871  RCLCPP_DEBUG(LOGGER, "%s: Solving the planning problem %u times...", name_.c_str(), count);
872  ompl_parallel_plan_.clearHybridizationPaths();
873  if (count <= max_planning_threads_)
874  {
875  ompl_parallel_plan_.clearPlanners();
876  if (ompl_simple_setup_->getPlannerAllocator())
877  {
878  for (unsigned int i = 0; i < count; ++i)
879  {
880  ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
881  }
882  }
883  else
884  {
885  for (unsigned int i = 0; i < count; ++i)
886  {
887  ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
888  }
889  }
890 
891  ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
892  registerTerminationCondition(ptc);
893  if (ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION)
894  {
895  result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
896  }
897  last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
898  unregisterTerminationCondition();
899  }
900  else
901  {
902  ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
903  registerTerminationCondition(ptc);
904  int n = count / max_planning_threads_;
905  result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
906  for (int i = 0; i < n && !ptc(); ++i)
907  {
908  ompl_parallel_plan_.clearPlanners();
909  if (ompl_simple_setup_->getPlannerAllocator())
910  {
911  for (unsigned int i = 0; i < max_planning_threads_; ++i)
912  {
913  ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
914  }
915  }
916  else
917  {
918  for (unsigned int i = 0; i < max_planning_threads_; ++i)
919  {
920  ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
921  }
922  }
923 
924  bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
925  // Was this latest call successful too?
926  result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && r) ?
927  moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
928  moveit_msgs::msg::MoveItErrorCodes::FAILURE;
929  }
930  n = count % max_planning_threads_;
931  if (n && !ptc())
932  {
933  ompl_parallel_plan_.clearPlanners();
934  if (ompl_simple_setup_->getPlannerAllocator())
935  {
936  for (int i = 0; i < n; ++i)
937  {
938  ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
939  }
940  }
941  else
942  {
943  for (int i = 0; i < n; ++i)
944  {
945  ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
946  }
947  }
948 
949  bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
950  // Was this latest call successful too?
951  result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && r) ?
952  moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
953  moveit_msgs::msg::MoveItErrorCodes::FAILURE;
954  }
955  last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
956  unregisterTerminationCondition();
957  }
958  }
959 
960  postSolve();
961  return result;
962 }
963 
964 void ompl_interface::ModelBasedPlanningContext::registerTerminationCondition(const ob::PlannerTerminationCondition& ptc)
965 {
966  std::unique_lock<std::mutex> slock(ptc_lock_);
967  ptc_ = &ptc;
968 }
969 
971 {
972  std::unique_lock<std::mutex> slock(ptc_lock_);
973  ptc_ = nullptr;
974 }
975 
976 int32_t ompl_interface::ModelBasedPlanningContext::logPlannerStatus(const og::SimpleSetupPtr& ompl_simple_setup)
977 {
978  auto result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
979  const ompl::base::PlannerStatus ompl_status = ompl_simple_setup->getLastPlannerStatus();
980  switch (ompl::base::PlannerStatus::StatusType(ompl_status))
981  {
982  case ompl::base::PlannerStatus::UNKNOWN:
983  RCLCPP_WARN(LOGGER, "Motion planning failed for an unknown reason");
984  result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
985  break;
986  case ompl::base::PlannerStatus::INVALID_START:
987  RCLCPP_WARN(LOGGER, "Invalid start state");
988  result = moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID;
989  break;
990  case ompl::base::PlannerStatus::INVALID_GOAL:
991  RCLCPP_WARN(LOGGER, "Invalid goal state");
992  result = moveit_msgs::msg::MoveItErrorCodes::GOAL_STATE_INVALID;
993  break;
994  case ompl::base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE:
995  RCLCPP_WARN(LOGGER, "Unrecognized goal type");
996  result = moveit_msgs::msg::MoveItErrorCodes::UNRECOGNIZED_GOAL_TYPE;
997  break;
998  case ompl::base::PlannerStatus::TIMEOUT:
999  RCLCPP_WARN(LOGGER, "Timed out: %.1fs ≥ %.1fs", ompl_simple_setup->getLastPlanComputationTime(),
1000  request_.allowed_planning_time);
1001  result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
1002  break;
1003  case ompl::base::PlannerStatus::APPROXIMATE_SOLUTION:
1004  // timeout is a common reason for APPROXIMATE_SOLUTION
1005  if (ompl_simple_setup->getLastPlanComputationTime() > request_.allowed_planning_time)
1006  {
1007  RCLCPP_WARN(LOGGER, "Planning timed out: %.1fs ≥ %.1fs", ompl_simple_setup->getLastPlanComputationTime(),
1008  request_.allowed_planning_time);
1009  result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
1010  }
1011  else
1012  {
1013  RCLCPP_WARN(LOGGER, "Solution is approximate");
1014  result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
1015  }
1016  break;
1017  case ompl::base::PlannerStatus::EXACT_SOLUTION:
1018  result = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1019  break;
1020  case ompl::base::PlannerStatus::CRASH:
1021  RCLCPP_WARN(LOGGER, "OMPL crashed!");
1022  result = moveit_msgs::msg::MoveItErrorCodes::CRASH;
1023  break;
1024  case ompl::base::PlannerStatus::ABORT:
1025  RCLCPP_WARN(LOGGER, "OMPL was aborted");
1026  result = moveit_msgs::msg::MoveItErrorCodes::ABORT;
1027  break;
1028  default:
1029  // This should never happen
1030  RCLCPP_WARN(LOGGER, "Unexpected PlannerStatus code from OMPL.");
1031  result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
1032  }
1033  return result;
1034 }
1035 
1037 {
1038  std::unique_lock<std::mutex> slock(ptc_lock_);
1039  if (ptc_)
1040  {
1041  ptc_->terminate();
1042  }
1043  return true;
1044 }
1045 
1047 {
1048  std::string constraint_path;
1049  if (node->get_parameter("constraint_approximations_path", constraint_path))
1050  {
1051  constraints_library_->saveConstraintApproximations(constraint_path);
1052  return true;
1053  }
1054  RCLCPP_WARN(LOGGER, "ROS param 'constraint_approximations' not found. Unable to save constraint approximations");
1055  return false;
1056 }
1057 
1059 {
1060  std::string constraint_path;
1061  if (node->get_parameter("constraint_approximations_path", constraint_path))
1062  {
1063  constraints_library_->loadConstraintApproximations(constraint_path);
1064  std::stringstream ss;
1065  constraints_library_->printConstraintApproximations(ss);
1066  RCLCPP_INFO_STREAM(LOGGER, ss.str());
1067  return true;
1068  }
1069  return false;
1070 }
A class that contains many different constraints, and can check RobotState *versus the full set....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
int32_t logPlannerStatus(const og::SimpleSetupPtr &ompl_simple_setup)
Convert OMPL PlannerStatus to moveit_msgs::msg::MoveItErrorCode.
virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string &peval) const
void clear() override
Clear the data structures used by the planner.
bool getSolutionPath(robot_trajectory::RobotTrajectory &traj) const
void registerTerminationCondition(const ob::PlannerTerminationCondition &ptc)
bool loadConstraintApproximations(const rclcpp::Node::SharedPtr &node)
Look up param server 'constraint_approximations' and use its value as the path to load constraint app...
bool setPathConstraints(const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
ModelBasedPlanningContext(const std::string &name, const ModelBasedPlanningContextSpecification &spec)
virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition(double timeout, const ompl::time::point &start)
bool saveConstraintApproximations(const rclcpp::Node::SharedPtr &node)
Look up param server 'constraint_approximations' and use its value as the path to save constraint app...
virtual void configure(const rclcpp::Node::SharedPtr &node, bool use_constraints_approximations)
Configure ompl_simple_setup_ and optionally the constraints_library_.
bool setGoalConstraints(const std::vector< moveit_msgs::msg::Constraints > &goal_constraints, const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
void convertPath(const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
void setCompleteInitialState(const moveit::core::RobotState &complete_initial_robot_state)
void setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters &wparams)
bool benchmark(double timeout, unsigned int count, const std::string &filename="")
bool terminate() override
If solve() is running, terminate the computation. Return false if termination not possible....
virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace *ss) const
bool solve(planning_interface::MotionPlanResponse &res) override
Solve the motion planning problem and store the result in res. This function should not clear data st...
An interface for a OMPL state validity checker.
Maintain a sequence of waypoints and the time durations between these waypoints.
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
locale-agnostic conversion functions from floating point numbers to strings
moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints &first, const moveit_msgs::msg::Constraints &second)
Merge two sets of constraints into one.
Definition: utils.cpp:58
double toDouble(const std::string &s)
Converts a std::string to double using the classic C locale.
std::string toString(double d)
Convert a double to std::string using the classic C locale.
The MoveIt interface to OMPL.
std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
This namespace includes the base class for MoveIt planners.
name
Definition: setup.py:7
moveit_msgs::msg::MoveItErrorCodes error_code
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory