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


ompl
Author(s): Ioan Sucan
autogenerated on Tue Dec 24 2024 03:28:09