37 #include "ompl/control/SimpleSetup.h"
38 #include "ompl/control/planners/rrt/RRT.h"
39 #include "ompl/control/planners/kpiece/KPIECE1.h"
45 throw Exception(
"Unable to allocate default planner for unspecified goal definition");
48 if (si->getStateSpace()->hasDefaultProjection())
57 configured_(false), planTime_(0.0), last_status_(base::PlannerStatus::UNKNOWN)
66 if (!configured_ || !si_->isSetup() || !planner_->isSetup())
76 OMPL_INFORM(
"No planner specified. Using default.");
80 planner_->setProblemDefinition(pdef_);
81 if (!planner_->isSetup())
85 params_.include(si_->params());
86 params_.include(planner_->params());
96 pdef_->clearSolutionPaths();
105 last_status_ = planner_->solve(time);
108 OMPL_INFORM(
"Solution found in %f seconds", planTime_);
110 OMPL_INFORM(
"No solution found after %f seconds", planTime_);
119 last_status_ = planner_->solve(ptc);
122 OMPL_INFORM(
"Solution found in %f seconds", planTime_);
124 OMPL_INFORM(
"No solution found after %f seconds", planTime_);
141 return haveSolutionPath() && (!pdef_->hasApproximateSolution() || pdef_->getSolutionDifference() < std::numeric_limits<double>::epsilon());
148 planner_->getPlannerData(pd);
155 si_->printProperties(out);
156 si_->printSettings(out);
160 planner_->printProperties(out);
161 planner_->printSettings(out);
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
void include(const ParamSet &other, const std::string &prefix="")
Include the params of a different ParamSet into this one. Optionally include a prefix for each of the...
base::ProblemDefinitionPtr pdef_
The created problem definition.
base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal)
Given a goal specification, decide on a planner for that goal.
virtual void clear(void)
Clear all planning data. This only includes data generated by motion plan computation. Planner settings, start & goal states are not affected.
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition of a control path.
SimpleSetup(const ControlSpacePtr &space)
Constructor needs the control space used for planning.
virtual base::PlannerStatus solve(double time=1.0)
Run the planner for a specified amount of time (default is 1 second)
A boost shared pointer wrapper for ompl::control::ControlSpace.
duration seconds(double sec)
Return the time duration representing a given number of seconds.
A boost shared pointer wrapper for ompl::base::Planner.
virtual void setup(void)
This method will create the necessary classes for planning. The solve() method will call this functio...
boost::posix_time::ptime point
Representation of a point in time.
base::ParamSet params_
The parameters that describe the planning context.
A class to store the exit status of Planner::solve()
virtual void print(std::ostream &out=std::cout) const
Print information about the current setup.
PathControl & getSolutionPath(void) const
Get the solution path. Throw an exception if no solution is available.
void getPlannerData(base::PlannerData &pd) const
Get information about the exploration data structure the motion planner used.
Kinodynamic Planning by Interior-Exterior Cell Exploration.
SpaceInformationPtr si_
The created space information.
The exception type for ompl.
Definition of a problem to be solved. This includes the start state(s) for the system and a goal spec...
bool haveExactSolutionPath(void) const
Return true if a solution path is available (previous call to solve() was successful) and the solutio...
Rapidly-exploring Random Tree.
A boost shared pointer wrapper for ompl::base::Goal.
virtual void clear(void)
Clears the entire data structure.
point now(void)
Get the current time point.
A boost shared pointer wrapper for ompl::base::Path.
#define OMPL_INFORM(fmt,...)
Log a formatted information string.