ompl::base::GoalLazySamples Class Reference

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

#include <GoalLazySamples.h>

Inheritance diagram for ompl::base::GoalLazySamples:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void addState (const State *st)
 Add a goal state.
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.
virtual bool canSample (void) const
 Return true of maxSampleCount() > 0 or if the sampling thread is active, as in this case it is possible a sample can be produced.
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().
double getMinNewSampleDistance (void) 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.
 GoalLazySamples (const SpaceInformationPtr &si, const 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 that produces samples from that region needs to be passed to this constructor. The sampling thread is automatically started if autoStart is true.
bool isSampling (void) const
 Return true if the sampling thread is active.
virtual void sampleGoal (State *st) const
 Sample a state in the goal region.
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.
void startSampling (void)
 Start the goal sampling thread.
void stopSampling (void)
 Stop the goal sampling thread.
bool wasLastStateAdded (void) const
 Return true if the last state returned by the sampling function was added. Return false otherwise.
virtual ~GoalLazySamples (void)

Protected Member Functions

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

Protected Attributes

bool lastStateAdded_
 Flag indicating whether the last state returned by the sampling function was added or not.
boost::mutex lock_
 Lock for updating the set of states.
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.
GoalSamplingFn samplerFunc_
 Function that produces samples.
boost::thread * samplingThread_
 Additional thread for sampling goal states.
bool terminateSamplingThread_
 Flag used to notify the sampling thread to terminate sampling.

Detailed Description

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

Definition at line 54 of file GoalLazySamples.h.


Constructor & Destructor Documentation

ompl::base::GoalLazySamples::GoalLazySamples ( const SpaceInformationPtr si,
const 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 that produces samples from that region needs to be passed to this constructor. The sampling thread is automatically started if autoStart is true.

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.

virtual ompl::base::GoalLazySamples::~GoalLazySamples ( void   )  [virtual]

Member Function Documentation

virtual void ompl::base::GoalLazySamples::addState ( const State st  )  [virtual]

Add a goal state.

Reimplemented from ompl::base::GoalStates.

bool ompl::base::GoalLazySamples::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.

virtual bool ompl::base::GoalLazySamples::canSample ( void   )  const [virtual]

Return true of maxSampleCount() > 0 or if the sampling thread is active, as in this case it is possible a sample can be produced.

Reimplemented from ompl::base::GoalSampleableRegion.

virtual void ompl::base::GoalLazySamples::clear ( void   )  [virtual]

Clear all goal states.

Reimplemented from ompl::base::GoalStates.

virtual double ompl::base::GoalLazySamples::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().

Reimplemented from ompl::base::GoalStates.

double ompl::base::GoalLazySamples::getMinNewSampleDistance ( void   )  const [inline]

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.

Definition at line 110 of file GoalLazySamples.h.

void ompl::base::GoalLazySamples::goalSamplingThread ( void   )  [protected]

The function that samples goals by calling samplerFunc_ in a separate thread.

bool ompl::base::GoalLazySamples::isSampling ( void   )  const

Return true if the sampling thread is active.

virtual void ompl::base::GoalLazySamples::sampleGoal ( State st  )  const [virtual]

Sample a state in the goal region.

Reimplemented from ompl::base::GoalStates.

void ompl::base::GoalLazySamples::setMinNewSampleDistance ( double  dist  )  [inline]

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.

Definition at line 103 of file GoalLazySamples.h.

void ompl::base::GoalLazySamples::startSampling ( void   ) 

Start the goal sampling thread.

void ompl::base::GoalLazySamples::stopSampling ( void   ) 

Stop the goal sampling thread.

bool ompl::base::GoalLazySamples::wasLastStateAdded ( void   )  const [inline]

Return true if the last state returned by the sampling function was added. Return false otherwise.

Definition at line 116 of file GoalLazySamples.h.


Member Data Documentation

Flag indicating whether the last state returned by the sampling function was added or not.

Definition at line 144 of file GoalLazySamples.h.

boost::mutex ompl::base::GoalLazySamples::lock_ [mutable, protected]

Lock for updating the set of states.

Definition at line 132 of file GoalLazySamples.h.

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.

Definition at line 148 of file GoalLazySamples.h.

Function that produces samples.

Definition at line 135 of file GoalLazySamples.h.

Additional thread for sampling goal states.

Definition at line 141 of file GoalLazySamples.h.

Flag used to notify the sampling thread to terminate sampling.

Definition at line 138 of file GoalLazySamples.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 09:33:59 2013