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> 
   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> 
   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> 
   72 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.ompl_planning.model_based_planning_context");
 
   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())
 
   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)  
 
   93   , simplify_solutions_(true)
 
  104                                                           bool use_constraints_approximations)
 
  106   loadConstraintApproximations(node);
 
  107   if (!use_constraints_approximations)
 
  109     setConstraintsApproximations(ConstraintsLibraryPtr());
 
  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); });
 
  116   if (spec_.constrained_state_space_)
 
  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));
 
  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));
 
  133   if (path_constraints_ && constraints_library_)
 
  135     const ConstraintApproximationPtr& constraint_approx =
 
  136         constraints_library_->getConstraintApproximation(path_constraints_msg_);
 
  137     if (constraint_approx)
 
  139       getOMPLStateSpace()->setInterpolationFunction(constraint_approx->getInterpolationFunction());
 
  140       RCLCPP_INFO(LOGGER, 
"Using precomputed interpolation states");
 
  145   if (ompl_simple_setup_->getGoal())
 
  146     ompl_simple_setup_->setup();
 
  151   if (!spec_.state_space_)
 
  153     RCLCPP_ERROR(LOGGER, 
"No state space is configured yet");
 
  156   ob::ProjectionEvaluatorPtr projection_eval = getProjectionEvaluator(peval);
 
  158     spec_.state_space_->registerDefaultProjection(projection_eval);
 
  161 ompl::base::ProjectionEvaluatorPtr
 
  164   if (peval.find_first_of(
"link(") == 0 && peval[peval.length() - 1] == 
')')
 
  166     std::string link_name = peval.substr(5, peval.length() - 6);
 
  167     if (getRobotModel()->hasLinkModel(link_name))
 
  168       return std::make_shared<ProjectionEvaluatorLinkPose>(
this, link_name);
 
  171                    "Attempted to set projection evaluator with respect to position of link '%s', " 
  172                    "but that link is not known to the kinematic model.",
 
  175   else if (peval.find_first_of(
"joints(") == 0 && peval[peval.length() - 1] == 
')')
 
  177     std::string joints = peval.substr(7, peval.length() - 8);
 
  178     boost::replace_all(joints, 
",", 
" ");
 
  179     std::vector<unsigned int> j;
 
  180     std::stringstream ss(joints);
 
  181     while (ss.good() && !ss.eof())
 
  184       ss >> joint >> std::ws;
 
  185       if (getJointModelGroup()->hasJointModel(joint))
 
  187         unsigned int variable_count = getJointModelGroup()->getJointModel(joint)->getVariableCount();
 
  188         if (variable_count > 0)
 
  190           int idx = getJointModelGroup()->getVariableGroupIndex(joint);
 
  191           for (
unsigned int q = 0; q < variable_count; ++q)
 
  193             j.push_back(idx + q);
 
  198           RCLCPP_WARN(LOGGER, 
"%s: Ignoring joint '%s' in projection since it has 0 DOF", name_.c_str(), joint.c_str());
 
  204                      "%s: Attempted to set projection evaluator with respect to value of joint " 
  205                      "'%s', but that joint is not known to the group '%s'.",
 
  206                      name_.c_str(), joint.c_str(), getGroupName().c_str());
 
  211       RCLCPP_ERROR(LOGGER, 
"%s: No valid joints specified for joint projection", name_.c_str());
 
  215       return std::make_shared<ProjectionEvaluatorJointValue>(
this, j);
 
  220     RCLCPP_ERROR(LOGGER, 
"Unable to allocate projection evaluator based on description: '%s'", peval.c_str());
 
  222   return ob::ProjectionEvaluatorPtr();
 
  225 ompl::base::StateSamplerPtr
 
  228   if (spec_.state_space_.get() != state_space)
 
  230     RCLCPP_ERROR(LOGGER, 
"%s: Attempted to allocate a state sampler for an unknown state space", name_.c_str());
 
  231     return ompl::base::StateSamplerPtr();
 
  234   RCLCPP_DEBUG(LOGGER, 
"%s: Allocating a new state sampler (attempts to use path constraints)", name_.c_str());
 
  236   if (path_constraints_)
 
  238     if (constraints_library_)
 
  240       const ConstraintApproximationPtr& constraint_approx =
 
  241           constraints_library_->getConstraintApproximation(path_constraints_msg_);
 
  242       if (constraint_approx)
 
  244         ompl::base::StateSamplerAllocator state_sampler_allocator =
 
  245             constraint_approx->getStateSamplerAllocator(path_constraints_msg_);
 
  246         if (state_sampler_allocator)
 
  248           ompl::base::StateSamplerPtr state_sampler = state_sampler_allocator(state_space);
 
  252                         "%s: Using precomputed state sampler (approximated constraint space) for constraint '%s'",
 
  253                         name_.c_str(), path_constraints_msg_.name.c_str());
 
  254             return state_sampler;
 
  260     constraint_samplers::ConstraintSamplerPtr constraint_sampler;
 
  261     if (spec_.constraint_sampler_manager_)
 
  262       constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
 
  263                                                                             path_constraints_->getAllConstraints());
 
  265     if (constraint_sampler)
 
  267       RCLCPP_INFO(LOGGER, 
"%s: Allocating specialized state sampler for state space", name_.c_str());
 
  268       return std::make_shared<ConstrainedSampler>(
this, constraint_sampler);
 
  271   RCLCPP_DEBUG(LOGGER, 
"%s: Allocating default state sampler for state space", name_.c_str());
 
  272   return state_space->allocDefaultStateSampler();
 
  277   const std::map<std::string, std::string>& config = spec_.config_;
 
  280   std::map<std::string, std::string> cfg = config;
 
  283   auto it = cfg.find(
"longest_valid_segment_fraction");
 
  285   if (it != cfg.end() || max_solution_segment_length_ != 0.0)
 
  288     double longest_valid_segment_fraction_config = (it != cfg.end())
 
  291     double longest_valid_segment_fraction_final = longest_valid_segment_fraction_config;
 
  292     if (max_solution_segment_length_ > 0.0)
 
  296       longest_valid_segment_fraction_final = std::min(
 
  297           longest_valid_segment_fraction_config,
 
  298           max_solution_segment_length_ / spec_.state_space_->getMaximumExtent()
 
  308   it = cfg.find(
"projection_evaluator");
 
  311     setProjectionEvaluator(boost::trim_copy(it->second));
 
  320   std::string optimizer;
 
  321   ompl::base::OptimizationObjectivePtr objective;
 
  322   it = cfg.find(
"optimization_objective");
 
  325     optimizer = it->second;
 
  328     if (optimizer == 
"PathLengthOptimizationObjective")
 
  331           std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
 
  333     else if (optimizer == 
"MinimaxObjective")
 
  335       objective = std::make_shared<ompl::base::MinimaxObjective>(ompl_simple_setup_->getSpaceInformation());
 
  337     else if (optimizer == 
"StateCostIntegralObjective")
 
  339       objective = std::make_shared<ompl::base::StateCostIntegralObjective>(ompl_simple_setup_->getSpaceInformation());
 
  341     else if (optimizer == 
"MechanicalWorkOptimizationObjective")
 
  344           std::make_shared<ompl::base::MechanicalWorkOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
 
  346     else if (optimizer == 
"MaximizeMinClearanceObjective")
 
  349           std::make_shared<ompl::base::MaximizeMinClearanceObjective>(ompl_simple_setup_->getSpaceInformation());
 
  354           std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
 
  357     ompl_simple_setup_->setOptimizationObjective(objective);
 
  361   it = cfg.find(
"multi_query_planning_enabled");
 
  364     multi_query_planning_enabled_ = boost::lexical_cast<bool>(it->second);
 
  368   it = cfg.find(
"interpolate");
 
  371     interpolate_ = boost::lexical_cast<bool>(it->second);
 
  376   it = cfg.find(
"simplify_solutions");
 
  379     simplify_solutions_ = boost::lexical_cast<bool>(it->second);
 
  384   it = cfg.find(
"hybridize");
 
  387     hybridize_ = boost::lexical_cast<bool>(it->second);
 
  392   it = cfg.find(
"type");
 
  395     if (name_ != getGroupName())
 
  396       RCLCPP_WARN(LOGGER, 
"%s: Attribute 'type' not specified in planner configuration", name_.c_str());
 
  400     std::string 
type = it->second;
 
  402     const std::string planner_name = getGroupName() + 
"/" + name_;
 
  403     ompl_simple_setup_->setPlannerAllocator(
 
  404         [planner_name, &spec = this->spec_, allocator = spec_.planner_selector_(
type)](
 
  405             const ompl::base::SpaceInformationPtr& si) { return allocator(si, planner_name, spec); });
 
  407                 "Planner configuration '%s' will use planner '%s'. " 
  408                 "Additional configuration parameters will be set when the planner is constructed.",
 
  409                 name_.c_str(), 
type.c_str());
 
  413   ompl_simple_setup_->getSpaceInformation()->setup();
 
  414   ompl_simple_setup_->getSpaceInformation()->params().setParams(cfg, 
true);
 
  416   ompl_simple_setup_->getSpaceInformation()->setup();
 
  421   if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
 
  422       wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
 
  423       wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
 
  425     RCLCPP_WARN(LOGGER, 
"It looks like the planning volume was not specified.");
 
  429                "%s: Setting planning volume (affects SE2 & SE3 joints only) to x = [%f, %f], y = " 
  430                "[%f, %f], z = [%f, %f]",
 
  431                name_.c_str(), wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y, wparams.max_corner.y,
 
  432                wparams.min_corner.z, wparams.max_corner.z);
 
  434   spec_.state_space_->setPlanningVolume(wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y,
 
  435                                         wparams.max_corner.y, wparams.min_corner.z, wparams.max_corner.z);
 
  440   ompl::time::point start = ompl::time::now();
 
  441   ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
 
  442   registerTerminationCondition(ptc);
 
  443   ompl_simple_setup_->simplifySolution(ptc);
 
  444   last_simplify_time_ = ompl_simple_setup_->getLastSimplificationTime();
 
  445   unregisterTerminationCondition();
 
  450   if (ompl_simple_setup_->haveSolutionPath())
 
  452     og::PathGeometric& pg = ompl_simple_setup_->getSolutionPath();
 
  456     unsigned int eventual_states = 1;
 
  457     std::vector<ompl::base::State*> states = pg.getStates();
 
  458     for (
size_t i = 0; i < states.size() - 1; ++i)
 
  460       eventual_states += ompl_simple_setup_->getStateSpace()->validSegmentCount(states[i], states[i + 1]);
 
  463     if (eventual_states < minimum_waypoint_count_)
 
  466       pg.interpolate(minimum_waypoint_count_);
 
  480   for (std::size_t i = 0; i < pg.getStateCount(); ++i)
 
  482     spec_.state_space_->copyToRobotState(ks, pg.getState(i));
 
  490   if (ompl_simple_setup_->haveSolutionPath())
 
  492     convertPath(ompl_simple_setup_->getSolutionPath(), traj);
 
  494   return ompl_simple_setup_->haveSolutionPath();
 
  499   if (ompl_simple_setup_->getStateValidityChecker())
 
  501     static_cast<StateValidityChecker*
