PathLengthDirectInfSampler.h
154 bool isInPhs(const ProlateHyperspheroidCPtr &phsCPtr, const std::vector<double> &informedVector) const;
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:58
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:48
An abstract class for the concept of using information about the state space and the current solution...
Definition: InformedStateSampler.h:61
An informed sampler for problems seeking to minimize path length.
Definition: PathLengthDirectInfSampler.h:81
bool sampleUniform(State *statePtr, const Cost &maxCost) override
Sample uniformly in the subset of the state space whose heuristic solution estimates are less than th...
Definition: PathLengthDirectInfSampler.cpp:249
bool hasInformedMeasure() const override
Whether the sampler can provide a measure of the informed subset.
Definition: PathLengthDirectInfSampler.cpp:295
double getInformedMeasure(const Cost ¤tCost) const override
The measure of the subset of the state space defined by the current solution cost that is being searc...
Definition: PathLengthDirectInfSampler.cpp:300
Cost heuristicSolnCost(const State *statePtr) const override
A helper function to calculate the heuristic estimate of the solution cost for the informed subset of...
Definition: PathLengthDirectInfSampler.cpp:328
PathLengthDirectInfSampler(const ProblemDefinitionPtr &probDefn, unsigned int maxNumberCalls)
Construct a sampler that only generates states with a heuristic solution estimate that is less than t...
Definition: PathLengthDirectInfSampler.cpp:58
A shared pointer wrapper for ompl::base::ProblemDefinition.
A shared pointer wrapper for ompl::base::StateSampler.
A shared pointer wrapper for ompl::base::StateSpace.
Main namespace. Contains everything in this library.
Definition: ConstrainedSpaceInformation.h:53