Loading...
Searching...
No Matches
ompl::base::InformedSampler Class Referenceabstract

An abstract class for the concept of using information about the state space and the current solution cost to limit future search to a planning subproblem that contains all possibly better solutions. More...

#include <ompl/base/samplers/InformedStateSampler.h>

Inheritance diagram for ompl::base::InformedSampler:

Public Member Functions

 InformedSampler (const InformedSampler &)=delete
 
InformedSampleroperator= (const InformedSampler &)=delete
 
 InformedSampler (const ProblemDefinitionPtr &probDefn, unsigned int maxNumberCalls)
 Construct a sampler that only generates states with a heuristic solution estimate that is less than the cost of the current solution. Requires a function pointer to a method to query the cost of the current solution. If iteration is required, only maxNumberCalls are attempted, to assure that the function returns. More...
 
virtual bool sampleUniform (State *statePtr, const Cost &maxCost)=0
 Sample uniformly in the subset of the state space whose heuristic solution estimates are less than the provided cost, i.e. in the interval [0, maxCost). Returns false if such a state was not found in the specified number of iterations. More...
 
virtual bool sampleUniform (State *statePtr, const Cost &minCost, const Cost &maxCost)=0
 Sample uniformly in the subset of the state space whose heuristic solution estimates are between the provided costs, [minCost, maxCost). Returns false if such a state was not found in the specified number of iterations. More...
 
virtual bool hasInformedMeasure () const =0
 Whether the sampler can provide a measure of the informed subset. More...
 
virtual double getInformedMeasure (const Cost &currentCost) const =0
 The measure of the subset of the state space defined by the current solution cost that is being searched. Does not consider problem boundaries but returns the measure of the entire space if no solution has been found or if a closed form expression for the measure does not exist. More...
 
virtual double getInformedMeasure (const Cost &minCost, const Cost &maxCost) const
 The measure of the subset of the state space defined by the current solution cost that is being searched. Does not consider problem boundaries but returns the measure of the entire space if no solution has been found or if a closed form expression for the measure does not exist. By default calls the 1-argument overloaded version with the min and max costs and subtracts the differences; however, there may be more efficient ways to do this for some cost functions. More...
 
virtual Cost heuristicSolnCost (const State *statePtr) const
 A helper function to calculate the heuristic estimate of the solution cost for a given state using the optimization objective stored in the problem definition. More...
 
ProblemDefinitionPtr getProblemDefn () const
 
unsigned int getMaxNumberOfIters () const
 

Protected Attributes

ProblemDefinitionPtr probDefn_
 A copy of the problem definition. More...
 
OptimizationObjectivePtr opt_
 A copy of the optimization objective. More...
 
StateSpacePtr space_
 A copy of the state space. More...
 
unsigned int numIters_
 The number of iterations I'm allowed to attempt. More...
 

Detailed Description

An abstract class for the concept of using information about the state space and the current solution cost to limit future search to a planning subproblem that contains all possibly better solutions.

Definition at line 60 of file InformedStateSampler.h.

Constructor & Destructor Documentation

◆ InformedSampler()

ompl::base::InformedSampler::InformedSampler ( const ProblemDefinitionPtr probDefn,
unsigned int  maxNumberCalls 
)

Construct a sampler that only generates states with a heuristic solution estimate that is less than the cost of the current solution. Requires a function pointer to a method to query the cost of the current solution. If iteration is required, only maxNumberCalls are attempted, to assure that the function returns.

Definition at line 49 of file InformedStateSampler.cpp.

Member Function Documentation

◆ getInformedMeasure() [1/2]

virtual double ompl::base::InformedSampler::getInformedMeasure ( const Cost currentCost) const
pure virtual

The measure of the subset of the state space defined by the current solution cost that is being searched. Does not consider problem boundaries but returns the measure of the entire space if no solution has been found or if a closed form expression for the measure does not exist.

Implemented in ompl::base::RejectionInfSampler, ompl::base::OrderedInfSampler, and ompl::base::PathLengthDirectInfSampler.

◆ getInformedMeasure() [2/2]

double ompl::base::InformedSampler::getInformedMeasure ( const Cost minCost,
const Cost maxCost 
) const
virtual

The measure of the subset of the state space defined by the current solution cost that is being searched. Does not consider problem boundaries but returns the measure of the entire space if no solution has been found or if a closed form expression for the measure does not exist. By default calls the 1-argument overloaded version with the min and max costs and subtracts the differences; however, there may be more efficient ways to do this for some cost functions.

Reimplemented in ompl::base::RejectionInfSampler.

Definition at line 71 of file InformedStateSampler.cpp.

◆ getMaxNumberOfIters()

unsigned int ompl::base::InformedSampler::getMaxNumberOfIters ( ) const

Helper for the OrderedInfSampler wrapper

Definition at line 115 of file InformedStateSampler.cpp.

◆ getProblemDefn()

ProblemDefinitionPtr ompl::base::InformedSampler::getProblemDefn ( ) const

Helper for the OrderedInfSampler wrapper

Definition at line 110 of file InformedStateSampler.cpp.

◆ hasInformedMeasure()

virtual bool ompl::base::InformedSampler::hasInformedMeasure ( ) const
pure virtual

Whether the sampler can provide a measure of the informed subset.

Implemented in ompl::base::OrderedInfSampler, ompl::base::PathLengthDirectInfSampler, and ompl::base::RejectionInfSampler.

◆ heuristicSolnCost()

Cost ompl::base::InformedSampler::heuristicSolnCost ( const State statePtr) const
virtual

A helper function to calculate the heuristic estimate of the solution cost for a given state using the optimization objective stored in the problem definition.

Todo:
With the future invention of a heuristic class, this should move.

Reimplemented in ompl::base::PathLengthDirectInfSampler.

Definition at line 77 of file InformedStateSampler.cpp.

◆ sampleUniform() [1/2]

virtual bool ompl::base::InformedSampler::sampleUniform ( State statePtr,
const Cost maxCost 
)
pure virtual

Sample uniformly in the subset of the state space whose heuristic solution estimates are less than the provided cost, i.e. in the interval [0, maxCost). Returns false if such a state was not found in the specified number of iterations.

Implemented in ompl::base::OrderedInfSampler, ompl::base::PathLengthDirectInfSampler, and ompl::base::RejectionInfSampler.

◆ sampleUniform() [2/2]

virtual bool ompl::base::InformedSampler::sampleUniform ( State statePtr,
const Cost minCost,
const Cost maxCost 
)
pure virtual

Sample uniformly in the subset of the state space whose heuristic solution estimates are between the provided costs, [minCost, maxCost). Returns false if such a state was not found in the specified number of iterations.

Implemented in ompl::base::OrderedInfSampler, ompl::base::PathLengthDirectInfSampler, and ompl::base::RejectionInfSampler.

Member Data Documentation

◆ numIters_

unsigned int ompl::base::InformedSampler::numIters_
protected

The number of iterations I'm allowed to attempt.

Definition at line 119 of file InformedStateSampler.h.

◆ opt_

OptimizationObjectivePtr ompl::base::InformedSampler::opt_
protected

A copy of the optimization objective.

Definition at line 115 of file InformedStateSampler.h.

◆ probDefn_

ProblemDefinitionPtr ompl::base::InformedSampler::probDefn_
protected

A copy of the problem definition.

Definition at line 113 of file InformedStateSampler.h.

◆ space_

StateSpacePtr ompl::base::InformedSampler::space_
protected

A copy of the state space.

Definition at line 117 of file InformedStateSampler.h.


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