Base class for a planner. More...
#include <Planner.h>
Public Member Functions | |
template<class T > | |
const T * | as (void) const |
Cast this instance to a desired type. | |
template<class T > | |
T * | as (void) |
Cast this instance to a desired type. | |
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. q. | |
virtual void | clear (void) |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
const std::string & | getName (void) const |
Get the name of the planner. | |
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 PlannerInputStates & | getPlannerInputStates (void) const |
Get the planner input states. | |
const ProblemDefinitionPtr & | getProblemDefinition (void) const |
Get the problem definition the planner is trying to solve. | |
const SpaceInformationPtr & | getSpaceInformation (void) const |
Get the space information this planner is using. | |
PlannerType | getType (void) const |
Return the type of the motion planner. This is useful if the planner wants to advertise what type of problems it can solve. | |
bool | isSetup (void) const |
Check if setup() was called for this planner. | |
Planner (const SpaceInformationPtr &si, const std::string &name) | |
Constructor. | |
void | setName (const std::string &name) |
Set the name of the planner. | |
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 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. | |
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. | |
bool | solve (const PlannerTerminationConditionFn &ptc, double checkInterval) |
Same as above except the termination condition is only evaluated at a specified interval. | |
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. | |
virtual | ~Planner (void) |
Destructor. | |
Protected Attributes | |
msg::Interface | msg_ |
Console interface. | |
std::string | name_ |
The name of this planner. | |
ProblemDefinitionPtr | pdef_ |
The user set problem definition. | |
PlannerInputStates | pis_ |
Utility class to extract valid input states. | |
bool | setup_ |
Flag indicating whether setup() has been called. | |
SpaceInformationPtr | si_ |
The space information for which planning is done. | |
PlannerType | type_ |
The planner type: defines the type of goals this planner can handle. |
Base class for a planner.
Definition at line 207 of file Planner.h.
ompl::base::Planner::Planner | ( | const SpaceInformationPtr & | si, | |
const std::string & | name | |||
) |
Constructor.
virtual ompl::base::Planner::~Planner | ( | void | ) | [inline, virtual] |
const T* ompl::base::Planner::as | ( | void | ) | const [inline] |
T* ompl::base::Planner::as | ( | void | ) | [inline] |
virtual void ompl::base::Planner::checkValidity | ( | void | ) | [virtual] |
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. q.
virtual void ompl::base::Planner::clear | ( | void | ) | [virtual] |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
Reimplemented in ompl::control::KPIECE1, ompl::control::RRT, ompl::geometric::EST, ompl::geometric::BKPIECE1, ompl::geometric::KPIECE1, ompl::geometric::LBKPIECE1, ompl::geometric::BasicPRM, ompl::geometric::LazyRRT, ompl::geometric::pRRT, ompl::geometric::RRT, ompl::geometric::RRTConnect, ompl::geometric::pSBL, and ompl::geometric::SBL.
const std::string& ompl::base::Planner::getName | ( | void | ) | const |
Get the name of the planner.
virtual void ompl::base::Planner::getPlannerData | ( | PlannerData & | data | ) | const [virtual] |
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).
Reimplemented in ompl::control::KPIECE1, ompl::control::RRT, ompl::geometric::EST, ompl::geometric::BKPIECE1, ompl::geometric::KPIECE1, ompl::geometric::LBKPIECE1, ompl::geometric::BasicPRM, ompl::geometric::LazyRRT, ompl::geometric::pRRT, ompl::geometric::RRT, ompl::geometric::RRTConnect, ompl::geometric::pSBL, and ompl::geometric::SBL.
const PlannerInputStates& ompl::base::Planner::getPlannerInputStates | ( | void | ) | const |
Get the planner input states.
const ProblemDefinitionPtr& ompl::base::Planner::getProblemDefinition | ( | void | ) | const |
Get the problem definition the planner is trying to solve.
const SpaceInformationPtr& ompl::base::Planner::getSpaceInformation | ( | void | ) | const |
Get the space information this planner is using.
PlannerType ompl::base::Planner::getType | ( | void | ) | const |
Return the type of the motion planner. This is useful if the planner wants to advertise what type of problems it can solve.
bool ompl::base::Planner::isSetup | ( | void | ) | const |
Check if setup() was called for this planner.
void ompl::base::Planner::setName | ( | const std::string & | name | ) |
Set the name of the planner.
virtual void ompl::base::Planner::setProblemDefinition | ( | const ProblemDefinitionPtr & | pdef | ) | [virtual] |
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().
Reimplemented in ompl::geometric::BasicPRM.
virtual void ompl::base::Planner::setup | ( | void | ) | [virtual] |
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.
Reimplemented in ompl::control::KPIECE1, ompl::control::RRT, ompl::geometric::EST, ompl::geometric::BKPIECE1, ompl::geometric::KPIECE1, ompl::geometric::LBKPIECE1, ompl::geometric::BasicPRM, ompl::geometric::LazyRRT, ompl::geometric::pRRT, ompl::geometric::RRT, ompl::geometric::RRTConnect, ompl::geometric::pSBL, and ompl::geometric::SBL.
bool ompl::base::Planner::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.
bool ompl::base::Planner::solve | ( | const PlannerTerminationConditionFn & | ptc, | |
double | checkInterval | |||
) |
Same as above except the termination condition is only evaluated at a specified interval.
virtual bool ompl::base::Planner::solve | ( | const PlannerTerminationCondition & | ptc | ) | [pure virtual] |
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.
Implemented in ompl::control::KPIECE1, ompl::control::RRT, ompl::geometric::EST, ompl::geometric::BKPIECE1, ompl::geometric::KPIECE1, ompl::geometric::LBKPIECE1, ompl::geometric::BasicPRM, ompl::geometric::LazyRRT, ompl::geometric::pRRT, ompl::geometric::RRT, ompl::geometric::RRTConnect, ompl::geometric::pSBL, and ompl::geometric::SBL.
msg::Interface ompl::base::Planner::msg_ [protected] |
std::string ompl::base::Planner::name_ [protected] |
ProblemDefinitionPtr ompl::base::Planner::pdef_ [protected] |
PlannerInputStates ompl::base::Planner::pis_ [protected] |
bool ompl::base::Planner::setup_ [protected] |
SpaceInformationPtr ompl::base::Planner::si_ [protected] |
PlannerType ompl::base::Planner::type_ [protected] |