Class FMT

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class FMT : public ompl::base::Planner

Asymptotically Optimal Fast Marching Tree algorithm developed by L. Janson and M. Pavone.

It also implements the resampling strategy (extended FMT) included in the BiDirectional FMT* paper.

Short description

FMT* is an asymptotically-optimal 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 FMT* algorithm essentially performs a lazy dynamic programming recursion on a set of probabilistically-drawn samples to grow a tree of paths, which moves steadily outward in cost-to-come space.

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

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, in IEEE/RSJ International Conference on Intelligent Robots Systems, 2015. [PDF]

External documentation

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. DOI: 10.1177/0278364915577958[PDF]

Public Functions

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

Protected Types

using MotionBinHeap = ompl::BinaryHeap<Motion*, MotionCompare>

A binary heap for storing explored motions in cost-to-come sorted order.

Protected Functions

inline double distanceFunction(const Motion *a, const Motion *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.

void freeMemory()

Free the memory allocated by this planner.

void sampleFree(const ompl::base::PlannerTerminationCondition &ptc)

Sample a state from the free configuration space and save it into the nearest neighbors data structure.

void assureGoalIsSampled(const ompl::base::GoalSampleableRegion *goal)

For each goal region, check to see if any of the sampled states fall within that region. If not, add a goal state from that region directly into the set of vertices. In this way, FMT is able to find a solution, if one exists. If no sampled nodes are within a goal region, there would be no way for the algorithm to successfully find a path to that region.

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 saveNeighborhood(Motion *m)

Save the neighbors within a neighborhood of a given state. The strategy used (nearestK or nearestR depends on the planner configuration.

void traceSolutionPathThroughTree(Motion *goalMotion)

Trace the path from a goal state back to the start state and save the result as a solution in the Problem Definiton.

bool expandTreeFromNode(Motion **z)

Complete one iteration of the main loop of the FMT* 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.

void updateNeighborhood(Motion *m, std::vector<Motion*> nbh)

For a motion m, updates the stored neighborhoods of all its neighbors by by inserting m (maintaining the cost-based sorting). Computes the nearest neighbors if there is no stored neighborhood.

Motion *getBestParent(Motion *m, std::vector<Motion*> &neighbors, base::Cost &cMin)

Returns the best parent and the connection cost in the neighborhood of a motion m.

Protected Attributes

MotionBinHeap Open_

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<Motion*, std::vector<Motion*>> neighborhoods_

A map linking a motion to all of the motions within a distance r of that motion.

unsigned int numSamples_ = {1000u}

The number of samples to use when planning.

unsigned int collisionChecks_ = {0u}

Number of collision checks performed by the algorithm.

bool nearestK_ = {true}

Flag to activate the K nearest neighbors strategy.

bool cacheCC_ = {true}

Flag to activate the collision check caching.

bool heuristics_ = {false}

Flag to activate the cost to go heuristics.

double NNr_

Radius employed in the nearestR strategy.

unsigned int NNk_

K used in the nearestK strategy.

double freeSpaceVolume_

The volume of the free configuration space, computed as an upper bound with 95% confidence.

double radiusMultiplier_ = {1.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.

std::shared_ptr<NearestNeighbors<Motion*>> nn_

A nearest-neighbor datastructure containing the set of all motions.

base::StateSamplerPtr sampler_

State sampler.

base::OptimizationObjectivePtr opt_

The cost objective function.

Motion *lastGoalMotion_

The most recent goal motion. Used for PlannerData computation.

base::State *goalState_

Goal state caching to accelerate cost to go heuristic computation.

bool extendedFMT_ = {true}

Add new samples if the tree was not able to find a solution.

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_
class Motion

Representation of a 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

Public Functions

Motion() = default
inline Motion(const base::SpaceInformationPtr &si)

Constructor that allocates memory for the state.

~Motion() = default
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 void setParent(Motion *parent)

Set the parent motion of the current motion.

inline Motion *getParent() const

Get the parent motion of the current motion.

inline void setCost(const base::Cost cost)

Set the cost-to-come for the current motion.

inline base::Cost getCost() const

Get the cost-to-come for the current motion.

inline void setSetType(const SetType currentSet)

Specify the set that this motion belongs to.

inline SetType getSetType() const

Get the set that this motion belongs to.

inline bool alreadyCC(Motion *m)

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

inline void addCC(Motion *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.

inline std::vector<Motion*> &getChildren()

Get the children of the motion.

Protected Attributes

base::State *state_ = {nullptr}

The state contained by the motion.

Motion *parent_ = {nullptr}

The parent motion in the exploration tree.

base::Cost cost_ = {0.}

The cost of this motion.

base::Cost hcost_ = {0.}

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

SetType currentSet_ = {SET_UNVISITED}

The flag indicating which set a motion belongs to.

std::set<Motion*> collChecksDone_

Contains the connections attempted FROM this node.

std::vector<Motion*> children_

The set of motions descending from the current motion.

struct MotionCompare

Comparator used to order motions in a binary heap.

Public Functions

MotionCompare() = default
inline bool operator()(const Motion *m1, const Motion *m2) const

Public Members

base::OptimizationObjective *opt_ = {nullptr}
bool heuristics_ = {false}