00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/ompl_interface/model_based_planning_context.h>
00038 #include <moveit/ompl_interface/detail/state_validity_checker.h>
00039 #include <moveit/ompl_interface/detail/constrained_sampler.h>
00040 #include <moveit/ompl_interface/detail/constrained_goal_sampler.h>
00041 #include <moveit/ompl_interface/detail/goal_union.h>
00042 #include <moveit/ompl_interface/detail/projection_evaluators.h>
00043 #include <moveit/ompl_interface/constraints_library.h>
00044 #include <moveit/kinematic_constraints/utils.h>
00045 #include <moveit/profiler/profiler.h>
00046 #include <eigen_conversions/eigen_msg.h>
00047
00048 #include <ompl/base/samplers/UniformValidStateSampler.h>
00049 #include <ompl/base/goals/GoalLazySamples.h>
00050 #include <ompl/tools/config/SelfConfig.h>
00051 #include <ompl/base/spaces/SE3StateSpace.h>
00052 #include <ompl/datastructures/PDF.h>
00053
00054 ompl_interface::ModelBasedPlanningContext::ModelBasedPlanningContext(const std::string &name, const ModelBasedPlanningContextSpecification &spec) :
00055 planning_interface::PlanningContext(name, spec.state_space_->getJointModelGroup()->getName()),
00056 spec_(spec),
00057 complete_initial_robot_state_(spec.state_space_->getRobotModel()),
00058 ompl_simple_setup_(spec.ompl_simple_setup_),
00059 ompl_benchmark_(*ompl_simple_setup_),
00060 ompl_parallel_plan_(ompl_simple_setup_->getProblemDefinition()),
00061 ptc_(NULL),
00062 last_plan_time_(0.0),
00063 last_simplify_time_(0.0),
00064 max_goal_samples_(0),
00065 max_state_sampling_attempts_(0),
00066 max_goal_sampling_attempts_(0),
00067 max_planning_threads_(0),
00068 max_solution_segment_length_(0.0),
00069 minimum_waypoint_count_(0),
00070 use_state_validity_cache_(true),
00071 simplify_solutions_(true)
00072 {
00073 ompl_simple_setup_->getStateSpace()->computeSignature(space_signature_);
00074 ompl_simple_setup_->getStateSpace()->setStateSamplerAllocator(boost::bind(&ModelBasedPlanningContext::allocPathConstrainedSampler, this, _1));
00075 }
00076
00077 void ompl_interface::ModelBasedPlanningContext::setProjectionEvaluator(const std::string &peval)
00078 {
00079 if (!spec_.state_space_)
00080 {
00081 logError("No state space is configured yet");
00082 return;
00083 }
00084 ob::ProjectionEvaluatorPtr pe = getProjectionEvaluator(peval);
00085 if (pe)
00086 spec_.state_space_->registerDefaultProjection(pe);
00087 }
00088
00089 ompl::base::ProjectionEvaluatorPtr ompl_interface::ModelBasedPlanningContext::getProjectionEvaluator(const std::string &peval) const
00090 {
00091 if (peval.find_first_of("link(") == 0 && peval[peval.length() - 1] == ')')
00092 {
00093 std::string link_name = peval.substr(5, peval.length() - 6);
00094 if (getRobotModel()->hasLinkModel(link_name))
00095 return ob::ProjectionEvaluatorPtr(new ProjectionEvaluatorLinkPose(this, link_name));
00096 else
00097 logError("Attempted to set projection evaluator with respect to position of link '%s', but that link is not known to the kinematic model.", link_name.c_str());
00098 }
00099 else
00100 if (peval.find_first_of("joints(") == 0 && peval[peval.length() - 1] == ')')
00101 {
00102 std::string joints = peval.substr(7, peval.length() - 8);
00103 boost::replace_all(joints, ",", " ");
00104 std::vector<unsigned int> j;
00105 std::stringstream ss(joints);
00106 while (ss.good() && !ss.eof())
00107 {
00108 std::string v; ss >> v >> std::ws;
00109 if (getJointModelGroup()->hasJointModel(v))
00110 {
00111 unsigned int vc = getJointModelGroup()->getJointModel(v)->getVariableCount();
00112 if (vc > 0)
00113 {
00114 int idx = getJointModelGroup()->getVariableGroupIndex(v);
00115 for (int q = 0 ; q < vc ; ++q)
00116 j.push_back(idx + q);
00117 }
00118 else
00119 logWarn("%s: Ignoring joint '%s' in projection since it has 0 DOF", name_.c_str(), v.c_str());
00120 }
00121 else
00122 logError("%s: Attempted to set projection evaluator with respect to value of joint '%s', but that joint is not known to the group '%s'.",
00123 name_.c_str(), v.c_str(), getGroupName().c_str());
00124 }
00125 if (j.empty())
00126 logError("%s: No valid joints specified for joint projection", name_.c_str());
00127 else
00128 return ob::ProjectionEvaluatorPtr(new ProjectionEvaluatorJointValue(this, j));
00129 }
00130 else
00131 logError("Unable to allocate projection evaluator based on description: '%s'", peval.c_str());
00132 return ob::ProjectionEvaluatorPtr();
00133 }
00134
00135 ompl::base::StateSamplerPtr ompl_interface::ModelBasedPlanningContext::allocPathConstrainedSampler(const ompl::base::StateSpace *ss) const
00136 {
00137 if (spec_.state_space_.get() != ss)
00138 {
00139 logError("%s: Attempted to allocate a state sampler for an unknown state space", name_.c_str());
00140 return ompl::base::StateSamplerPtr();
00141 }
00142
00143 logDebug("%s: Allocating a new state sampler (attempts to use path constraints)", name_.c_str());
00144
00145 if (path_constraints_)
00146 {
00147 if (spec_.constraints_library_)
00148 {
00149 const ConstraintApproximationPtr &ca = spec_.constraints_library_->getConstraintApproximation(path_constraints_msg_);
00150 if (ca)
00151 {
00152 ompl::base::StateSamplerAllocator c_ssa = ca->getStateSamplerAllocator(path_constraints_msg_);
00153 if (c_ssa)
00154 {
00155 ompl::base::StateSamplerPtr res = c_ssa(ss);
00156 if (res)
00157 {
00158 logInform("%s: Using precomputed state sampler (approximated constraint space) for constraint '%s'", name_.c_str(), path_constraints_msg_.name.c_str());
00159 return res;
00160 }
00161 }
00162 }
00163 }
00164
00165 constraint_samplers::ConstraintSamplerPtr cs;
00166 if (spec_.constraint_sampler_manager_)
00167 cs = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(), path_constraints_->getAllConstraints());
00168
00169 if (cs)
00170 {
00171 logInform("%s: Allocating specialized state sampler for state space", name_.c_str());
00172 return ob::StateSamplerPtr(new ConstrainedSampler(this, cs));
00173 }
00174 }
00175 logDebug("%s: Allocating default state sampler for state space", name_.c_str());
00176 return ss->allocDefaultStateSampler();
00177 }
00178
00179 void ompl_interface::ModelBasedPlanningContext::configure()
00180 {
00181
00182 ompl::base::ScopedState<> ompl_start_state(spec_.state_space_);
00183 spec_.state_space_->copyToOMPLState(ompl_start_state.get(), getCompleteInitialRobotState());
00184 ompl_simple_setup_->setStartState(ompl_start_state);
00185 ompl_simple_setup_->setStateValidityChecker(ob::StateValidityCheckerPtr(new StateValidityChecker(this)));
00186
00187 if (path_constraints_ && spec_.constraints_library_)
00188 {
00189 const ConstraintApproximationPtr &ca = spec_.constraints_library_->getConstraintApproximation(path_constraints_msg_);
00190 if (ca)
00191 {
00192 getOMPLStateSpace()->setInterpolationFunction(ca->getInterpolationFunction());
00193 logInform("Using precomputed interpolation states");
00194 }
00195 }
00196
00197 useConfig();
00198 if (ompl_simple_setup_->getGoal())
00199 ompl_simple_setup_->setup();
00200 }
00201
00202 void ompl_interface::ModelBasedPlanningContext::useConfig()
00203 {
00204 const std::map<std::string, std::string> &config = spec_.config_;
00205 if (config.empty())
00206 return;
00207 std::map<std::string, std::string> cfg = config;
00208
00209
00210 std::map<std::string, std::string>::iterator it = cfg.find("projection_evaluator");
00211 if (it != cfg.end())
00212 {
00213 setProjectionEvaluator(boost::trim_copy(it->second));
00214 cfg.erase(it);
00215 }
00216
00217 if (cfg.empty())
00218 return;
00219
00220
00221 it = cfg.find("type");
00222 if (it == cfg.end())
00223 {
00224 if (name_ != getGroupName())
00225 logWarn("%s: Attribute 'type' not specified in planner configuration", name_.c_str());
00226 }
00227 else
00228 {
00229 std::string type = it->second;
00230 cfg.erase(it);
00231 ompl_simple_setup_->setPlannerAllocator(boost::bind(spec_.planner_selector_(type), _1,
00232 name_ != getGroupName() ? name_ : "", spec_));
00233 logInform("Planner configuration '%s' will use planner '%s'. Additional configuration parameters will be set when the planner is constructed.",
00234 name_.c_str(), type.c_str());
00235 }
00236
00237
00238 ompl_simple_setup_->getSpaceInformation()->setup();
00239 ompl_simple_setup_->getSpaceInformation()->params().setParams(cfg, true);
00240
00241 ompl_simple_setup_->getSpaceInformation()->setup();
00242 }
00243
00244 void ompl_interface::ModelBasedPlanningContext::setPlanningVolume(const moveit_msgs::WorkspaceParameters &wparams)
00245 {
00246 if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
00247 wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
00248 wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
00249 logWarn("It looks like the planning volume was not specified.");
00250
00251 logDebug("%s: Setting planning volume (affects SE2 & SE3 joints only) to x = [%f, %f], y = [%f, %f], z = [%f, %f]", name_.c_str(),
00252 wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y, wparams.max_corner.y, wparams.min_corner.z, wparams.max_corner.z);
00253
00254 spec_.state_space_->setPlanningVolume(wparams.min_corner.x, wparams.max_corner.x,
00255 wparams.min_corner.y, wparams.max_corner.y,
00256 wparams.min_corner.z, wparams.max_corner.z);
00257 }
00258
00259 void ompl_interface::ModelBasedPlanningContext::simplifySolution(double timeout)
00260 {
00261 ompl_simple_setup_->simplifySolution(timeout);
00262 last_simplify_time_ = ompl_simple_setup_->getLastSimplificationTime();
00263 }
00264
00265 void ompl_interface::ModelBasedPlanningContext::interpolateSolution()
00266 {
00267 if (ompl_simple_setup_->haveSolutionPath())
00268 {
00269 og::PathGeometric &pg = ompl_simple_setup_->getSolutionPath();
00270 pg.interpolate(std::max((unsigned int)floor(0.5 + pg.length() / max_solution_segment_length_), minimum_waypoint_count_));
00271 }
00272 }
00273
00274 void ompl_interface::ModelBasedPlanningContext::convertPath(const ompl::geometric::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
00275 {
00276 robot_state::RobotState ks = complete_initial_robot_state_;
00277 for (std::size_t i = 0 ; i < pg.getStateCount() ; ++i)
00278 {
00279 spec_.state_space_->copyToRobotState(ks, pg.getState(i));
00280 traj.addSuffixWayPoint(ks, 0.0);
00281 }
00282 }
00283
00284 bool ompl_interface::ModelBasedPlanningContext::getSolutionPath(robot_trajectory::RobotTrajectory &traj) const
00285 {
00286 traj.clear();
00287 if (!ompl_simple_setup_->haveSolutionPath())
00288 return false;
00289 convertPath(ompl_simple_setup_->getSolutionPath(), traj);
00290 return true;
00291 }
00292
00293 void ompl_interface::ModelBasedPlanningContext::setVerboseStateValidityChecks(bool flag)
00294 {
00295 if (ompl_simple_setup_->getStateValidityChecker())
00296 static_cast<StateValidityChecker*>(ompl_simple_setup_->getStateValidityChecker().get())->setVerbose(flag);
00297 }
00298
00299 ompl::base::GoalPtr ompl_interface::ModelBasedPlanningContext::constructGoal()
00300 {
00301
00302
00303 std::vector<ob::GoalPtr> goals;
00304 for (std::size_t i = 0 ; i < goal_constraints_.size() ; ++i)
00305 {
00306 constraint_samplers::ConstraintSamplerPtr cs;
00307 if (spec_.constraint_sampler_manager_)
00308 cs = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(), goal_constraints_[i]->getAllConstraints());
00309 if (cs)
00310 {
00311 ob::GoalPtr g = ob::GoalPtr(new ConstrainedGoalSampler(this, goal_constraints_[i], cs));
00312 goals.push_back(g);
00313 }
00314 }
00315
00316 if (!goals.empty())
00317 return goals.size() == 1 ? goals[0] : ompl::base::GoalPtr(new GoalSampleableRegionMux(goals));
00318 else
00319 logError("Unable to construct goal representation");
00320
00321 return ob::GoalPtr();
00322 }
00323
00324 void ompl_interface::ModelBasedPlanningContext::setCompleteInitialState(const robot_state::RobotState &complete_initial_robot_state)
00325 {
00326 complete_initial_robot_state_ = complete_initial_robot_state;
00327 }
00328
00329 void ompl_interface::ModelBasedPlanningContext::clear()
00330 {
00331 ompl_simple_setup_->clear();
00332 ompl_simple_setup_->clearStartStates();
00333 ompl_simple_setup_->setGoal(ob::GoalPtr());
00334 ompl_simple_setup_->setStateValidityChecker(ob::StateValidityCheckerPtr());
00335 path_constraints_.reset();
00336 goal_constraints_.clear();
00337 getOMPLStateSpace()->setInterpolationFunction(InterpolationFunction());
00338 }
00339
00340 bool ompl_interface::ModelBasedPlanningContext::setPathConstraints(const moveit_msgs::Constraints &path_constraints,
00341 moveit_msgs::MoveItErrorCodes *error)
00342 {
00343
00344 path_constraints_.reset(new kinematic_constraints::KinematicConstraintSet(getRobotModel()));
00345 path_constraints_->add(path_constraints, getPlanningScene()->getTransforms());
00346 path_constraints_msg_ = path_constraints;
00347
00348 return true;
00349 }
00350
00351 bool ompl_interface::ModelBasedPlanningContext::setGoalConstraints(const std::vector<moveit_msgs::Constraints> &goal_constraints,
00352 const moveit_msgs::Constraints &path_constraints,
00353 moveit_msgs::MoveItErrorCodes *error)
00354 {
00355
00356 goal_constraints_.clear();
00357 for (std::size_t i = 0 ; i < goal_constraints.size() ; ++i)
00358 {
00359 moveit_msgs::Constraints constr = kinematic_constraints::mergeConstraints(goal_constraints[i], path_constraints);
00360 kinematic_constraints::KinematicConstraintSetPtr kset(new kinematic_constraints::KinematicConstraintSet(getRobotModel()));
00361 kset->add(constr, getPlanningScene()->getTransforms());
00362 if (!kset->empty())
00363 goal_constraints_.push_back(kset);
00364 }
00365
00366 if (goal_constraints_.empty())
00367 {
00368 logWarn("%s: No goal constraints specified. There is no problem to solve.", name_.c_str());
00369 if (error)
00370 error->val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
00371 return false;
00372 }
00373
00374 ob::GoalPtr goal = constructGoal();
00375 ompl_simple_setup_->setGoal(goal);
00376 if (goal)
00377 return true;
00378 else
00379 return false;
00380 }
00381
00382 bool ompl_interface::ModelBasedPlanningContext::benchmark(double timeout, unsigned int count, const std::string &filename)
00383 {
00384 ompl_benchmark_.clearPlanners();
00385 ompl_simple_setup_->setup();
00386 ompl_benchmark_.addPlanner(ompl_simple_setup_->getPlanner());
00387 ompl_benchmark_.setExperimentName(getRobotModel()->getName() + "_" + getGroupName() + "_" +
00388 getPlanningScene()->getName() + "_" + name_);
00389
00390 ot::Benchmark::Request req;
00391 req.maxTime = timeout;
00392 req.runCount = count;
00393 req.displayProgress = true;
00394 req.saveConsoleOutput = false;
00395 ompl_benchmark_.benchmark(req);
00396 return filename.empty() ? ompl_benchmark_.saveResultsToFile() : ompl_benchmark_.saveResultsToFile(filename.c_str());
00397 }
00398
00399 void ompl_interface::ModelBasedPlanningContext::startSampling()
00400 {
00401 bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
00402 if (gls)
00403 static_cast<ob::GoalLazySamples*>(ompl_simple_setup_->getGoal().get())->startSampling();
00404 else
00405
00406 static_cast<GoalSampleableRegionMux*>(ompl_simple_setup_->getGoal().get())->startSampling();
00407 }
00408
00409 void ompl_interface::ModelBasedPlanningContext::stopSampling()
00410 {
00411 bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
00412 if (gls)
00413 static_cast<ob::GoalLazySamples*>(ompl_simple_setup_->getGoal().get())->stopSampling();
00414 else
00415
00416 static_cast<GoalSampleableRegionMux*>(ompl_simple_setup_->getGoal().get())->stopSampling();
00417 }
00418
00419 void ompl_interface::ModelBasedPlanningContext::preSolve()
00420 {
00421
00422 ompl_simple_setup_->getProblemDefinition()->clearSolutionPaths();
00423 const ob::PlannerPtr planner = ompl_simple_setup_->getPlanner();
00424 if (planner)
00425 planner->clear();
00426 startSampling();
00427 ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
00428 }
00429
00430 void ompl_interface::ModelBasedPlanningContext::postSolve()
00431 {
00432 stopSampling();
00433 int v = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getValidMotionCount();
00434 int iv = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getInvalidMotionCount();
00435 logDebug("There were %d valid motions and %d invalid motions.", v, iv);
00436
00437 if (ompl_simple_setup_->getProblemDefinition()->hasApproximateSolution())
00438 logWarn("Computed solution is approximate");
00439 }
00440
00441 bool ompl_interface::ModelBasedPlanningContext::solve(planning_interface::MotionPlanResponse &res)
00442 {
00443 if (solve(request_.allowed_planning_time, request_.num_planning_attempts))
00444 {
00445 double ptime = getLastPlanTime();
00446 if (simplify_solutions_ && ptime < request_.allowed_planning_time)
00447 {
00448 simplifySolution(request_.allowed_planning_time - ptime);
00449 ptime += getLastSimplifyTime();
00450 }
00451 interpolateSolution();
00452
00453
00454 logDebug("%s: Returning successful solution with %lu states", getName().c_str(),
00455 getOMPLSimpleSetup()->getSolutionPath().getStateCount());
00456
00457 res.trajectory_.reset(new robot_trajectory::RobotTrajectory(getRobotModel(), getGroupName()));
00458 getSolutionPath(*res.trajectory_);
00459 res.planning_time_ = ptime;
00460 return true;
00461 }
00462 else
00463 {
00464 logInform("Unable to solve the planning problem");
00465 res.error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
00466 return false;
00467 }
00468 }
00469
00470 bool ompl_interface::ModelBasedPlanningContext::solve(planning_interface::MotionPlanDetailedResponse &res)
00471 {
00472 if (solve(request_.allowed_planning_time, request_.num_planning_attempts))
00473 {
00474 res.trajectory_.reserve(3);
00475
00476
00477 double ptime = getLastPlanTime();
00478 res.processing_time_.push_back(ptime);
00479 res.description_.push_back("plan");
00480 res.trajectory_.resize(res.trajectory_.size() + 1);
00481 res.trajectory_.back().reset(new robot_trajectory::RobotTrajectory(getRobotModel(), getGroupName()));
00482 getSolutionPath(*res.trajectory_.back());
00483
00484
00485 if (simplify_solutions_ && ptime < request_.allowed_planning_time)
00486 {
00487 simplifySolution(request_.allowed_planning_time - ptime);
00488 res.processing_time_.push_back(getLastSimplifyTime());
00489 res.description_.push_back("simplify");
00490 res.trajectory_.resize(res.trajectory_.size() + 1);
00491 res.trajectory_.back().reset(new robot_trajectory::RobotTrajectory(getRobotModel(), getGroupName()));
00492 getSolutionPath(*res.trajectory_.back());
00493 }
00494
00495 ompl::time::point start_interpolate = ompl::time::now();
00496 interpolateSolution();
00497 res.processing_time_.push_back(ompl::time::seconds(ompl::time::now() - start_interpolate));
00498 res.description_.push_back("interpolate");
00499 res.trajectory_.resize(res.trajectory_.size() + 1);
00500 res.trajectory_.back().reset(new robot_trajectory::RobotTrajectory(getRobotModel(), getGroupName()));
00501 getSolutionPath(*res.trajectory_.back());
00502
00503
00504 logDebug("%s: Returning successful solution with %lu states", getName().c_str(),
00505 getOMPLSimpleSetup()->getSolutionPath().getStateCount());
00506 return true;
00507 }
00508 else
00509 {
00510 logInform("Unable to solve the planning problem");
00511 res.error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
00512 return false;
00513 }
00514 }
00515
00516 bool ompl_interface::ModelBasedPlanningContext::solve(double timeout, unsigned int count)
00517 {
00518 moveit::tools::Profiler::ScopedBlock sblock("PlanningContext:Solve");
00519 ompl::time::point start = ompl::time::now();
00520 preSolve();
00521
00522 bool result = false;
00523 if (count <= 1)
00524 {
00525 logDebug("%s: Solving the planning problem once...", name_.c_str());
00526 ob::PlannerTerminationCondition ptc = ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
00527 registerTerminationCondition(ptc);
00528 result = ompl_simple_setup_->solve(ptc) == ompl::base::PlannerStatus::EXACT_SOLUTION;
00529 last_plan_time_ = ompl_simple_setup_->getLastPlanComputationTime();
00530 unregisterTerminationCondition();
00531 }
00532 else
00533 {
00534 logDebug("%s: Solving the planning problem %u times...", name_.c_str(), count);
00535 ompl_parallel_plan_.clearHybridizationPaths();
00536 if (count <= max_planning_threads_)
00537 {
00538 ompl_parallel_plan_.clearPlanners();
00539 if (ompl_simple_setup_->getPlannerAllocator())
00540 for (unsigned int i = 0 ; i < count ; ++i)
00541 ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
00542 else
00543 for (unsigned int i = 0 ; i < count ; ++i)
00544 ompl_parallel_plan_.addPlanner(ompl::geometric::getDefaultPlanner(ompl_simple_setup_->getGoal()));
00545
00546 ob::PlannerTerminationCondition ptc = ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
00547 registerTerminationCondition(ptc);
00548 result = ompl_parallel_plan_.solve(ptc, 1, count, true) == ompl::base::PlannerStatus::EXACT_SOLUTION;
00549 last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
00550 unregisterTerminationCondition();
00551 }
00552 else
00553 {
00554 ob::PlannerTerminationCondition ptc = ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
00555 registerTerminationCondition(ptc);
00556 int n = count / max_planning_threads_;
00557 result = true;
00558 for (int i = 0 ; i < n && ptc() == false ; ++i)
00559 {
00560 ompl_parallel_plan_.clearPlanners();
00561 if (ompl_simple_setup_->getPlannerAllocator())
00562 for (unsigned int i = 0 ; i < max_planning_threads_ ; ++i)
00563 ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
00564 else
00565 for (unsigned int i = 0 ; i < max_planning_threads_ ; ++i)
00566 ompl_parallel_plan_.addPlanner(og::getDefaultPlanner(ompl_simple_setup_->getGoal()));
00567 bool r = ompl_parallel_plan_.solve(ptc, 1, count, true) == ompl::base::PlannerStatus::EXACT_SOLUTION;
00568 result = result && r;
00569 }
00570 n = count % max_planning_threads_;
00571 if (n && ptc() == false)
00572 {
00573 ompl_parallel_plan_.clearPlanners();
00574 if (ompl_simple_setup_->getPlannerAllocator())
00575 for (int i = 0 ; i < n ; ++i)
00576 ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
00577 else
00578 for (int i = 0 ; i < n ; ++i)
00579 ompl_parallel_plan_.addPlanner(og::getDefaultPlanner(ompl_simple_setup_->getGoal()));
00580 bool r = ompl_parallel_plan_.solve(ptc, 1, count, true) == ompl::base::PlannerStatus::EXACT_SOLUTION;
00581 result = result && r;
00582 }
00583 last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
00584 unregisterTerminationCondition();
00585 }
00586 }
00587
00588 postSolve();
00589
00590 return result;
00591 }
00592
00593 void ompl_interface::ModelBasedPlanningContext::registerTerminationCondition(const ob::PlannerTerminationCondition &ptc)
00594 {
00595 boost::mutex::scoped_lock slock(ptc_lock_);
00596 ptc_ = &ptc;
00597 }
00598
00599 void ompl_interface::ModelBasedPlanningContext::unregisterTerminationCondition()
00600 {
00601 boost::mutex::scoped_lock slock(ptc_lock_);
00602 ptc_ = NULL;
00603 }
00604
00605 bool ompl_interface::ModelBasedPlanningContext::terminate()
00606 {
00607 boost::mutex::scoped_lock slock(ptc_lock_);
00608 if (ptc_)
00609 ptc_->terminate();
00610 return true;
00611 }