Loading...
Searching...
No Matches

Bi-directional Expansive Space Trees. More...

#include <ompl/geometric/planners/est/BiEST.h>

Inheritance diagram for ompl::geometric::BiEST:

Classes

class  Motion
 The definition of a motion. More...
 

Public Member Functions

 BiEST (const base::SpaceInformationPtr &si)
 Constructor. More...
 
base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc) override
 Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work for more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true. More...
 
void clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. More...
 
void setRange (double distance)
 Set the range the planner is supposed to use. More...
 
double getRange () const
 Get the range the planner is using. More...
 
void setup () override
 Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving. More...
 
void getPlannerData (base::PlannerData &data) const override
 Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).
More...
 
- Public Member Functions inherited from ompl::base::Planner
 Planner (const Planner &)=delete
 
Planneroperator= (const Planner &)=delete
 
 Planner (SpaceInformationPtr si, std::string name)
 Constructor. More...
 
virtual ~Planner ()=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...
 
const SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using. More...
 
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve. More...
 
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve. More...
 
const PlannerInputStatesgetPlannerInputStates () const
 Get the planner input states. More...
 
virtual void setProblemDefinition (const ProblemDefinitionPtr &pdef)
 Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear() or clearQuery(). More...
 
virtual PlannerStatus solve (const PlannerTerminationCondition &ptc)=0
 Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work for more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true. More...
 
PlannerStatus solve (const PlannerTerminationConditionFn &ptc, double checkInterval)
 Same as above except the termination condition is only evaluated at a specified interval. More...
 
PlannerStatus solve (double solveTime)
 Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning. More...
 
virtual void clear ()
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. More...
 
virtual void clearQuery ()
 Clears internal datastructures of any query-specific information from the previous query. Planner settings are not affected. The planner, if able, should retain all datastructures generated from previous queries that can be used to help solve the next query. Note that clear() should also clear all query-specific information along with all other datastructures in the planner. By default clearQuery() calls clear(). More...
 
virtual void getPlannerData (PlannerData &data) const
 Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).
More...
 
const std::string & getName () const
 Get the name of the planner. More...
 
void setName (const std::string &name)
 Set the name of the planner. More...
 
const PlannerSpecsgetSpecs () const
 Return the specifications (capabilities of this planner) More...
 
virtual void setup ()
 Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving. More...
 
virtual void checkValidity ()
 Check to see if the planner is in a working state (setup has been called, a goal was set, the input states seem to be in order). In case of error, this function throws an exception. More...
 
bool isSetup () const
 Check if setup() was called for this planner. More...
 
ParamSetparams ()
 Get the parameters for this planner. More...
 
const ParamSetparams () const
 Get the parameters for this planner. More...
 
const PlannerProgressPropertiesgetPlannerProgressProperties () const
 Retrieve a planner's planner progress property map. More...
 
virtual void printProperties (std::ostream &out) const
 Print properties of the motion planner. More...
 
virtual void printSettings (std::ostream &out) const
 Print information about the motion planner's settings. More...
 

Protected Member Functions

double distanceFunction (const Motion *a, const Motion *b) const
 Compute distance between motions (actually distance between contained states) More...
 
void freeMemory ()
 Free the memory allocated by this planner. More...
 
void addMotion (Motion *motion, std::vector< Motion * > &motions, PDF< Motion * > &pdf, const std::shared_ptr< NearestNeighbors< Motion * > > &nn, const std::vector< Motion * > &neighbors)
 Add a motion to the exploration tree. More...
 
- Protected Member Functions inherited from ompl::base::Planner
template<typename T , typename PlannerType , typename SetterType , typename GetterType >
void declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const GetterType &getter, const std::string &rangeSuggestion="")
 This function declares a parameter for this planner instance, and specifies the setter and getter functions. More...
 
template<typename T , typename PlannerType , typename SetterType >
void declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const std::string &rangeSuggestion="")
 This function declares a parameter for this planner instance, and specifies the setter function. More...
 
void addPlannerProgressProperty (const std::string &progressPropertyName, const PlannerProgressProperty &prop)
 Add a planner progress property called progressPropertyName with a property querying function prop to this planner's progress property map. More...
 

Protected Attributes

std::shared_ptr< NearestNeighbors< Motion * > > nnStart_
 A nearest-neighbors datastructure containing the tree of motions. More...
 
std::shared_ptr< NearestNeighbors< Motion * > > nnGoal_
 
std::vector< Motion * > startMotions_
 The set of all states in the start tree. More...
 
std::vector< Motion * > goalMotions_
 
PDF< Motion * > startPdf_
 The probability distribution function over states in each tree. More...
 
PDF< Motion * > goalPdf_
 
base::ValidStateSamplerPtr sampler_
 Valid state sampler. More...
 
double maxDistance_ {0.0}
 The maximum length of a motion to be added to a tree. More...
 
double nbrhoodRadius_
 The radius considered for neighborhood. More...
 
RNG rng_
 The random number generator. More...
 
std::pair< base::State *, base::State * > connectionPoint_ {nullptr,nullptr}
 The pair of states in each tree connected during planning. Used for PlannerData computation. More...
 
- Protected Attributes inherited from ompl::base::Planner
SpaceInformationPtr si_
 The space information for which planning is done. More...
 
ProblemDefinitionPtr pdef_
 The user set problem definition. More...
 
PlannerInputStates pis_
 Utility class to extract valid input states
More...
 
std::string name_
 The name of this planner. More...
 
PlannerSpecs specs_
 The specifications of the planner (its capabilities) More...
 
ParamSet params_
 A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function. More...
 