>(ompl_simple_setup_->getStateValidityChecker().get())->setVerbose(flag);
 
  509   std::vector<ob::GoalPtr> goals;
 
  510   for (kinematic_constraints::KinematicConstraintSetPtr& goal_constraint : goal_constraints_)
 
  512     constraint_samplers::ConstraintSamplerPtr constraint_sampler;
 
  513     if (spec_.constraint_sampler_manager_)
 
  515       constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
 
  516                                                                             goal_constraint->getAllConstraints());
 
  519     if (constraint_sampler)
 
  521       ob::GoalPtr goal = std::make_shared<ConstrainedGoalSampler>(
this, goal_constraint, constraint_sampler);
 
  522       goals.push_back(goal);
 
  528     return goals.size() == 1 ? goals[0] : std::make_shared<GoalSampleableRegionMux>(goals);
 
  532     RCLCPP_ERROR(LOGGER, 
"Unable to construct goal representation");
 
  535   return ob::GoalPtr();
 
  538 ompl::base::PlannerTerminationCondition
 
  540                                                                                 const ompl::time::point& start)
 
  542   auto it = spec_.config_.find(
"termination_condition");
 
  543   if (it == spec_.config_.end())
 
  545     return ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
 
  548   std::string termination_string = it->second;
 
  549   std::vector<std::string> termination_and_params;
 
  550   boost::split(termination_and_params, termination_string, boost::is_any_of(
"[ ,]"));
 
  552   if (termination_and_params.empty())
 
  554     RCLCPP_ERROR(LOGGER, 
"Termination condition not specified");
 
  560   else if (termination_and_params[0] == 
"Iteration")
 
  562     if (termination_and_params.size() > 1)
 
  564       return ob::plannerOrTerminationCondition(
 
  565           ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
 
  566           ob::IterationTerminationCondition(std::stoul(termination_and_params[1])));
 
  570       RCLCPP_ERROR(LOGGER, 
"Missing argument to Iteration termination condition");
 
  574 #if OMPL_VERSION_VALUE >= 1005000 
  577   else if (termination_and_params[0] == 
"CostConvergence")
 
  579     std::size_t solutions_window = 10u;
 
  580     double epsilon = 0.1;
 
  581     if (termination_and_params.size() > 1)
 
  583       solutions_window = std::stoul(termination_and_params[1]);
 
  584       if (termination_and_params.size() > 2)
 
  589     return ob::plannerOrTerminationCondition(
 
  590         ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
 
  591         ob::CostConvergenceTerminationCondition(ompl_simple_setup_->getProblemDefinition(), solutions_window, epsilon));
 
  597   else if (termination_and_params[0] == 
"ExactSolution")
 
  599     return ob::plannerOrTerminationCondition(
 
  600         ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
 
  601         ob::exactSolnPlannerTerminationCondition(ompl_simple_setup_->getProblemDefinition()));
 
  605     RCLCPP_ERROR(LOGGER, 
"Unknown planner termination condition");
 
  608   return ob::plannerAlwaysTerminatingCondition();
 
  614   complete_initial_robot_state_ = complete_initial_robot_state;
 
  615   complete_initial_robot_state_.
