ompl::base::GoalSampleableRegion Class Referenceabstract

Abstract definition of a goal region that can be sampled. More...

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

Inheritance diagram for ompl::base::GoalSampleableRegion:

Public Member Functions

 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. More...
 
template<class T >
const T * as () const
 Cast this instance to a desired type. More...
 
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 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.
 

Additional Inherited Members

- 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

Abstract definition of a goal region that can be sampled.

Definition at line 111 of file GoalSampleableRegion.h.


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