Definition of a goal region that can be sampled, but the sampling process can be slow. This class allows sampling to happen in a separate thread, and the number of goals may increase, as the planner is running, in a thread-safe manner. More...

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

Inheritance diagram for ompl::base::GoalLazySamples:

Public Types

using NewStateCallbackFn = std::function< void(const base::State *)>
 When new samples are generated and added to the list of possible samples, a callback can be called. This type specifies the signature of that callback.
 

Public Member Functions

 GoalLazySamples (const SpaceInformationPtr &si, GoalSamplingFn samplerFunc, bool autoStart=true, double minDist=std::numeric_limits< double >::epsilon())
 Create a goal region that can be sampled in a lazy fashion. A function (samplerFunc) that produces samples from that region needs to be passed to this constructor. The sampling thread is automatically started if autoStart is true. The sampling function is not called in parallel by OMPL. Hence, the function is not required to be thread safe, unless the user issues additional calls in parallel. The instance of GoalLazySamples remains thread safe however. More...
 
void sampleGoal (State *st) const override
 Sample a state in the goal region.
 
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 addState (const State *st) override
 Add a goal state.
 
void startSampling ()
 Start the goal sampling thread.
 
void stopSampling ()
 Stop the goal sampling thread.
 
bool isSampling () const
 Return true if the sampling thread is active.
 
void setMinNewSampleDistance (double dist)
 Set the minimum distance that a new state returned by the sampling thread needs to be away from previously added states, so that it is added to the list of goal states.
 
double getMinNewSampleDistance () const
 Get the minimum distance that a new state returned by the sampling thread needs to be away from previously added states, so that it is added to the list of goal states.
 
unsigned int samplingAttemptsCount () const
 The number of times the sampling function was called and it returned true.
 
void setNewStateCallback (const NewStateCallbackFn &callback)
 Set the callback function to be called when a new state is added to the list of possible samples. This function is not required to be thread safe, as calls are made one at a time.
 
bool addStateIfDifferent (const State *st, double minDistance)
 Add a state st if it further away that minDistance from previously added states. Return true if the state was added.
 
bool couldSample () const override
 Return true if GoalStates::couldSample() is true or if the sampling thread is active, as in this case it is possible a sample can be produced at some point.
 
bool hasStates () const override
 Check if there are any states in this goal region.
 
const StategetState (unsigned int index) const override
 Return a pointer to the indexth state in the state list.
 
std::size_t getStateCount () const override
 Return the number of valid goal states.
 
void clear () override
 Clear all goal states.
 
unsigned int maxSampleCount () const override
 Return the maximum number of samples that can be asked for before repeating.
 
- Public Member Functions inherited from ompl::base::GoalStates
 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.
 
void addState (const ScopedState<> &st)
 Add a goal state (calls the previous definition of addState())
 
- Public Member Functions inherited from ompl::base::GoalSampleableRegion
 GoalSampleableRegion (const SpaceInformationPtr &si)
 Create a goal region that can be sampled.
 
bool canSample () const
 Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
 
- 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())
 
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.
 

Protected Member Functions

void goalSamplingThread ()
 The function that samples goals by calling samplerFunc_ in a separate thread.
 

Protected Attributes

std::mutex lock_
 Lock for updating the set of states.
 
GoalSamplingFn samplerFunc_
 Function that produces samples.
 
bool terminateSamplingThread_
 Flag used to notify the sampling thread to terminate sampling.
 
std::thread * samplingThread_
 Additional thread for sampling goal states.
 
unsigned int samplingAttempts_
 The number of times the sampling function was called and it returned true.
 
double minDist_
 Samples returned by the sampling thread are added to the list of states only if they are at least minDist_ away from already added samples.
 
NewStateCallbackFn callback_
 If defined, this function is called when a new state is added to the list of possible samples.
 
- Protected Attributes inherited from ompl::base::GoalStates
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 goal region that can be sampled, but the sampling process can be slow. This class allows sampling to happen in a separate thread, and the number of goals may increase, as the planner is running, in a thread-safe manner.

Todo:
The Python bindings for GoalLazySamples class are still broken. The OMPL C++ code creates a new thread from which you should be able to call a python Goal sampling function. Acquiring the right threads and locks and messing around with the Python Global Interpreter Lock (GIL) is very tricky. See ompl/py-bindings/generate_bindings.py for an initial attempt to make this work.

Definition at line 134 of file GoalLazySamples.h.

Constructor & Destructor Documentation

◆ GoalLazySamples()

ompl::base::GoalLazySamples::GoalLazySamples ( const SpaceInformationPtr si,
GoalSamplingFn  samplerFunc,
bool  autoStart = true,
double  minDist = std::numeric_limits<double>::epsilon() 
)

Create a goal region that can be sampled in a lazy fashion. A function (samplerFunc) that produces samples from that region needs to be passed to this constructor. The sampling thread is automatically started if autoStart is true. The sampling function is not called in parallel by OMPL. Hence, the function is not required to be thread safe, unless the user issues additional calls in parallel. The instance of GoalLazySamples remains thread safe however.

The function samplerFunc returns a truth value. If the return value is true, further calls to the function can be made. If the return is false, no more calls should be made. The function takes two arguments: the instance of GoalLazySamples making the call and the state to fill with a goal state. For every state filled in by samplerFunc, addStateIfDifferent() is called. A state computed by the sampling thread is added if it is "sufficiently different" from previously added states. A state is considered "sufficiently different" if it is at least minDist away from previously added states.

Definition at line 43 of file GoalLazySamples.cpp.


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