update();
 
  620   if (!multi_query_planning_enabled_)
 
  622     ompl_simple_setup_->clear();
 
  625 #if OMPL_VERSION_VALUE >= 1005000 
  632     auto planner = 
dynamic_cast<ompl::geometric::LazyPRM*
>(ompl_simple_setup_->getPlanner().get());
 
  633     if (planner != 
nullptr)
 
  635       planner->clearValidity();
 
  639   ompl_simple_setup_->clearStartStates();
 
  640   ompl_simple_setup_->setGoal(ob::GoalPtr());
 
  641   ompl_simple_setup_->setStateValidityChecker(ob::StateValidityCheckerPtr());
 
  642   path_constraints_.reset();
 
  643   goal_constraints_.clear();
 
  648                                                                    moveit_msgs::msg::MoveItErrorCodes* )
 
  651   path_constraints_ = std::make_shared<kinematic_constraints::KinematicConstraintSet>(getRobotModel());
 
  652   path_constraints_->add(
path_constraints, getPlanningScene()->getTransforms());
 
  659     const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
 
  660     const moveit_msgs::msg::Constraints& 
path_constraints, moveit_msgs::msg::MoveItErrorCodes* error)
 
  663   goal_constraints_.clear();
 
  664   for (
const moveit_msgs::msg::Constraints& goal_constraint : goal_constraints)
 
  667     kinematic_constraints::KinematicConstraintSetPtr kset(
 
  669     kset->add(constr, getPlanningScene()->getTransforms());
 
  672       goal_constraints_.push_back(kset);
 
  676   if (goal_constraints_.empty())
 
  678     RCLCPP_WARN(LOGGER, 
"%s: No goal constraints specified. There is no problem to solve.", name_.c_str());
 
  681       error->val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
 
  686   ob::GoalPtr goal = constructGoal();
 
  687   ompl_simple_setup_->setGoal(goal);
 
  688   return static_cast<bool>(goal);
 
  692                                                           const std::string& filename)
 
  694   ompl_benchmark_.clearPlanners();
 
  695   ompl_simple_setup_->setup();
 
  696   ompl_benchmark_.addPlanner(ompl_simple_setup_->getPlanner());
 
  697   ompl_benchmark_.setExperimentName(getRobotModel()->getName() + 
"_" + getGroupName() + 
"_" +
 
  698                                     getPlanningScene()->getName() + 
"_" + name_);
 
  700   ot::Benchmark::Request req;
 
  701   req.maxTime = timeout;
 
  702   req.runCount = count;
 
  703   req.displayProgress = 
