37 #include <boost/algorithm/string/trim.hpp>
38 #include <boost/algorithm/string/split.hpp>
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>
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>
70 constexpr
char LOGNAME[] =
"model_based_planning_context";
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())
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)
91 , simplify_solutions_(true)
102 loadConstraintApproximations(nh);
103 if (!use_constraints_approximations)
105 setConstraintsApproximations(ConstraintsLibraryPtr());
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); });
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)));
118 if (path_constraints_ && constraints_library_)
120 const ConstraintApproximationPtr& constraint_approx =
121 constraints_library_->getConstraintApproximation(path_constraints_msg_);
122 if (constraint_approx)
124 getOMPLStateSpace()->setInterpolationFunction(constraint_approx->getInterpolationFunction());
130 if (ompl_simple_setup_->getGoal())
131 ompl_simple_setup_->setup();
136 if (!spec_.state_space_)
141 ob::ProjectionEvaluatorPtr projection_eval = getProjectionEvaluator(peval);
143 spec_.state_space_->registerDefaultProjection(projection_eval);
146 ompl::base::ProjectionEvaluatorPtr
149 if (peval.find_first_of(
"link(") == 0 && peval[peval.length() - 1] ==
')')
151 std::string link_name = peval.substr(5, peval.length() - 6);
152 if (getRobotModel()->hasLinkModel(link_name))
156 "Attempted to set projection evaluator with respect to position of link '%s', "
157 "but that link is not known to the kinematic model.",
160 else if (peval.find_first_of(
"joints(") == 0 && peval[peval.length() - 1] ==
')')
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())
169 ss >> joint >> std::ws;
170 if (getJointModelGroup()->hasJointModel(joint))
172 unsigned int variable_count = getJointModelGroup()->getJointModel(joint)->getVariableCount();
173 if (variable_count > 0)
175 int idx = getJointModelGroup()->getVariableGroupIndex(joint);
176 for (
unsigned int q = 0; q < variable_count; ++q)
177 j.push_back(idx + q);
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());
195 ROS_ERROR_NAMED(
LOGNAME,
"Unable to allocate projection evaluator based on description: '%s'", peval.c_str());
196 return ob::ProjectionEvaluatorPtr();
199 ompl::base::StateSamplerPtr
202 if (spec_.state_space_.get() != state_space)
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();
208 ROS_DEBUG_NAMED(
LOGNAME,
"%s: Allocating a new state sampler (attempts to use path constraints)", name_.c_str());
210 if (path_constraints_)
212 if (constraints_library_)
214 const ConstraintApproximationPtr& constraint_approx =
215 constraints_library_->getConstraintApproximation(path_constraints_msg_);
216 if (constraint_approx)
218 ompl::base::StateSamplerAllocator state_sampler_allocator =
219 constraint_approx->getStateSamplerAllocator(path_constraints_msg_);
220 if (state_sampler_allocator)
222 ompl::base::StateSamplerPtr state_sampler = state_sampler_allocator(state_space);
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;
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());
239 if (constraint_sampler)
246 return state_space->allocDefaultStateSampler();
251 const std::map<std::string, std::string>& config = spec_.config_;
254 std::map<std::string, std::string> cfg = config;
257 auto it = cfg.find(
"longest_valid_segment_fraction");
259 if (it != cfg.end() || max_solution_segment_length_ != 0.0)
262 double longest_valid_segment_fraction_config = (it != cfg.end())
265 double longest_valid_segment_fraction_final = longest_valid_segment_fraction_config;
266 if (max_solution_segment_length_ > 0.0)
270 longest_valid_segment_fraction_final = std::min(
271 longest_valid_segment_fraction_config,
272 max_solution_segment_length_ / spec_.state_space_->getMaximumExtent()
282 it = cfg.find(
"projection_evaluator");
285 setProjectionEvaluator(boost::trim_copy(it->second));
292 std::string optimizer;
293 ompl::base::OptimizationObjectivePtr objective;
294 it = cfg.find(
"optimization_objective");
297 optimizer = it->second;
300 if (optimizer ==
"PathLengthOptimizationObjective")
303 std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
305 else if (optimizer ==
"MinimaxObjective")
307 objective = std::make_shared<ompl::base::MinimaxObjective>(ompl_simple_setup_->getSpaceInformation());
309 else if (optimizer ==
"StateCostIntegralObjective")
311 objective = std::make_shared<ompl::base::StateCostIntegralObjective>(ompl_simple_setup_->getSpaceInformation());
313 else if (optimizer ==
"MechanicalWorkOptimizationObjective")
316 std::make_shared<ompl::base::MechanicalWorkOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
318 else if (optimizer ==
"MaximizeMinClearanceObjective")
321 std::make_shared<ompl::base::MaximizeMinClearanceObjective>(ompl_simple_setup_->getSpaceInformation());
326 std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
329 ompl_simple_setup_->setOptimizationObjective(objective);
333 it = cfg.find(
"multi_query_planning_enabled");
335 multi_query_planning_enabled_ = boost::lexical_cast<bool>(it->second);
338 it = cfg.find(
"interpolate");
341 interpolate_ = boost::lexical_cast<bool>(it->second);
346 it = cfg.find(
"hybridize");
349 hybridize_ = boost::lexical_cast<bool>(it->second);
354 it = cfg.find(
"type");
357 if (name_ != getGroupName())
358 ROS_WARN_NAMED(
LOGNAME,
"%s: Attribute 'type' not specified in planner configuration", name_.c_str());
362 std::string type = it->second;
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());
375 ompl_simple_setup_->getSpaceInformation()->setup();
376 ompl_simple_setup_->getSpaceInformation()->params().setParams(cfg,
true);
378 ompl_simple_setup_->getSpaceInformation()->setup();
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)
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);
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);
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();
410 if (ompl_simple_setup_->haveSolutionPath())
412 og::PathGeometric& pg = ompl_simple_setup_->getSolutionPath();
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++)
420 eventual_states += ompl_simple_setup_->getStateSpace()->validSegmentCount(states[i], states[i + 1]);
423 if (eventual_states < minimum_waypoint_count_)
426 pg.interpolate(minimum_waypoint_count_);
440 for (std::size_t i = 0; i < pg.getStateCount(); ++i)
442 spec_.state_space_->copyToRobotState(ks, pg.getState(i));
450 if (ompl_simple_setup_->haveSolutionPath())
451 convertPath(ompl_simple_setup_->getSolutionPath(), traj);
452 return ompl_simple_setup_->haveSolutionPath();
457 if (ompl_simple_setup_->getStateValidityChecker())
458 static_cast<StateValidityChecker*
>(ompl_simple_setup_->getStateValidityChecker().get())->setVerbose(flag);
465 std::vector<ob::GoalPtr> goals;
466 for (kinematic_constraints::KinematicConstraintSetPtr& goal_constraint : goal_constraints_)
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)
475 goals.push_back(goal);
484 return ob::GoalPtr();
487 ompl::base::PlannerTerminationCondition
489 const ompl::time::point& start)
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(
"[ ,]"));
498 if (termination_and_params.empty())
503 else if (termination_and_params[0] ==
"Iteration")
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])));
514 else if (termination_and_params[0] ==
"CostConvergence")
516 std::size_t solutions_window = 10u;
518 if (termination_and_params.size() > 1)
520 solutions_window = std::stoul(termination_and_params[1]);
521 if (termination_and_params.size() > 2)
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));
531 else if (termination_and_params[0] ==
"ExactSolution")
533 return ob::plannerOrTerminationCondition(
534 ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() -
start)),
535 ob::exactSolnPlannerTerminationCondition(ompl_simple_setup_->getProblemDefinition()));
541 return ob::plannerAlwaysTerminatingCondition();
547 complete_initial_robot_state_ = complete_initial_robot_state;
548 complete_initial_robot_state_.
update();
553 if (!multi_query_planning_enabled_)
554 ompl_simple_setup_->clear();
561 auto planner =
dynamic_cast<ompl::geometric::LazyPRM*
>(ompl_simple_setup_->getPlanner().get());
562 if (planner !=
nullptr)
563 planner->clearValidity();
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();
574 moveit_msgs::MoveItErrorCodes* )
577 path_constraints_ = std::make_shared<kinematic_constraints::KinematicConstraintSet>(getRobotModel());
578 path_constraints_->add(path_constraints, getPlanningScene()->getTransforms());
579 path_constraints_msg_ = path_constraints;
585 const std::vector<moveit_msgs::Constraints>& goal_constraints,
const moveit_msgs::Constraints& path_constraints,
586 moveit_msgs::MoveItErrorCodes* error)
589 goal_constraints_.clear();
590 for (
const moveit_msgs::Constraints& goal_constraint : goal_constraints)
593 kinematic_constraints::KinematicConstraintSetPtr kset(
595 kset->add(constr, getPlanningScene()->getTransforms());
597 goal_constraints_.push_back(kset);
600 if (goal_constraints_.empty())
602 ROS_WARN_NAMED(
LOGNAME,
"%s: No goal constraints specified. There is no problem to solve.", name_.c_str());
604 error->val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
608 ob::GoalPtr goal = constructGoal();
609 ompl_simple_setup_->setGoal(goal);
610 return static_cast<bool>(goal);
614 const std::string& filename)
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_);
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());
633 bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
635 static_cast<ob::GoalLazySamples*
>(ompl_simple_setup_->getGoal().get())->startSampling();
643 bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
645 static_cast<ob::GoalLazySamples*
>(ompl_simple_setup_->getGoal().get())->stopSampling();
654 ompl_simple_setup_->getProblemDefinition()->clearSolutionPaths();
655 const ob::PlannerPtr planner = ompl_simple_setup_->getPlanner();
656 if (planner && !multi_query_planning_enabled_)
659 ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
665 int v = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getValidMotionCount();
666 int iv = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getInvalidMotionCount();
672 res.
error_code_ = solve(request_.allowed_planning_time, request_.num_planning_attempts);
673 if (res.
error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
675 double ptime = getLastPlanTime();
676 if (simplify_solutions_)
678 simplifySolution(request_.allowed_planning_time - ptime);
679 ptime += getLastSimplifyTime();
683 interpolateSolution();
687 getOMPLSimpleSetup()->getSolutionPath().getStateCount());
689 res.
trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
703 res.
error_code_ = solve(request_.allowed_planning_time, request_.num_planning_attempts);
704 if (res.
error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
709 double ptime = getLastPlanTime();
713 res.
trajectory_.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
717 if (simplify_solutions_)
719 simplifySolution(request_.allowed_planning_time - ptime);
723 res.
trajectory_.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
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));
734 res.
trajectory_.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
739 getOMPLSimpleSetup()->getSolutionPath().getStateCount());
752 ompl::time::point
start = ompl::time::now();
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_)
762 result.val = errorCode(ompl_simple_setup_->solve(ptc));
763 last_plan_time_ = ompl_simple_setup_->getLastPlanComputationTime();
768 ompl_parallel_plan_.clearHybridizationPaths();
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());
776 for (
unsigned int i = 0; i < num_planners; ++i)
777 ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
779 return errorCode(ompl_parallel_plan_.solve(ptc, 1, num_planners, hybridize_));
782 if (count <= max_planning_threads_)
784 result.val = plan_parallel(count);
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_);
794 last_plan_time_ = ompl::time::seconds(ompl::time::now() -
start);
796 unregisterTerminationCondition();
803 std::unique_lock<std::mutex> slock(ptc_lock_);
809 std::unique_lock<std::mutex> slock(ptc_lock_);
815 auto result = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
816 switch (ompl::base::PlannerStatus::StatusType(status))
818 case ompl::base::PlannerStatus::UNKNOWN:
820 result = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
822 case ompl::base::PlannerStatus::INVALID_START:
824 result = moveit_msgs::MoveItErrorCodes::START_STATE_INVALID;
826 case ompl::base::PlannerStatus::INVALID_GOAL:
828 result = moveit_msgs::MoveItErrorCodes::GOAL_STATE_INVALID;
830 case ompl::base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE:
832 result = moveit_msgs::MoveItErrorCodes::UNRECOGNIZED_GOAL_TYPE;
834 case ompl::base::PlannerStatus::TIMEOUT:
836 result = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
838 case ompl::base::PlannerStatus::APPROXIMATE_SOLUTION:
840 result = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
842 case ompl::base::PlannerStatus::EXACT_SOLUTION:
843 result = moveit_msgs::MoveItErrorCodes::SUCCESS;
845 case ompl::base::PlannerStatus::CRASH:
847 result = moveit_msgs::MoveItErrorCodes::CRASH;
849 case ompl::base::PlannerStatus::ABORT:
851 result = moveit_msgs::MoveItErrorCodes::ABORT;
856 result = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
863 std::unique_lock<std::mutex> slock(ptc_lock_);
871 std::string constraint_path;
872 if (nh.
getParam(
"constraint_approximations_path", constraint_path))
874 constraints_library_->saveConstraintApproximations(constraint_path);
877 ROS_WARN_NAMED(
LOGNAME,
"ROS param 'constraint_approximations' not found. Unable to save constraint approximations");
883 std::string constraint_path;
884 if (nh.
getParam(
"constraint_approximations_path", constraint_path))
886 constraints_library_->loadConstraintApproximations(constraint_path);
887 std::stringstream ss;
888 constraints_library_->printConstraintApproximations(ss);