Public Member Functions |
| Planner (const SpaceInformationPtr &si, const std::string &name) |
| Constructor.
|
virtual | ~Planner (void) |
| Destructor.
|
template<class T > |
T * | as (void) |
| Cast this instance to a desired type.
|
template<class T > |
const T * | as (void) const |
| Cast this instance to a desired type.
|
const SpaceInformationPtr & | getSpaceInformation (void) const |
| Get the space information this planner is using.
|
const ProblemDefinitionPtr & | getProblemDefinition (void) const |
| Get the problem definition the planner is trying to solve.
|
const PlannerInputStates & | getPlannerInputStates (void) const |
| Get the planner input states.
|
virtual void | setProblemDefinition (const ProblemDefinitionPtr &pdef) |
| Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear().
|
virtual bool | solve (const PlannerTerminationCondition &ptc)=0 |
| Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). The function terminates if the call to ptc returns true.
|
bool | solve (const PlannerTerminationConditionFn &ptc, double checkInterval) |
| Same as above except the termination condition is only evaluated at a specified interval.
|
bool | solve (double solveTime) |
| Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning.
|
virtual void | clear (void) |
| Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
|
virtual void | getPlannerData (PlannerData &data) const |
| Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).
|
const std::string & | getName (void) const |
| Get the name of the planner.
|
void | setName (const std::string &name) |
| Set the name of the planner.
|
const PlannerSpecs & | getSpecs (void) const |
| Return the specifications (capabilities of this planner)
|
virtual void | setup (void) |
| Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving.
|
virtual void | checkValidity (void) |
| Check to see if the planner is in a working state (setup has been called, a goal was set, the input states seem to be in order). In case of error, this function throws an exception.
|
bool | isSetup (void) const |
| Check if setup() was called for this planner.
|
Protected Attributes |
SpaceInformationPtr | si_ |
| The space information for which planning is done.
|
ProblemDefinitionPtr | pdef_ |
| The user set problem definition.
|
PlannerInputStates | pis_ |
| Utility class to extract valid input states.
|
std::string | name_ |
| The name of this planner.
|
PlannerSpecs | specs_ |
| The specifications of the planner (its capabilities)
|
bool | setup_ |
| Flag indicating whether setup() has been called.
|
msg::Interface | msg_ |
| Console interface.
|
Base class for a planner.
Definition at line 223 of file Planner.h.