PlannerProgressProperties plannerProgressProperties_
 A mapping between this planner's progress property names and the functions used for querying those progress properties. More...
 
bool setup_
 Flag indicating whether setup() has been called. More...
 

Additional Inherited Members

- Public Types inherited from ompl::base::Planner
using PlannerProgressProperty = std::function< std::string()>
 Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine. More...
 
using PlannerProgressProperties = std::map< std::string, PlannerProgressProperty >
 A dictionary which maps the name of a progress property to the function to be used for querying that property. More...
 

Detailed Description

Bi-directional Expansive Space Trees.

Short description
EST is a tree-based motion planner that attempts to detect the less explored area of the space by measuring the density of the explored space, biasing exploration toward parts of the space with lowest density.
External documentation
D. Hsu, J.-C. Latombe, and R. Motwani, Path planning in expansive configuration spaces, Intl. J. Computational Geometry and Applications, vol. 9, no. 4-5, pp. 495–512, 1999. DOI: 10.1142/S0218195999000285
[PDF]

Definition at line 65 of file BiEST.h.

Constructor & Destructor Documentation

◆ BiEST()

ompl::geometric::BiEST::BiEST ( const base::SpaceInformationPtr &  si)

Constructor.

Definition at line 43 of file BiEST.cpp.

◆ ~BiEST()

ompl::geometric::BiEST::~BiEST ( )
override

Definition at line 51 of file BiEST.cpp.

Member Function Documentation

◆ addMotion()

void ompl::geometric::BiEST::addMotion ( Motion motion,
std::vector< Motion * > &  motions,
PDF< Motion * > &  pdf,
const std::shared_ptr< NearestNeighbors< Motion * > > &  nn,
const std::vector< Motion * > &  neighbors 
)
protected

Add a motion to the exploration tree.

Definition at line 279 of file BiEST.cpp.

◆ clear()

void ompl::geometric::BiEST::clear ( )
overridevirtual

Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.

Reimplemented from ompl::base::Planner.

Definition at line 81 of file BiEST.cpp.

◆ distanceFunction()

double ompl::geometric::BiEST::distanceFunction ( const Motion a,
const Motion b 
) const
inlineprotected

Compute distance between motions (actually distance between contained states)

Definition at line 130 of file BiEST.h.

◆ freeMemory()

void ompl::geometric::BiEST::freeMemory ( )
protected

Free the memory allocated by this planner.

Definition at line 100 of file BiEST.cpp.

◆ getPlannerData()

void ompl::geometric::BiEST::getPlannerData ( base::PlannerData data) const
overridevirtual

Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).

Reimplemented from ompl::base::Planner.

Definition at line 296 of file BiEST.cpp.

◆ getRange()

double ompl::geometric::BiEST::getRange ( ) const
inline

Get the range the planner is using.

Definition at line 92 of file BiEST.h.

◆ setRange()

void ompl::geometric::BiEST::setRange ( double  distance)
inline

Set the range the planner is supposed to use.

This parameter greatly influences the runtime of the algorithm. It represents the maximum length of a motion to be added in the tree of motions.

Definition at line 82 of file BiEST.h.

◆ setup()

void ompl::geometric::BiEST::setup ( )
overridevirtual

Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving.

Reimplemented from ompl::base::Planner.

Definition at line 56 of file BiEST.cpp.

◆ solve()

ompl::base::PlannerStatus ompl::geometric::BiEST::solve ( const base::PlannerTerminationCondition ptc)
overridevirtual

Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work for more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.

Implements ompl::base::Planner.

Definition at line 117 of file BiEST.cpp.

Member Data Documentation

◆ connectionPoint_

std::pair<base::State *, base::State *> ompl::geometric::BiEST::connectionPoint_ {nullptr,nullptr}
protected

The pair of states in each tree connected during planning. Used for PlannerData computation.

Definition at line 168 of file BiEST.h.

◆ goalMotions_

std::vector<Motion *> ompl::geometric::BiEST::goalMotions_
protected

Definition at line 141 of file BiEST.h.

◆ goalPdf_

PDF<Motion *> ompl::geometric::BiEST::goalPdf_
protected

Definition at line 145 of file BiEST.h.

◆ maxDistance_

double ompl::geometric::BiEST::maxDistance_ {0.0}
protected

The maximum length of a motion to be added to a tree.

Definition at line 159 of file BiEST.h.

◆ nbrhoodRadius_

double ompl::geometric::BiEST::nbrhoodRadius_
protected

The radius considered for neighborhood.

Definition at line 162 of file BiEST.h.

◆ nnGoal_

std::shared_ptr<NearestNeighbors<Motion *> > ompl::geometric::BiEST::nnGoal_
protected

Definition at line 137 of file BiEST.h.

◆ nnStart_

std::shared_ptr<NearestNeighbors<Motion *> > ompl::geometric::BiEST::nnStart_
protected

A nearest-neighbors datastructure containing the tree of motions.

Definition at line 136 of file BiEST.h.

◆ rng_

RNG ompl::geometric::BiEST::rng_
protected

The random number generator.

Definition at line 165 of file BiEST.h.

◆ sampler_

base::ValidStateSamplerPtr ompl::geometric::BiEST::sampler_
protected

Valid state sampler.

Definition at line 156 of file BiEST.h.

◆ startMotions_

std::vector<Motion *> ompl::geometric::BiEST::startMotions_
protected

The set of all states in the start tree.

Definition at line 140 of file BiEST.h.

◆ startPdf_

PDF<Motion *> ompl::geometric::BiEST::startPdf_
protected

The probability distribution function over states in each tree.

Definition at line 144 of file BiEST.h.


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