ompl::geometric::VFRRT Class Reference

#include <ompl/geometric/planners/rrt/VFRRT.h>

Inheritance diagram for ompl::geometric::VFRRT:

Public Types

using VectorField = std::function< Eigen::VectorXd(const base::State *)>
 
- 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.
 
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.
 

Public Member Functions

 VFRRT (const base::SpaceInformationPtr &si, VectorField vf, double exploration, double initial_lambda, unsigned int update_freq)
 
 ~VFRRT () override
 
void clear () override
 
double determineMeanNorm ()
 
Eigen::VectorXd getNewDirection (const base::State *qnear, const base::State *qrand)
 
double biasedSampling (const Eigen::VectorXd &vrand, const Eigen::VectorXd &vfield, double lambdaScale)
 
void updateGain ()
 
Eigen::VectorXd computeAlphaBeta (double omega, const Eigen::VectorXd &vrand, const Eigen::VectorXd &vfield)
 
MotionextendTree (Motion *m, base::State *rstate, const Eigen::VectorXd &v)
 
void updateExplorationEfficiency (Motion *m)
 
base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc) override
 
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.
 
- Public Member Functions inherited from ompl::geometric::RRT
 RRT (const base::SpaceInformationPtr &si, bool addIntermediateStates=false)
 Constructor.
 
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).

 
void setGoalBias (double goalBias)
 Set the goal bias. More...
 
double getGoalBias () const
 Get the goal bias the planner is using.
 
bool getIntermediateStates () const
 Return true if the intermediate states generated along motions are to be added to the tree itself.
 
void setIntermediateStates (bool addIntermediateStates)
 Specify whether the intermediate states generated along motions are to be added to the tree itself.
 
void setRange (double distance)
 Set the range the planner is supposed to use. More...
 
double getRange () const
 Get the range the planner is using.
 
template<template< typename T > class NN>
void setNearestNeighbors ()
 Set a different nearest neighbors datastructure.
 
- Public Member Functions inherited from ompl::base::Planner
 Planner (const Planner &)=delete
 
Planneroperator= (const Planner &)=delete
 
 Planner (SpaceInformationPtr si, std::string name)
 Constructor.
 
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.
 
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve.
 
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve.
 
const PlannerInputStatesgetPlannerInputStates () const
 Get the planner input states.
 
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().
 
PlannerStatus solve (const PlannerTerminationConditionFn &ptc, double checkInterval)
 Same as above except the termination condition is only evaluated at a specified interval.
 
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.
 
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().
 
const std::string & getName () const
 Get the name of the planner.
 
void setName (const std::string &name)
 Set the name of the planner.
 
const PlannerSpecsgetSpecs () const
 Return the specifications (capabilities of this planner)
 
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.
 
bool isSetup () const
 Check if setup() was called for this planner.
 
ParamSetparams ()
 Get the parameters for this planner.
 
const ParamSetparams () const
 Get the parameters for this planner.
 
const PlannerProgressPropertiesgetPlannerProgressProperties () const
 Retrieve a planner's planner progress property map.
 
virtual void printProperties (std::ostream &out) const
 Print properties of the motion planner.
 
virtual void printSettings (std::ostream &out) const
 Print information about the motion planner's settings.
 

Additional Inherited Members

- Protected Member Functions inherited from ompl::geometric::RRT
void freeMemory ()
 Free the memory allocated by this planner.
 
double distanceFunction (const Motion *a, const Motion *b) const
 Compute distance between motions (actually distance between contained states)
 
- 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.
 
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.
 
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.
 
- Protected Attributes inherited from ompl::geometric::RRT
base::StateSamplerPtr sampler_
 State sampler.
 
std::shared_ptr< NearestNeighbors< Motion * > > nn_
 A nearest-neighbors datastructure containing the tree of motions.
 
double goalBias_ {.05}
 The fraction of time the goal is picked as the state to expand towards (if such a state is available)
 
double maxDistance_ {0.}
 The maximum length of a motion to be added to a tree.
 
bool addIntermediateStates_
 Flag indicating whether intermediate states are added to the built tree of motions.
 
RNG rng_
 The random number generator.
 
