Helper class to extract valid start & goal states. Usually used internally by planners. More...
#include <Planner.h>
Public Member Functions | |
void | checkValidity (void) const |
Check if the problem definition was set, start state are available and goal was set. | |
void | clear (void) |
Clear all stored information. | |
unsigned int | getSampledGoalsCount (void) const |
Get the number of sampled goal states, including invalid ones. | |
unsigned int | getSeenStartStatesCount (void) const |
Get the number of start states from the problem definition that were already seen, including invalid ones. | |
bool | haveMoreGoalStates (void) const |
Check if there are more potential start states. | |
bool | haveMoreStartStates (void) const |
Check if there are more potential start states. | |
const State * | nextGoal (void) |
Same as above but only one attempt is made to find a valid goal. | |
const State * | nextGoal (const PlannerTerminationCondition &ptc) |
Return the next valid goal state or NULL if no more valid goal states are available. Because sampling of goal states may also produce invalid goals, this function takes an argument that specifies whether a termination condition has been reached. If the termination condition evaluates to true the function terminates even if no valid goal has been found. | |
const State * | nextStart (void) |
Return the next valid start state or NULL if no more valid start states are available. | |
PlannerInputStates (void) | |
Default constructor. No work is performed. A call to use() needs to be made, before making any calls to nextStart() or nextGoal(). | |
PlannerInputStates (const Planner *planner) | |
Default constructor. No work is performed. | |
PlannerInputStates (const PlannerPtr &planner) | |
Default constructor. No work is performed. | |
bool | update (void) |
Set the space information and problem definition this class operates on, based on the available planner instance. Returns true if changes were found (different problem definition) and clear() was called. | |
bool | use (const SpaceInformation *si, const ProblemDefinition *pdef) |
Set the space information and problem definition this class operates on, based on the available planner instance. If a planner is not set in the constructor argument, a call to this function is needed before any calls to nextStart() or nextGoal() are made. Returns true if changes were found (different problem definition) and clear() was called. | |
bool | use (const SpaceInformationPtr &si, const ProblemDefinitionPtr &pdef) |
Set the space information and problem definition this class operates on, based on the available planner instance. If a planner is not set in the constructor argument, a call to this function is needed before any calls to nextStart() or nextGoal() are made. Returns true if changes were found (different problem definition) and clear() was called. | |
~PlannerInputStates (void) | |
Destructor. Clear allocated memory. | |
Private Attributes | |
unsigned int | addedStartStates_ |
const ProblemDefinition * | pdef_ |
const Planner * | planner_ |
unsigned int | sampledGoalsCount_ |
const SpaceInformation * | si_ |
State * | tempState_ |
Helper class to extract valid start & goal states. Usually used internally by planners.
This class is meant to behave correctly if the user updates the problem definition between subsequent calls to ompl::base::Planner::solve() without calling ompl::base::Planner::clear() in between. Only allowed changes to the problem definition are accounted for: adding of starring states or adding of goal states for instances inherited from ompl::base::GoalSampleableRegion.
Definition at line 90 of file Planner.h.
ompl::base::PlannerInputStates::PlannerInputStates | ( | const PlannerPtr & | planner | ) | [inline] |
ompl::base::PlannerInputStates::PlannerInputStates | ( | const Planner * | planner | ) | [inline] |
ompl::base::PlannerInputStates::PlannerInputStates | ( | void | ) | [inline] |
Default constructor. No work is performed. A call to use() needs to be made, before making any calls to nextStart() or nextGoal().
ompl::base::PlannerInputStates::~PlannerInputStates | ( | void | ) | [inline] |
void ompl::base::PlannerInputStates::checkValidity | ( | void | ) | const |
Check if the problem definition was set, start state are available and goal was set.
void ompl::base::PlannerInputStates::clear | ( | void | ) |
Clear all stored information.
unsigned int ompl::base::PlannerInputStates::getSampledGoalsCount | ( | void | ) | const [inline] |
unsigned int ompl::base::PlannerInputStates::getSeenStartStatesCount | ( | void | ) | const [inline] |
bool ompl::base::PlannerInputStates::haveMoreGoalStates | ( | void | ) | const |
Check if there are more potential start states.
bool ompl::base::PlannerInputStates::haveMoreStartStates | ( | void | ) | const |
Check if there are more potential start states.
const State* ompl::base::PlannerInputStates::nextGoal | ( | void | ) |
Same as above but only one attempt is made to find a valid goal.
const State* ompl::base::PlannerInputStates::nextGoal | ( | const PlannerTerminationCondition & | ptc | ) |
Return the next valid goal state or NULL if no more valid goal states are available. Because sampling of goal states may also produce invalid goals, this function takes an argument that specifies whether a termination condition has been reached. If the termination condition evaluates to true the function terminates even if no valid goal has been found.
const State* ompl::base::PlannerInputStates::nextStart | ( | void | ) |
Return the next valid start state or NULL if no more valid start states are available.
bool ompl::base::PlannerInputStates::update | ( | void | ) |
Set the space information and problem definition this class operates on, based on the available planner instance. Returns true if changes were found (different problem definition) and clear() was called.
bool ompl::base::PlannerInputStates::use | ( | const SpaceInformation * | si, | |
const ProblemDefinition * | pdef | |||
) |
Set the space information and problem definition this class operates on, based on the available planner instance. If a planner is not set in the constructor argument, a call to this function is needed before any calls to nextStart() or nextGoal() are made. Returns true if changes were found (different problem definition) and clear() was called.
bool ompl::base::PlannerInputStates::use | ( | const SpaceInformationPtr & | si, | |
const ProblemDefinitionPtr & | pdef | |||
) |
Set the space information and problem definition this class operates on, based on the available planner instance. If a planner is not set in the constructor argument, a call to this function is needed before any calls to nextStart() or nextGoal() are made. Returns true if changes were found (different problem definition) and clear() was called.
unsigned int ompl::base::PlannerInputStates::addedStartStates_ [private] |
const ProblemDefinition* ompl::base::PlannerInputStates::pdef_ [private] |
const Planner* ompl::base::PlannerInputStates::planner_ [private] |
unsigned int ompl::base::PlannerInputStates::sampledGoalsCount_ [private] |
const SpaceInformation* ompl::base::PlannerInputStates::si_ [private] |
State* ompl::base::PlannerInputStates::tempState_ [private] |