37 #ifndef DEMOS_KOULES_GOAL_
38 #define DEMOS_KOULES_GOAL_
40 #include <ompl/base/goals/GoalSampleableRegion.h>
A boost shared pointer wrapper for ompl::base::StateSampler.
Abstract definition of a goal region that can be sampled.
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
virtual double distanceGoal(const ompl::base::State *st) const
Compute the distance to the goal (heuristic). This function is the one used in computing the distance...
Definition of an abstract state.
virtual void sampleGoal(ompl::base::State *st) const
Sample a state in the goal region.
virtual unsigned int maxSampleCount(void) const
Return the maximum number of samples that can be asked for before repeating.
double threshold_
The maximum distance that is allowed to the goal. By default, this is initialized to the minimum epsi...