true;
 
  704   req.saveConsoleOutput = 
false;
 
  705   ompl_benchmark_.benchmark(req);
 
  706   return filename.empty() ? ompl_benchmark_.saveResultsToFile() : ompl_benchmark_.saveResultsToFile(filename.c_str());
 
  711   bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
 
  714     static_cast<ob::GoalLazySamples*
>(ompl_simple_setup_->getGoal().get())->startSampling();
 
  725   bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
 
  728     static_cast<ob::GoalLazySamples*
>(ompl_simple_setup_->getGoal().get())->stopSampling();
 
  740   ompl_simple_setup_->getProblemDefinition()->clearSolutionPaths();
 
  741   const ob::PlannerPtr planner = ompl_simple_setup_->getPlanner();
 
  742   if (planner && !multi_query_planning_enabled_)
 
  747   ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
 
  753   int v = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getValidMotionCount();
 
  754   int iv = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getInvalidMotionCount();
 
  755   RCLCPP_DEBUG(LOGGER, 
"There were %d valid motions and %d invalid motions.", v, iv);
 
  758   RCLCPP_DEBUG(LOGGER, 
"%s",
 
  760                  std::stringstream debug_out;
 
  761                  ompl_simple_setup_->print(debug_out);
 
  762                  return debug_out.str();
 
  769   res.
error_code_ = solve(request_.allowed_planning_time, request_.num_planning_attempts);
 
  770   if (res.
error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
 
  772     double ptime = getLastPlanTime();
 
  773     if (simplify_solutions_)
 
  775       simplifySolution(request_.allowed_planning_time - ptime);
 
  776       ptime += getLastSimplifyTime();
 
  781       interpolateSolution();
 
  785     RCLCPP_DEBUG(LOGGER, 
"%s: Returning successful solution with %lu states", getName().c_str(),
 
  786                  getOMPLSimpleSetup()->getSolutionPath().getStateCount());
 
  788     res.
trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
 
  795     RCLCPP_INFO(LOGGER, 
"Unable to solve the planning problem");
 
  802   moveit_msgs::msg::MoveItErrorCodes moveit_result =
 
  803       solve(request_.allowed_planning_time, request_.num_planning_attempts);
 
  804   if (moveit_result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
 
  809     double ptime = getLastPlanTime();
 
  813     res.
trajectory_.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
 
  817     if (simplify_solutions_)
 
  819       simplifySolution(request_.allowed_planning_time - ptime);
 
  823       res.
trajectory_.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
 
  829       ompl::time::point start_interpolate = ompl::time::now();
 
  830       interpolateSolution();
 
  831       res.
processing_time_.push_back(ompl::time::seconds(ompl::time::now() - start_interpolate));
 
  834       res.
trajectory_.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
 
  838     RCLCPP_DEBUG(LOGGER, 
"%s: Returning successful solution with %lu states", getName().c_str(),
 
  839                  getOMPLSimpleSetup()->getSolutionPath().getStateCount());
 
  845     RCLCPP_INFO(LOGGER, 
"Unable to solve the planning problem");
 
  846     res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
 
  854   ompl::time::point start = ompl::time::now();
 
  857   moveit_msgs::msg::MoveItErrorCodes result;
 
  858   result.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
 
  859   if (count <= 1 || multi_query_planning_enabled_)  
 
  861     RCLCPP_DEBUG(LOGGER, 
"%s: Solving the planning problem once...", name_.c_str());
 
  862     ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
 
  863     registerTerminationCondition(ptc);
 
  864     std::ignore = ompl_simple_setup_->solve(ptc);
 
  865     last_plan_time_ = ompl_simple_setup_->getLastPlanComputationTime();
 
  866     unregisterTerminationCondition();
 
  868     result.val = logPlannerStatus(ompl_simple_setup_);
 
  872     RCLCPP_DEBUG(LOGGER, 
"%s: Solving the planning problem %u times...", name_.c_str(), count);
 
  873     ompl_parallel_plan_.clearHybridizationPaths();
 
  874     if (count <= max_planning_threads_)
 
  876       ompl_parallel_plan_.clearPlanners();
 
  877       if (ompl_simple_setup_->getPlannerAllocator())
 
  878         for (
unsigned int i = 0; i < count; ++i)
 
  880           ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
 
  884         for (
unsigned int i = 0; i < count; ++i)
 
  886           ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
 
  890       ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
 
  891       registerTerminationCondition(ptc);
 
  892       if (ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION)
 
  894         result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
  896       last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
 
  897       unregisterTerminationCondition();
 
  901       ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
 
  902       registerTerminationCondition(ptc);
 
  903       int n = count / max_planning_threads_;
 
  904       result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
  905       for (
int i = 0; i < n && !ptc(); ++i)
 
  907         ompl_parallel_plan_.clearPlanners();
 
  908         if (ompl_simple_setup_->getPlannerAllocator())
 
  910           for (
unsigned int i = 0; i < max_planning_threads_; ++i)
 
  912             ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
 
  917           for (
unsigned int i = 0; i < max_planning_threads_; ++i)
 
  919             ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
 
  923         bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
 
  925         result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && 
r) ?
 
  926                          moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
 
  927                          moveit_msgs::msg::MoveItErrorCodes::FAILURE;
 
  929       n = count % max_planning_threads_;
 
  932         ompl_parallel_plan_.clearPlanners();
 
  933         if (ompl_simple_setup_->getPlannerAllocator())
 
  935           for (
int i = 0; i < n; ++i)
 
  937             ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
 
  942           for (
int i = 0; i < n; ++i)
 
  944             ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
 
  948         bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
 
  950         result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && 
r) ?
 
  951                          moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
 
  952                          moveit_msgs::msg::MoveItErrorCodes::FAILURE;
 
  954       last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
 
  955       unregisterTerminationCondition();
 
  965   std::unique_lock<std::mutex> slock(ptc_lock_);
 
  971   std::unique_lock<std::mutex> slock(ptc_lock_);
 
  977   auto result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
 
  978   const ompl::base::PlannerStatus ompl_status = ompl_simple_setup->getLastPlannerStatus();
 
  979   switch (ompl::base::PlannerStatus::StatusType(ompl_status))
 
  981     case ompl::base::PlannerStatus::UNKNOWN:
 
  982       RCLCPP_WARN(LOGGER, 
"Motion planning failed for an unknown reason");
 
  983       result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
 
  985     case ompl::base::PlannerStatus::INVALID_START:
 
  986       RCLCPP_WARN(LOGGER, 
"Invalid start state");
 
  987       result = moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID;
 
  989     case ompl::base::PlannerStatus::INVALID_GOAL:
 
  990       RCLCPP_WARN(LOGGER, 
"Invalid goal state");
 
  991       result = moveit_msgs::msg::MoveItErrorCodes::GOAL_STATE_INVALID;
 
  993     case ompl::base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE:
 
  994       RCLCPP_WARN(LOGGER, 
"Unrecognized goal type");
 
  995       result = moveit_msgs::msg::MoveItErrorCodes::UNRECOGNIZED_GOAL_TYPE;
 
  997     case ompl::base::PlannerStatus::TIMEOUT:
 
  998       RCLCPP_WARN(LOGGER, 
"Timed out: %.1fs ≥ %.1fs", ompl_simple_setup->getLastPlanComputationTime(),
 
  999                   request_.allowed_planning_time);
 
 1000       result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
 
 1002     case ompl::base::PlannerStatus::APPROXIMATE_SOLUTION:
 
 1004       if (ompl_simple_setup->getLastPlanComputationTime() > request_.allowed_planning_time)
 
 1006         RCLCPP_WARN(LOGGER, 
"Planning timed out: %.1fs ≥ %.1fs", ompl_simple_setup->getLastPlanComputationTime(),
 
 1007                     request_.allowed_planning_time);
 
 1008         result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
 
 1012         RCLCPP_WARN(LOGGER, 
"Solution is approximate");
 
 1013         result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
 
 1016     case ompl::base::PlannerStatus::EXACT_SOLUTION:
 
 1017       result = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
 1019     case ompl::base::PlannerStatus::CRASH:
 
 1020       RCLCPP_WARN(LOGGER, 
"OMPL crashed!");
 
 1021       result = moveit_msgs::msg::MoveItErrorCodes::CRASH;
 
 1023     case ompl::base::PlannerStatus::ABORT:
 
 1024       RCLCPP_WARN(LOGGER, 
"OMPL was aborted");
 
 1025       result = moveit_msgs::msg::MoveItErrorCodes::ABORT;
 
 1029       RCLCPP_WARN(LOGGER, 
"Unexpected PlannerStatus code from OMPL.");
 
 1030       result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
 
 1037   std::unique_lock<std::mutex> slock(ptc_lock_);
 
 1047   std::string constraint_path;
 
 1048   if (node->get_parameter(
"constraint_approximations_path", constraint_path))
 
 1050     constraints_library_->saveConstraintApproximations(constraint_path);
 
 1053   RCLCPP_WARN(LOGGER, 
"ROS param 'constraint_approximations' not found. Unable to save constraint approximations");
 
 1059   std::string constraint_path;
 
 1060   if (node->get_parameter(
"constraint_approximations_path", constraint_path))
 
 1062     constraints_library_->loadConstraintApproximations(constraint_path);
 
 1063     std::stringstream ss;
 
 1064     constraints_library_->printConstraintApproximations(ss);
 
 1065     RCLCPP_INFO_STREAM(LOGGER, ss.str());
 
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.
 
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.
 
void setVerboseStateValidityChecks(bool flag)
 
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)
 
void interpolateSolution()
 
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)
 
moveit::core::RobotState complete_initial_robot_state_
 
void setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters &wparams)
 
ConstraintsLibraryPtr constraints_library_
 
void unregisterTerminationCondition()
 
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
 
void simplifySolution(double timeout)
 
void setProjectionEvaluator(const std::string &peval)
 
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...
 
virtual ob::GoalPtr constructGoal()
 
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.
 
RobotTrajectory & clear()
 
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.
 
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.
 
moveit_msgs::msg::MoveItErrorCodes error_code_
 
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
 
std::vector< double > processing_time_
 
std::vector< std::string > description_
 
robot_trajectory::RobotTrajectoryPtr trajectory_
 
moveit_msgs::msg::MoveItErrorCodes error_code_