Definition of a set of goal states. More...
#include <GoalStates.h>

Public Member Functions | |
| void | addState (const ScopedState<> &st) |
| Add a goal state (calls the previous definition of addState()). | |
| virtual void | addState (const State *st) |
| Add a goal state. | |
| virtual void | clear (void) |
| Clear all goal states. | |
| virtual double | distanceGoal (const State *st) const |
| Compute the distance to the goal (heuristic). This function is the one used in computing the distance to the goal in a call to isSatisfied(). | |
| GoalStates (const SpaceInformationPtr &si) | |
| Create a goal representation that is in fact a set of states. | |
| bool | hasStates (void) const |
| Check if there are any states in this goal region. | |
| virtual unsigned int | maxSampleCount (void) const |
| Return the maximum number of samples that can be asked for before repeating. | |
| virtual void | print (std::ostream &out=std::cout) const |
| Print information about the goal data structure to a stream. | |
| virtual void | sampleGoal (State *st) const |
| Sample a state in the goal region. | |
| virtual | ~GoalStates (void) |
Public Attributes | |
| std::vector< State * > | states |
| The goal states. Only ones that are valid are considered by the motion planner. | |
Private Member Functions | |
| void | freeMemory (void) |
| Free allocated memory. | |
Private Attributes | |
| unsigned int | samplePosition |
| The index of the next sample to be returned. | |
Definition of a set of goal states.
Definition at line 50 of file GoalStates.h.
| ompl::base::GoalStates::GoalStates | ( | const SpaceInformationPtr & | si | ) | [inline] |
Create a goal representation that is in fact a set of states.
Definition at line 55 of file GoalStates.h.
| virtual ompl::base::GoalStates::~GoalStates | ( | void | ) | [virtual] |
| void ompl::base::GoalStates::addState | ( | const ScopedState<> & | st | ) |
Add a goal state (calls the previous definition of addState()).
| virtual void ompl::base::GoalStates::addState | ( | const State * | st | ) | [virtual] |
Add a goal state.
Reimplemented in ompl::base::GoalLazySamples.
| virtual void ompl::base::GoalStates::clear | ( | void | ) | [virtual] |
Clear all goal states.
Reimplemented in ompl::base::GoalLazySamples.
| virtual double ompl::base::GoalStates::distanceGoal | ( | const State * | st | ) | const [virtual] |
Compute the distance to the goal (heuristic). This function is the one used in computing the distance to the goal in a call to isSatisfied().
Implements ompl::base::GoalRegion.
Reimplemented in ompl::base::GoalLazySamples.
| void ompl::base::GoalStates::freeMemory | ( | void | ) | [private] |
Free allocated memory.
| bool ompl::base::GoalStates::hasStates | ( | void | ) | const [inline] |
Check if there are any states in this goal region.
Definition at line 79 of file GoalStates.h.
| virtual unsigned int ompl::base::GoalStates::maxSampleCount | ( | void | ) | const [virtual] |
Return the maximum number of samples that can be asked for before repeating.
Implements ompl::base::GoalSampleableRegion.
| virtual void ompl::base::GoalStates::print | ( | std::ostream & | out = std::cout |
) | const [virtual] |
Print information about the goal data structure to a stream.
Reimplemented from ompl::base::GoalRegion.
| virtual void ompl::base::GoalStates::sampleGoal | ( | State * | st | ) | const [virtual] |
Sample a state in the goal region.
Implements ompl::base::GoalSampleableRegion.
Reimplemented in ompl::base::GoalLazySamples.
unsigned int ompl::base::GoalStates::samplePosition [mutable, private] |
The index of the next sample to be returned.
Definition at line 90 of file GoalStates.h.
| std::vector<State*> ompl::base::GoalStates::states |
The goal states. Only ones that are valid are considered by the motion planner.
Definition at line 85 of file GoalStates.h.