Bidirectional Asymptotically Optimal Fast Marching Tree algorithm developed by J. Starek, J.V. Gomez, et al. More...

#include <ompl/geometric/planners/fmt/BFMT.h>

Inheritance diagram for ompl::geometric::BFMT:

Classes

class  BiDirMotion
 Representation of a bidirectional motion. More...
 
struct  BiDirMotionCompare
 Comparator used to order motions in a binary heap. More...
 
struct  CostIndexCompare
 

Public Types

enum  TreeType { FWD = 0, REV = 1 }
 Tree identifier.
 
enum  ExploreType { SWAP_EVERY_TIME = 0, CHOOSE_SMALLEST_Z = 1 }
 Exploration strategy identifier.
 
enum  TerminateType { FEASIBILITY = 0, OPTIMALITY = 1 }
 Termination strategy identifier.
 
using BiDirMotionPtrs = std::vector< BiDirMotion * >
 
- 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

 BFMT (const base::SpaceInformationPtr &si)
 
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.
 
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.
 
void clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
 
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 setNumSamples (const unsigned int numSamples)
 Set the number of states that the planner should sample. The planner will sample this number of states in addition to the initial states. If any of the goal states are not reachable from the randomly sampled states, those goal states will also be added. The default value is 1000.
 
unsigned int getNumSamples () const
 Get the number of states that the planner will sample.
 
void setNearestK (bool nearestK)
 If nearestK is true, FMT will be run using the Knearest strategy.
 
bool getNearestK () const
 Get the state of the nearestK strategy.
 
