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))
169 return std::make_shared<ProjectionEvaluatorLinkPose>(
this, link_name);
174 "Attempted to set projection evaluator with respect to position of link '%s', "
175 "but that link is not known to the kinematic model.",
179 else if (peval.find_first_of(
"joints(") == 0 && peval[peval.length() - 1] ==
')')
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())
188 ss >> joint >> std::ws;
189 if (getJointModelGroup()->hasJointModel(joint))
191 unsigned int variable_count = getJointModelGroup()->getJointModel(joint)->getVariableCount();
192 if (variable_count > 0)
194 int idx = getJointModelGroup()->getVariableGroupIndex(joint);
195 for (
unsigned int q = 0; q < variable_count; ++q)
197 j.push_back(idx + q);
202 RCLCPP_WARN(LOGGER,
"%s: Ignoring joint '%s' in projection since it has 0 DOF", name_.c_str(), joint.c_str());
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());
215 RCLCPP_ERROR(LOGGER,
"%s: No valid joints specified for joint projection", name_.c_str());
219 return std::make_shared<ProjectionEvaluatorJointValue>(
this, j);
224 RCLCPP_ERROR(LOGGER,
"Unable to allocate projection evaluator based on description: '%s'", peval.c_str());
226 return ob::ProjectionEvaluatorPtr();
229 ompl::base::StateSamplerPtr
232 if (spec_.state_space_.get() != state_space)
234 RCLCPP_ERROR(LOGGER,
"%s: Attempted to allocate a state sampler for an unknown state space", name_.c_str());
235 return ompl::base::StateSamplerPtr();
238 RCLCPP_DEBUG(LOGGER,
"%s: Allocating a new state sampler (attempts to use path constraints)", name_.c_str());
240 if (path_constraints_)
242 if (constraints_library_)
244 const ConstraintApproximationPtr& constraint_approx =
245 constraints_library_->getConstraintApproximation(path_constraints_msg_);
246 if (constraint_approx)
248 ompl::base::StateSamplerAllocator state_sampler_allocator =
249 constraint_approx->getStateSamplerAllocator(path_constraints_msg_);
250 if (state_sampler_allocator)
252 ompl::base::StateSamplerPtr state_sampler = state_sampler_allocator(state_space);
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;
264 constraint_samplers::ConstraintSamplerPtr constraint_sampler;
265 if (spec_.constraint_sampler_manager_)
267 constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
268 path_constraints_->getAllConstraints());
271 if (constraint_sampler)
273 RCLCPP_INFO(LOGGER,
"%s: Allocating specialized state sampler for state space", name_.c_str());
274 return std::make_shared<ConstrainedSampler>(
this, constraint_sampler);
277 RCLCPP_DEBUG(LOGGER,
"%s: Allocating default state sampler for state space", name_.c_str());
278 return state_space->allocDefaultStateSampler();
283 const std::map<std::string, std::string>& config = spec_.config_;
286 std::map<std::string, std::string> cfg = config;
289 auto it = cfg.find(
"longest_valid_segment_fraction");
291 if (it != cfg.end() || max_solution_segment_length_ != 0.0)
294 double longest_valid_segment_fraction_config = (it != cfg.end())
297 double longest_valid_segment_fraction_final = longest_valid_segment_fraction_config;
298 if (max_solution_segment_length_ > 0.0)
302 longest_valid_segment_fraction_final = std::min(
303 longest_valid_segment_fraction_config,
304 max_solution_segment_length_ / spec_.state_space_->getMaximumExtent()
314 it = cfg.find(
"projection_evaluator");
317 setProjectionEvaluator(boost::trim_copy(it->second));
326 std::string optimizer;
327 ompl::base::OptimizationObjectivePtr objective;
328 it = cfg.find(
"optimization_objective");
331 optimizer = it->second;
334 if (optimizer ==
"PathLengthOptimizationObjective")
337 std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
339 else if (optimizer ==
"MinimaxObjective")
341 objective = std::make_shared<ompl::base::MinimaxObjective>(ompl_simple_setup_->getSpaceInformation());
343 else if (optimizer ==
"StateCostIntegralObjective")
345 objective = std::make_shared<ompl::base::StateCostIntegralObjective>(ompl_simple_setup_->getSpaceInformation());
347 else if (optimizer ==
"MechanicalWorkOptimizationObjective")
350 std::make_shared<ompl::base::MechanicalWorkOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
352 else if (optimizer ==
"MaximizeMinClearanceObjective")
355 std::make_shared<ompl::base::MaximizeMinClearanceObjective>(ompl_simple_setup_->getSpaceInformation());
360 "Optimization objective %s is invalid or not defined, using PathLengthOptimizationObjective instead",
363 std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
366 ompl_simple_setup_->setOptimizationObjective(objective);
370 it = cfg.find(
"multi_query_planning_enabled");
373 multi_query_planning_enabled_ = boost::lexical_cast<bool>(it->second);
377 it = cfg.find(
"interpolate");
380 interpolate_ = boost::lexical_cast<bool>(it->second);
385 it = cfg.find(
"simplify_solutions");
388 simplify_solutions_ = boost::lexical_cast<bool>(it->second);
393 it = cfg.find(
"hybridize");
396 hybridize_ = boost::lexical_cast<bool>(it->second);
401 it = cfg.find(
"type");
404 if (name_ != getGroupName())
405 RCLCPP_WARN(LOGGER,
"%s: Attribute 'type' not specified in planner configuration", name_.c_str());
409 std::string type = it->second;
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); });
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());
422 ompl_simple_setup_->getSpaceInformation()->setup();
423 ompl_simple_setup_->getSpaceInformation()->params().setParams(cfg,
true);
425 ompl_simple_setup_->getSpaceInformation()->setup();
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)
434 RCLCPP_WARN(LOGGER,
"It looks like the planning volume was not specified.");
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);
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);
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();
459 if (ompl_simple_setup_->haveSolutionPath())
461 og::PathGeometric& pg = ompl_simple_setup_->getSolutionPath();
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)
469 eventual_states += ompl_simple_setup_->getStateSpace()->validSegmentCount(states[i], states[i + 1]);
472 if (eventual_states < minimum_waypoint_count_)
475 pg.interpolate(minimum_waypoint_count_);
489 for (std::size_t i = 0; i < pg.getStateCount(); ++i)
491 spec_.state_space_->copyToRobotState(ks, pg.getState(i));
499 if (ompl_simple_setup_->haveSolutionPath())
501 convertPath(ompl_simple_setup_->getSolutionPath(), traj);
503 return ompl_simple_setup_->haveSolutionPath();
508 if (ompl_simple_setup_->getStateValidityChecker())
510 static_cast<StateValidityChecker*
>(ompl_simple_setup_->getStateValidityChecker().get())->setVerbose(flag);
518 std::vector<ob::GoalPtr> goals;
519 for (kinematic_constraints::KinematicConstraintSetPtr& goal_constraint : goal_constraints_)
521 constraint_samplers::ConstraintSamplerPtr constraint_sampler;
522 if (spec_.constraint_sampler_manager_)
524 constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
525 goal_constraint->getAllConstraints());
528 if (constraint_sampler)
530 ob::GoalPtr goal = std::make_shared<ConstrainedGoalSampler>(
this, goal_constraint, constraint_sampler);
531 goals.push_back(goal);
537 return goals.size() == 1 ? goals[0] : std::make_shared<GoalSampleableRegionMux>(goals);
541 RCLCPP_ERROR(LOGGER,
"Unable to construct goal representation");
544 return ob::GoalPtr();
547 ompl::base::PlannerTerminationCondition
549 const ompl::time::point& start)
551 auto it = spec_.config_.find(
"termination_condition");
552 if (it == spec_.config_.end())
554 return ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
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(
"[ ,]"));
561 if (termination_and_params.empty())
563 RCLCPP_ERROR(LOGGER,
"Termination condition not specified");
569 else if (termination_and_params[0] ==
"Iteration")
571 if (termination_and_params.size() > 1)
573 return ob::plannerOrTerminationCondition(
574 ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
575 ob::IterationTerminationCondition(std::stoul(termination_and_params[1])));
579 RCLCPP_ERROR(LOGGER,
"Missing argument to Iteration termination condition");
584 else if (termination_and_params[0] ==
"CostConvergence")
586 std::size_t solutions_window = 10u;
587 double epsilon = 0.1;
588 if (termination_and_params.size() > 1)
590 solutions_window = std::stoul(termination_and_params[1]);
591 if (termination_and_params.size() > 2)
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));
603 else if (termination_and_params[0] ==
"ExactSolution")
605 return ob::plannerOrTerminationCondition(
606 ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
607 ob::exactSolnPlannerTerminationCondition(ompl_simple_setup_->getProblemDefinition()));
611 RCLCPP_ERROR(LOGGER,
"Unknown planner termination condition");
614 return ob::plannerAlwaysTerminatingCondition();
620 complete_initial_robot_state_ = complete_initial_robot_state;
621 complete_initial_robot_state_.
update();
626 if (!multi_query_planning_enabled_)
628 ompl_simple_setup_->clear();
636 auto planner =
dynamic_cast<ompl::geometric::LazyPRM*
>(ompl_simple_setup_->getPlanner().get());
637 if (planner !=
nullptr)
639 planner->clearValidity();
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();
651 moveit_msgs::msg::MoveItErrorCodes* )
654 path_constraints_ = std::make_shared<kinematic_constraints::KinematicConstraintSet>(getRobotModel());
655 path_constraints_->add(path_constraints, getPlanningScene()->getTransforms());
656 path_constraints_msg_ = path_constraints;
662 const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
663 const moveit_msgs::msg::Constraints& path_constraints, moveit_msgs::msg::MoveItErrorCodes* error)
666 goal_constraints_.clear();
667 for (
const moveit_msgs::msg::Constraints& goal_constraint : goal_constraints)
670 kinematic_constraints::KinematicConstraintSetPtr kset(
672 kset->add(constr, getPlanningScene()->getTransforms());
675 goal_constraints_.push_back(kset);
679 if (goal_constraints_.empty())
681 RCLCPP_WARN(LOGGER,
"%s: No goal constraints specified. There is no problem to solve.", name_.c_str());
684 error->val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
689 ob::GoalPtr goal = constructGoal();
690 ompl_simple_setup_->setGoal(goal);
691 return static_cast<bool>(goal);
695 const std::string& filename)
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_);
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());
714 bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
717 static_cast<ob::GoalLazySamples*
>(ompl_simple_setup_->getGoal().get())->startSampling();
728 bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
731 static_cast<ob::GoalLazySamples*
>(ompl_simple_setup_->getGoal().get())->stopSampling();
743 ompl_simple_setup_->getProblemDefinition()->clearSolutionPaths();
744 const ob::PlannerPtr planner = ompl_simple_setup_->getPlanner();
745 if (planner && !multi_query_planning_enabled_)
750 ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
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);
761 std::stringstream debug_out;
762 ompl_simple_setup_->print(debug_out);
763 RCLCPP_DEBUG(LOGGER,
"%s", rclcpp::get_c_string(debug_out.str()));
768 res.
error_code = solve(request_.allowed_planning_time, request_.num_planning_attempts);
769 if (res.
error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
771 double ptime = getLastPlanTime();
772 if (simplify_solutions_)
774 simplifySolution(request_.allowed_planning_time - ptime);
775 ptime += getLastSimplifyTime();
780 interpolateSolution();
784 RCLCPP_DEBUG(LOGGER,
"%s: Returning successful solution with %lu states", getName().c_str(),
785 getOMPLSimpleSetup()->getSolutionPath().getStateCount());
787 res.
trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
794 RCLCPP_INFO(LOGGER,
"Unable to solve the planning problem");
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)
808 double ptime = getLastPlanTime();
812 res.
trajectory.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
816 if (simplify_solutions_)
818 simplifySolution(request_.allowed_planning_time - ptime);
822 res.
trajectory.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
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));
833 res.
trajectory.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
837 RCLCPP_DEBUG(LOGGER,
"%s: Returning successful solution with %lu states", getName().c_str(),
838 getOMPLSimpleSetup()->getSolutionPath().getStateCount());
844 RCLCPP_INFO(LOGGER,
"Unable to solve the planning problem");
845 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
853 ompl::time::point start = ompl::time::now();
856 moveit_msgs::msg::MoveItErrorCodes result;
857 result.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
858 if (count <= 1 || multi_query_planning_enabled_)
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();
867 result.val = logPlannerStatus(ompl_simple_setup_);
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_)
875 ompl_parallel_plan_.clearPlanners();
876 if (ompl_simple_setup_->getPlannerAllocator())
878 for (
unsigned int i = 0; i < count; ++i)
880 ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
885 for (
unsigned int i = 0; i < count; ++i)
887 ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
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)
895 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
897 last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
898 unregisterTerminationCondition();
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)
908 ompl_parallel_plan_.clearPlanners();
909 if (ompl_simple_setup_->getPlannerAllocator())
911 for (
unsigned int i = 0; i < max_planning_threads_; ++i)
913 ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
918 for (
unsigned int i = 0; i < max_planning_threads_; ++i)
920 ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
924 bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
926 result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && r) ?
927 moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
928 moveit_msgs::msg::MoveItErrorCodes::FAILURE;
930 n = count % max_planning_threads_;
933 ompl_parallel_plan_.clearPlanners();
934 if (ompl_simple_setup_->getPlannerAllocator())
936 for (
int i = 0; i < n; ++i)
938 ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
943 for (
int i = 0; i < n; ++i)
945 ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
949 bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
951 result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && r) ?
952 moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
953 moveit_msgs::msg::MoveItErrorCodes::FAILURE;
955 last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
956 unregisterTerminationCondition();
966 std::unique_lock<std::mutex> slock(ptc_lock_);
972 std::unique_lock<std::mutex> slock(ptc_lock_);
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))
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;
986 case ompl::base::PlannerStatus::INVALID_START:
987 RCLCPP_WARN(LOGGER,
"Invalid start state");
988 result = moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID;
990 case ompl::base::PlannerStatus::INVALID_GOAL:
991 RCLCPP_WARN(LOGGER,
"Invalid goal state");
992 result = moveit_msgs::msg::MoveItErrorCodes::GOAL_STATE_INVALID;
994 case ompl::base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE:
995 RCLCPP_WARN(LOGGER,
"Unrecognized goal type");
996 result = moveit_msgs::msg::MoveItErrorCodes::UNRECOGNIZED_GOAL_TYPE;
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;
1003 case ompl::base::PlannerStatus::APPROXIMATE_SOLUTION:
1005 if (ompl_simple_setup->getLastPlanComputationTime() > request_.allowed_planning_time)
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;
1013 RCLCPP_WARN(LOGGER,
"Solution is approximate");
1014 result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
1017 case ompl::base::PlannerStatus::EXACT_SOLUTION:
1018 result = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1020 case ompl::base::PlannerStatus::CRASH:
1021 RCLCPP_WARN(LOGGER,
"OMPL crashed!");
1022 result = moveit_msgs::msg::MoveItErrorCodes::CRASH;
1024 case ompl::base::PlannerStatus::ABORT:
1025 RCLCPP_WARN(LOGGER,
"OMPL was aborted");
1026 result = moveit_msgs::msg::MoveItErrorCodes::ABORT;
1030 RCLCPP_WARN(LOGGER,
"Unexpected PlannerStatus code from OMPL.");
1031 result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
1038 std::unique_lock<std::mutex> slock(ptc_lock_);
1048 std::string constraint_path;
1049 if (node->get_parameter(
"constraint_approximations_path", constraint_path))
1051 constraints_library_->saveConstraintApproximations(constraint_path);
1054 RCLCPP_WARN(LOGGER,
"ROS param 'constraint_approximations' not found. Unable to save constraint approximations");
1060 std::string constraint_path;
1061 if (node->get_parameter(
"constraint_approximations_path", constraint_path))
1063 constraints_library_->loadConstraintApproximations(constraint_path);
1064 std::stringstream ss;
1065 constraints_library_->printConstraintApproximations(ss);
1066 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.
rclcpp::Logger get_logger()
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< std::string > description
std::vector< double > processing_time
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory