Loading...
Searching...
No Matches
ompl::base::GoalStates Class Reference

Definition of a set of goal states. More...

#include <ompl/base/goals/GoalStates.h>

Inheritance diagram for ompl::base::GoalStates:

Public Member Functions

 GoalStates (const SpaceInformationPtr &si)
 Create a goal representation that is in fact a set of states

 
void sampleGoal (State *st) const override
 Sample a state in the goal region.
 
unsigned int maxSampleCount () const override
 Return the maximum number of samples that can be asked for before repeating.
 
double distanceGoal (const State *st) const override
 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()
 
void print (std::ostream &out=std::cout) const override
 Print information about the goal data structure to a stream.
 
virtual void addState (const State *st)
 Add a goal state.
 
void addState (const ScopedState<> &st)
 Add a goal state (calls the previous definition of addState())
 
virtual void clear ()
 Clear all goal states.
 
virtual bool hasStates () const
 Check if there are any states in this goal region.
 
virtual const StategetState (unsigned int index) const
 Return a pointer to the indexth state in the state list.
 
virtual std::size_t getStateCount () const
 Return the number of valid goal states.
 
- Public Member Functions inherited from ompl::base::GoalSampleableRegion
 GoalSampleableRegion (const SpaceInformationPtr &si)
 Create a goal region that can be sampled.
 
virtual void sampleGoal (State *st) const =0
 Sample a state in the goal region.
 
virtual unsigned int maxSampleCount () const =0
 Return the maximum number of samples that can be asked for before repeating.
 
bool canSample () const
 Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
 
virtual bool couldSample () const
 Return true if samples could be generated by this sampler at some point in the future. By default this is equivalent to canSample(), but for GoalLazySamples, this call also reflects the fact that a sampling thread is active and although no samples are produced yet, some may become available at some point in the future.
 
- Public Member Functions inherited from ompl::base::GoalRegion
 GoalRegion (const SpaceInformationPtr &si)
 Create a goal region.
 
bool isSatisfied (const State *st) const override
 Equivalent to calling isSatisfied(const State *, double *) with a nullptr second argument.
 
bool isSatisfied (const State *st, double *distance) const override
 Decide whether a given state is part of the goal region. Returns true if the distance to goal is less than the threshold (using distanceGoal())
 
virtual double distanceGoal (const State *st) const =0
 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()
 
void print (std::ostream &out=std::cout) const override
 Print information about the goal data structure to a stream.
 
void setThreshold (double threshold)
 Set the distance to the goal that is allowed for a state to be considered in the goal region.
 
double getThreshold () const
 Get the distance to the goal that is allowed for a state to be considered in the goal region.
 
- Public Member Functions inherited from ompl::base::Goal
 Goal (const Goal &)=delete
 
Goaloperator= (const Goal &)=delete
 
 Goal (SpaceInformationPtr si)
 Constructor. The goal must always know the space information it is part of.
 
virtual ~Goal ()=default
 Destructor.
 
template<class T >
T * as ()
 Cast this instance to a desired type.
 
template<class T >
const T * as () const
 Cast this instance to a desired type.
 
GoalType getType () const
 Return the goal type.
 
bool hasType (GoalType type) const
 Check if this goal can be cast to a particular goal type.
 
const SpaceInformationPtrgetSpaceInformation () const
 Get the space information this goal is for.
 
virtual bool isSatisfied (const State *st) const =0
 Return true if the state satisfies the goal constraints.
 
virtual bool isSatisfied (const State *st, double *distance) const
 Return true if the state satisfies the goal constraints and compute the distance between the state given as argument and the goal (even if the goal is not satisfied). This distance can be an approximation. It can even be set to a constant, if such a computation is not possible.
 
virtual bool isStartGoalPairValid (const State *, const State *) const
 Since there can be multiple starting states (and multiple goal states) it is possible certain pairs are not to be allowed. By default we however assume all such pairs are allowed. Note: if this function returns true, isSatisfied() need not be called.
 
virtual void print (std::ostream &out=std::cout) const
 Print information about the goal.
 

Protected Attributes

std::vector< State * > states_
 The goal states. Only ones that are valid are considered by the motion planner.
 
- Protected Attributes inherited from ompl::base::GoalRegion
double threshold_
 The maximum distance that is allowed to the goal. By default, this is initialized to the minimum epsilon value a double can represent.
 
- Protected Attributes inherited from ompl::base::Goal
GoalType type_
 Goal type.
 
SpaceInformationPtr si_
 The space information for this goal.
 

Detailed Description

Definition of a set of goal states.

Definition at line 49 of file GoalStates.h.

Constructor & Destructor Documentation

◆ GoalStates()

ompl::base::GoalStates::GoalStates ( const SpaceInformationPtr si)
inline

Create a goal representation that is in fact a set of states

Definition at line 53 of file GoalStates.h.

◆ ~GoalStates()

ompl::base::GoalStates::~GoalStates ( )
override

Definition at line 42 of file GoalStates.cpp.

Member Function Documentation

◆ addState() [1/2]

void ompl::base::GoalStates::addState ( const ScopedState<> &  st)

Add a goal state (calls the previous definition of addState())

Definition at line 104 of file GoalStates.cpp.

◆ addState() [2/2]

void ompl::base::GoalStates::addState ( const State st)
virtual

Add a goal state.

Reimplemented in ompl::base::GoalLazySamples.

Definition at line 99 of file GoalStates.cpp.

◆ clear()

void ompl::base::GoalStates::clear ( )
virtual

Clear all goal states.

Reimplemented in ompl::base::GoalLazySamples.

Definition at line 47 of file GoalStates.cpp.

◆ distanceGoal()

double ompl::base::GoalStates::distanceGoal ( const State st) const
overridevirtual

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 PlanarManipulatorIKGoal.

Definition at line 59 of file GoalStates.cpp.

◆ getState()

const ompl::base::State * ompl::base::GoalStates::getState ( unsigned int  index) const
virtual

Return a pointer to the indexth state in the state list.

Reimplemented in ompl::base::GoalLazySamples.

Definition at line 109 of file GoalStates.cpp.

◆ getStateCount()

std::size_t ompl::base::GoalStates::getStateCount ( ) const
virtual

Return the number of valid goal states.

Reimplemented in ompl::base::GoalLazySamples.

Definition at line 117 of file GoalStates.cpp.

◆ hasStates()

bool ompl::base::GoalStates::hasStates ( ) const
virtual

Check if there are any states in this goal region.

Reimplemented in ompl::base::GoalLazySamples.

Definition at line 122 of file GoalStates.cpp.

◆ maxSampleCount()

unsigned int ompl::base::GoalStates::maxSampleCount ( ) const
overridevirtual

Return the maximum number of samples that can be asked for before repeating.

Implements ompl::base::GoalSampleableRegion.

Definition at line 94 of file GoalStates.cpp.

◆ print()

void ompl::base::GoalStates::print ( std::ostream &  out = std::cout) const
overridevirtual

Print information about the goal data structure to a stream.

Reimplemented from ompl::base::GoalRegion.

Definition at line 71 of file GoalStates.cpp.

◆ sampleGoal()

void ompl::base::GoalStates::sampleGoal ( State st) const
overridevirtual

Sample a state in the goal region.

Implements ompl::base::GoalSampleableRegion.

Definition at line 81 of file GoalStates.cpp.

Member Data Documentation

◆ states_

std::vector<State *> ompl::base::GoalStates::states_
protected

The goal states. Only ones that are valid are considered by the motion planner.

Definition at line 88 of file GoalStates.h.


The documentation for this class was generated from the following files: