ompl::geometric::FMT Class Reference

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

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

Inheritance diagram for ompl::geometric::FMT:

List of all members.

Classes

class  Motion
 Representation of a motion. More...
struct  MotionCompare
 Comparator used to order motions in a binary heap. More...

Public Member Functions

 FMT (const base::SpaceInformationPtr &si)
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.
virtual base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc)
 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). The function terminates if the call to ptc returns true.
virtual void clear ()
 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
 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 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, A. Clark, and M. Pavone, "Fast Marching Trees: a Fast Marching Sampling-Based Method for Optimal Motion Planning in Many Dimensions," International Symposium on Robotics Research, 2013. http://arxiv.org/pdf/1306.3532v3.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.

Protected Types

typedef ompl::BinaryHeap
< Motion *, MotionCompare
MotionBinHeap
 A binary heap for storing explored motions in cost-to-come sorted order.

Protected Member Functions

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 (const 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, A. Clark, and M. Pavone, "Fast Marching Trees: a Fast Marching Sampling-Based Method for Optimal Motion Planning in Many Dimensions," International Journal on Robotics Research, 2013. http://arxiv.org/pdf/1306.3532v3.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, const double r)
 Save the neighbors within a given radius of a state.
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, const double r)
 Complete one iteration of the main loop of the FMT* algorithm: Find all nodes in set W within a radius r of the node z. Attempt to connect them to their optimal cost-to-come parent in set H. Remove all newly connected nodes from W and insert them into H. Remove motion z from H, and update z to be the current lowest cost-to-come node in H.

Protected Attributes

MotionBinHeap H_
 A binary heap for storing explored motions in cost-to-come sorted order. The motions in H have been explored, yet are still close enough to the frontier of the explored set H to be connected to nodes in the unexplored set W.
std::map< Motion
*, MotionBinHeap::Element * > 
hElements_
 A map of all of the elements stored within the MotionBinHeap H, used to convert between Motion *and Element*.
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_
 The number of samples to use when planning.
double freeSpaceVolume_
 The volume of the free configuration space.
double radiusMultiplier_
 This planner uses a nearest neighbor search radius proportional to the lower bound for optimality derived for FMT* in Section 4 of [L. Janson, A. Clark, and M. Pavone, "Fast Marching Trees: a Fast Marching Sampling-Based Method for Optimal Motion Planning in Many Dimensions," International Journal on Robotics Research, 2013. http://arxiv.org/pdf/1306.3532v3.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.
boost::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.
MotionlastGoalMotion_
 The most recent goal motion. Used for PlannerData computation.

Detailed Description

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

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.
External documentation
L. Janson, A. Clark, and M. Pavone, Fast Marching Trees: a Fast Marching Sampling-Based Method for Optimal Motion Planning in Many Dimensions, International Journal on Robotics Research, 2014. Submitted. http://arxiv.org/pdf/1306.3532v3.pdf
[[PDF]](http://web.stanford.edu/~pavone/papers/Janson.Pavone.IJRR14.pdf)

Definition at line 77 of file FMT.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines