Class BFMT

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class BFMT : public ompl::base::Planner

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]

Public Types

enum TreeType

Tree identifier.

Values:

enumerator FWD
enumerator REV
enum ExploreType

Exploration strategy identifier.

Values:

enumerator SWAP_EVERY_TIME
enumerator CHOOSE_SMALLEST_Z
enum TerminateType

Termination strategy identifier.

Values:

enumerator FEASIBILITY
enumerator OPTIMALITY
using BiDirMotionPtrs = std::vector<BiDirMotion*>

Public Functions

BFMT(const base::SpaceInformationPtr &si)
~BFMT() override
virtual 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.

virtual 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.

virtual void clear() override

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

virtual 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).

inline 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.

inline unsigned int getNumSamples() const

Get the number of states that the planner will sample.

inline void setNearestK(bool nearestK)

If nearestK is true, FMT will be run using the Knearest strategy.

inline bool getNearestK() const

Get the state of the nearestK strategy.

inline 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.

inline double getRadiusMultiplier() const

Get the multiplier used for the nearest neighbors search radius.

inline 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)

inline double getFreeSpaceVolume() const

Get the volume of the free configuration space that is being used by the planner.

inline void setCacheCC(bool ccc)

Sets the collision check caching to save calls to the collision checker with slightly memory usage as a counterpart.

inline bool getCacheCC() const

Get the state of the collision check caching.

inline void setHeuristics(bool h)

Activates the cost to go heuristics when ordering the heap.

inline bool getHeuristics() const

Returns true if the heap is ordered taking into account cost to go heuristics.

inline void setExtendedFMT(bool e)

Activates the extended FMT*: adding new samples if planner does not finish successfully.

inline bool getExtendedFMT() const

Returns true if the extended FMT* is activated.

inline 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.

inline bool getExploration() const

Returns the exploration strategy.

inline 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.

inline bool getTermination() const

Returns the termination strategy.

inline void setPrecomputeNN(bool p)

Sets Nearest Neighbors precomputation. Currently, it precomputes once solve() has been called.

inline bool setPrecomputeNN() const

Returns true if Nearest Neighbor precomputation is done.

Protected Types

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

Protected Functions

void swapTrees()

Change the active tree.

inline void useFwdTree()

Sets forward tree active.

inline void useRevTree()

Sets reverse tree active.

inline 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.

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 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::State *heurGoalState_[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.

class BiDirMotion

Representation of a bidirectional motion.

Public Types

enum SetType

The FMT* planner begins with all nodes included in set Unvisited “Waiting for optimal connection”. As nodes are connected to the tree, they are transferred into set Open “Horizon of explored tree.” Once a node in Open is no longer close enough to the frontier to connect to any more nodes in Unvisited, it is removed from Open. These three SetTypes are flags indicating which set the node belongs to; Open, Unvisited, or Closed (neither)

Values:

enumerator SET_CLOSED
enumerator SET_OPEN
enumerator SET_UNVISITED
using BiDirMotionPtrs = std::vector<BiDirMotion*>

Public Functions

inline BiDirMotion(TreeType *tree)
inline BiDirMotion(const base::SpaceInformationPtr &si, TreeType *tree)

Constructor that allocates memory for the state.

inline base::Cost getCost() const

Set the state associated with the motion.

inline base::Cost getOtherCost() const

Get cost of this motion in the inactive tree.

inline void setCost(base::Cost cost)

Set the cost of the motion.

inline void setParent(BiDirMotion *parent)

Set the parent of the motion.

inline BiDirMotion *getParent() const

Get the parent of the motion.

inline void setChildren(BiDirMotionPtrs children)

Set the children of the motion.

inline BiDirMotionPtrs getChildren() const

Get the children of the motion.

inline void setCurrentSet(SetType set)

Set the current set of the motion.

inline SetType getCurrentSet() const

Fet the current set of the motion.

inline SetType getOtherSet() const

Get set of this motion in the inactive tree.

inline void setTreeType(TreeType *treePtr)

Set tree identifier for this motion.

inline TreeType getTreeType() const

Get tree identifier for this motion.

inline void setState(base::State *state)

Set the state associated with the motion.

inline base::State *getState() const

Get the state associated with the motion.

inline bool alreadyCC(BiDirMotion *m)

Returns true if the connection to m has been already tested and failed because of a collision.

inline void addCC(BiDirMotion *m)

Caches a failed collision check to m.

inline void setHeuristicCost(const base::Cost h)

Set the cost to go heuristic cost.

inline base::Cost getHeuristicCost() const

Get the cost to go heuristic cost.

Public Members

base::State *state_

The state contained by the motion.

BiDirMotion *parent_[2]

The parent motion in the exploration tree

BiDirMotionPtrs children_[2]

The set of motions descending from the current motion

SetType currentSet_[2]

Current set in which the motion is included.

TreeType *tree_

Tree identifier

base::Cost cost_[2]

The cost of this motion

base::Cost hcost_[2]

The minimum cost to go of this motion (heuristically computed)

std::set<BiDirMotion*> collChecksDone_

Contains the connections attempted FROM this node.

struct BiDirMotionCompare

Comparator used to order motions in a binary heap.

Public Functions

inline bool operator()(const BiDirMotion *p1, const BiDirMotion *p2) const

Public Members

base::OptimizationObjective *opt_
bool heuristics_
struct CostIndexCompare

Public Functions

inline CostIndexCompare(const std::vector<base::Cost> &costs, const base::OptimizationObjective &opt)
inline bool operator()(unsigned i, unsigned j)

Public Members

const std::vector<base::Cost> &costs_
const base::OptimizationObjective &opt_