MotionlastGoalMotion_ {nullptr}
 The most recent goal motion. Used for PlannerData computation.
 
- Protected Attributes inherited from ompl::base::Planner
SpaceInformationPtr si_
 The space information for which planning is done.
 
ProblemDefinitionPtr pdef_
 The user set problem definition.
 
PlannerInputStates pis_
 Utility class to extract valid input states

 
std::string name_
 The name of this planner.
 
PlannerSpecs specs_
 The specifications of the planner (its capabilities)
 
ParamSet params_
 A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function.
 
PlannerProgressProperties plannerProgressProperties_
 A mapping between this planner's progress property names and the functions used for querying those progress properties.
 
bool setup_
 Flag indicating whether setup() has been called.
 

Detailed Description

Short description
Vector Field Rapidly-exploring Random Tree (VFRRT) is a tree-based motion planner that tries to minimize the so-called upstream cost of a path. The upstream cost is defined by an integral over a user-defined vector field.
External documentation
I. Ko, B. Kim, and F. C. Park, Randomized path planning on vector fields, Intl. J. of Robotics Research, 33(13), pp. 1664–1682, 2014. DOI: 10.1177/0278364914545812

[PDF]

Definition at line 130 of file VFRRT.h.

Constructor & Destructor Documentation

◆ VFRRT()

ompl::geometric::VFRRT::VFRRT ( const base::SpaceInformationPtr &  si,
VectorField  vf,
double  exploration,
double  initial_lambda,
unsigned int  update_freq 
)

Constructor.

Definition at line 51 of file VFRRT.cpp.

◆ ~VFRRT()

ompl::geometric::VFRRT::~VFRRT ( )
overridedefault

Destructor.

Member Function Documentation

◆ biasedSampling()

double ompl::geometric::VFRRT::biasedSampling ( const Eigen::VectorXd &  vrand,
const Eigen::VectorXd &  vfield,
double  lambdaScale 
)

Calculates the weight omega which can be used to compute alpha and beta.

Definition at line 116 of file VFRRT.cpp.

◆ clear()

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

Reset internal data.

Reimplemented from ompl::geometric::RRT.

Definition at line 65 of file VFRRT.cpp.

◆ computeAlphaBeta()

Eigen::VectorXd ompl::geometric::VFRRT::computeAlphaBeta ( double  omega,
const Eigen::VectorXd &  vrand,
const Eigen::VectorXd &  vfield 
)

Computes alpha and beta, using these values to produce the vector returned by getNewDirection. This produced vector can be used to determine the direction an added state should be to maximize the upstream criterion of the produced path.

Definition at line 140 of file VFRRT.cpp.

◆ determineMeanNorm()

double ompl::geometric::VFRRT::determineMeanNorm ( )

Make a Monte Carlo estimate for the mean vector norm in the field.

Definition at line 80 of file VFRRT.cpp.

◆ extendTree()

ompl::geometric::VFRRT::Motion * ompl::geometric::VFRRT::extendTree ( Motion m,
base::State rstate,
const Eigen::VectorXd &  v 
)

This attempts to extend the tree from the motion m to a new motion in the direction specified by the vector v.

Definition at line 154 of file VFRRT.cpp.

◆ getNewDirection()

Eigen::VectorXd ompl::geometric::VFRRT::getNewDirection ( const base::State qnear,
const base::State qrand 
)

Use the vector field to alter the direction of a sample.

Definition at line 93 of file VFRRT.cpp.

◆ solve()

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

Solve the planning problem.

Reimplemented from ompl::geometric::RRT.

Definition at line 194 of file VFRRT.cpp.

◆ updateExplorationEfficiency()

void ompl::geometric::VFRRT::updateExplorationEfficiency ( Motion m)

Updates measures for exploration efficiency if a given motion m is added to the nearest NearestNeighbors structure.

Definition at line 184 of file VFRRT.cpp.

◆ updateGain()

void ompl::geometric::VFRRT::updateGain ( )

Every nth time this function is called (where the nth step is the update frequency given in the constructor) the value of lambda is updated and the counts of efficient and inefficient samples added to the tree are reset to 0. The measure for exploration inefficiency is also reset to 0.

Definition at line 127 of file VFRRT.cpp.


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