void setRadiusMultiplier (const double radiusMultiplier)
 The planner searches for neighbors of a node within a cost r, where r is the value described for BFMT* in Section 4 of [L. Janson, E. Schmerling, A. Clark, M. Pavone. Fast marching tree: a fast marching sampling-based method for optimal motion planning in many dimensions. The International Journal of Robotics Research, 34(7):883-921, 2015](https://arxiv.org/pdf/1306.3532.pdf). For guaranteed asymptotic convergence, the user should choose a constant multiplier for the search radius that is greater than one. The default value is 1.1. In general, a radius multiplier between 0.9 and 5 appears to perform the best.
 
double getRadiusMultiplier () const
 Get the multiplier used for the nearest neighbors search radius.
 
void setFreeSpaceVolume (const double freeSpaceVolume)
 Store the volume of the obstacle-free configuration space. If no value is specified, the default assumes an obstacle-free unit hypercube, freeSpaceVolume = (maximumExtent/sqrt(dimension))^(dimension)
 
double getFreeSpaceVolume () const
 Get the volume of the free configuration space that is being used by the planner.
 
void setCacheCC (bool ccc)
 Sets the collision check caching to save calls to the collision checker with slightly memory usage as a counterpart.
 
bool getCacheCC () const
 Get the state of the collision check caching.
 
void setHeuristics (bool h)
 Activates the cost to go heuristics when ordering the heap.
 
bool getHeuristics () const
 Returns true if the heap is ordered taking into account cost to go heuristics.
 
void setExtendedFMT (bool e)
 Activates the extended FMT*: adding new samples if planner does not finish successfully.
 
bool getExtendedFMT () const
 Returns true if the extended FMT* is activated.
 
void setExploration (bool balanced)
 Sets exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go.
 
bool getExploration () const
 Returns the exploration strategy.
 
void setTermination (bool optimality)
 Sets the termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found.
 
bool getTermination () const
 Returns the termination strategy.
 
void setPrecomputeNN (bool p)
 Sets Nearest Neighbors precomputation. Currently, it precomputes once solve() has been called.
 
bool setPrecomputeNN () const
 Returns true if Nearest Neighbor precomputation is done.
 
- 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.
 

Protected Types

using BiDirMotionBinHeap = ompl::BinaryHeap< BiDirMotion *, BiDirMotionCompare >
 

Protected Member Functions

void swapTrees ()
 Change the active tree.
 
void useFwdTree ()
 Sets forward tree active.
 
void useRevTree ()
 Sets reverse tree active.
 
double distanceFunction (const BiDirMotion *a, const BiDirMotion *b) const
 Compute the distance between two motions as the cost between their contained states. Note that for computationally intensive cost functions, the cost between motions should be stored to avoid duplicate calculations.
 
double calculateUnitBallVolume (unsigned int dimension) const
 Compute the volume of the unit ball in a given dimension.
 
double calculateRadius (unsigned int dimension, unsigned int n) const
 Calculate the radius to use for nearest neighbor searches, using the bound given in [L. Janson, E. Schmerling, A. Clark, M. Pavone. Fast marching tree: a fast marching sampling-based method for optimal motion planning in many dimensions. The International Journal of Robotics Research, 34(7):883-921, 2015](https://arxiv.org/pdf/1306.3532.pdf). The radius depends on the radiusMultiplier parameter, the volume of the free configuration space, the volume of the unit ball in the current dimension, and the number of nodes in the graph.
 
void freeMemory ()
 Free the memory allocated by this planner.
 
void saveNeighborhood (BiDirMotion *m)
 Save the neighbors within a neighborhood of a given state. The strategy used (nearestK or nearestR depends on the planner configuration.
 
void sampleFree (const std::shared_ptr< NearestNeighbors< BiDirMotion * >> &nn, const base::PlannerTerminationCondition &ptc)
 Sample a state from the free configuration space and save it into the nearest neighbors data structure.
 
void initializeProblem (base::GoalSampleableRegion *&goal_s)
 Carries out some planner checks.
 
void expandTreeFromNode (BiDirMotion *&z, BiDirMotion *&connection_point)
 Complete one iteration of the main loop of the BFMT* algorithm: Find K nearest nodes in set Unvisited (or within a radius r) of the node z. Attempt to connect them to their optimal cost-to-come parent in set Open. Remove all newly connected nodes fromUnvisited and insert them into Open. Remove motion z from Open, and update z to be the current lowest cost-to-come node in Open.
 
bool plan (BiDirMotion *x_init, BiDirMotion *x_goal, BiDirMotion *&connection_point, const base::PlannerTerminationCondition &ptc)
 Executes the actual planning algorithm, swapping and expanding the trees. More...
 
bool termination (BiDirMotion *&z, BiDirMotion *&connection_point, const base::PlannerTerminationCondition &ptc)
 Checks if the termination condition is met.
 
void chooseTreeAndExpansionNode (BiDirMotion *&z)
 Chooses and expand a tree according to the exploration strategy.
 
void tracePath (BiDirMotion *z, BiDirMotionPtrs &path)
 Trace the path along a tree towards the root (forward or reverse)
 
void updateNeighborhood (BiDirMotion *m, std::vector< BiDirMotion * > nbh)
 For a motion m, updates the stored neighborhoods of all its neighbors by by inserting m (maintaining the cost-based sorting)
 
void insertNewSampleInOpen (const base::PlannerTerminationCondition &ptc)
 Extended FMT strategy: inserts a new motion in open if the heap is empty.
 
- 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

unsigned int numSamples_ {1000u}
 The number of samples to use when planning.
 
double radiusMultiplier_ {1.}
 This planner uses a nearest neighbor search radius proportional to the lower bound for optimality derived for FMT* in Section 4 of [L. Janson, E. Schmerling, A. Clark, M. Pavone. Fast marching tree: a fast marching sampling-based method for optimal motion planning in many dimensions. The International Journal of Robotics Research, 34(7):883-921, 2015](https://arxiv.org/pdf/1306.3532.pdf). The radius multiplier is the multiplier for the lower bound. For guaranteed asymptotic convergence, the user should choose a multiplier for the search radius that is greater than one. The default value is 1.1. In general, a radius between 0.9 and 5 appears to perform the best.
 
double freeSpaceVolume_
 The volume of numSathe free configuration space, computed as an upper bound with 95% confidence.
 
unsigned int collisionChecks_ {0u}
 Number of collision checks performed by the algorithm.
 
bool nearestK_ {true}
 Flag to activate the K nearest neighbors strategy.
 
double NNr_ {0.}
 Radius employed in the nearestR strategy.
 
unsigned int NNk_ {0}
 K used in the nearestK strategy.
 
TreeType tree_ {FWD}
 Active tree.
 
ExploreType exploration_ {SWAP_EVERY_TIME}
 Exploration strategy used.
 
TerminateType termination_ {OPTIMALITY}
 Termination strategy used.
 
bool precomputeNN_ {false}
 If true all the nearest neighbors maps are precomputed before solving.
 
std::shared_ptr< NearestNeighbors< BiDirMotion * > > nn_
 A nearest-neighbor datastructure containing the set of all motions.
 
std::map< BiDirMotion *, BiDirMotionPtrs > neighborhoods_
 A map linking a motion to all of the motions within a distance r of that motion.
 
BiDirMotionBinHeap Open_ [2]
 A binary heap for storing explored motions in cost-to-come sorted order. The motions in Open have been explored, yet are still close enough to the frontier of the explored set Open to be connected to nodes in the unexplored set Unvisited.
 
std::map< BiDirMotion *, BiDirMotionBinHeap::Element * > Open_elements [2]
 Map to know the corresponding heap element from the given motion.
 
base::StateSamplerPtr sampler_
 State sampler.
 
base::OptimizationObjectivePtr opt_
 The cost objective function.
 
bool heuristics_ {true}
 Flag to activate the cost to go heuristics.
 
base::StateheurGoalState_ [2]
 Goal state caching to accelerate cost to go heuristic computation.
 
bool cacheCC_ {true}
 Flag to activate the collision check caching.
 
bool extendedFMT_ {true}
 Add new samples if the tree was not able to find a solution.
 
- 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

Bidirectional Asymptotically Optimal Fast Marching Tree algorithm developed by J. Starek, J.V. Gomez, et al.

Short description
BFMT* is an asymptotically-optimal, bidirectional sampling-based motion planning algorithm, which is guaranteed to converge to a shortest path solution. The algorithm is specifically aimed at solving complex motion planning problems in high-dimensional configuration spaces. The BFMT* algorithm essentially performs a lazy dynamic programming recursion on a set of probabilistically-drawn samples to grow two trees of paths, which moves steadily outward in cost-to-come space, one from the start state and the other one from the goal state.
Deviation from the paper
The implementation includes a cache in the collision checking since the original algorithm could check the same collision more than once. It increases the memory requirements to O(n logn), but as samples tend to infinity this bound tend to O(n).
External documentation
J. A. Starek, J. V. Gomez, E. Schmerling, L. Janson, L. Moreno, and M. Pavone, An Asymptotically-Optimal Sampling-Based Algorithm for Bi-directional Motion Planning, inIEEE/RSJ International Conference on Intelligent Robots Systems, 2015. [PDF]

Definition at line 146 of file BFMT.h.

Member Function Documentation

◆ plan()

bool ompl::geometric::BFMT::plan ( BiDirMotion x_init,
BiDirMotion x_goal,
BiDirMotion *&  connection_point,
const base::PlannerTerminationCondition ptc 
)
protected

Executes the actual planning algorithm, swapping and expanding the trees.

Todo:
This precomputation is useful only if the same planner is used many times. otherwise is probably a waste of time. Do a real precomputation before calling solve().

Definition at line 571 of file BFMT.cpp.


The documentation for this class was generated from the following files:
  • ompl/geometric/planners/fmt/BFMT.h
  • ompl/geometric/planners/fmt/src/BFMT.cpp