Adaptively Informed Trees (AIT*) More...
#include <ompl/geometric/planners/informedtrees/AITstar.h>
Public Member Functions | |
AITstar (const ompl::base::SpaceInformationPtr &spaceInformation) | |
Constructs a AIT*. | |
~AITstar ()=default | |
Destructs a AIT*. | |
void | setup () override |
Additional setup that can only be done once a problem definition is set. | |
ompl::base::PlannerStatus::StatusType | ensureSetup () |
Checks whether the planner is successfully setup. | |
ompl::base::PlannerStatus::StatusType | ensureStartAndGoalStates (const ompl::base::PlannerTerminationCondition &terminationCondition) |
Checks whether the problem is successfully setup. | |
void | clear () override |
Clears the algorithm's internal state. | |
ompl::base::PlannerStatus | solve (const ompl::base::PlannerTerminationCondition &terminationCondition) override |
Solves a motion planning problem. | |
ompl::base::Cost | bestCost () const |
Get the cost of the incumbent solution. | |
void | getPlannerData (base::PlannerData &data) const override |
Get the planner data. | |
void | setBatchSize (std::size_t batchSize) |
Set the batch size. | |
std::size_t | getBatchSize () const |
Get the batch size. | |
void | setRewireFactor (double rewireFactor) |
Set the rewire factor of the RGG graph. | |
double | getRewireFactor () const |
Get the rewire factor of the RGG graph. | |
void | trackApproximateSolutions (bool track) |
Set whether to track approximate solutions. | |
bool | areApproximateSolutionsTracked () const |
Get whether approximate solutions are tracked. | |
void | enablePruning (bool prune) |
Set whether pruning is enabled or not. | |
bool | isPruningEnabled () const |
Get whether pruning is enabled or not. | |
void | setUseKNearest (bool useKNearest) |
Set whether to use a k-nearest RGG connection model. If false, AIT* uses an r-disc model. | |
bool | getUseKNearest () const |
Get whether to use a k-nearest RGG connection model. If false, AIT* uses an r-disc model. | |
void | setMaxNumberOfGoals (unsigned int numberOfGoals) |
Set the maximum number of goals AIT* will sample from sampleable goal regions. | |
unsigned int | getMaxNumberOfGoals () const |
Get the maximum number of goals AIT* will sample from sampleable goal regions. | |
std::vector< aitstar::Edge > | getEdgesInQueue () const |
Get the edge queue. | |
std::vector< std::shared_ptr< aitstar::Vertex > > | getVerticesInQueue () const |
Get the vertex queue. | |
aitstar::Edge | getNextEdgeInQueue () const |
Get the next edge in the queue. | |
std::shared_ptr< aitstar::Vertex > | getNextVertexInQueue () const |
Get the next vertex in the queue. | |
std::vector< std::shared_ptr< aitstar::Vertex > > | getVerticesInReverseSearchTree () const |
Get the vertices in the reverse search tree. | |
Public Member Functions inherited from ompl::base::Planner | |
Planner (const Planner &)=delete | |
Planner & | operator= (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 SpaceInformationPtr & | getSpaceInformation () const |
Get the space information this planner is using. | |
const ProblemDefinitionPtr & | getProblemDefinition () const |
Get the problem definition the planner is trying to solve. | |
ProblemDefinitionPtr & | getProblemDefinition () |
Get the problem definition the planner is trying to solve. | |
const PlannerInputStates & | getPlannerInputStates () 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 PlannerSpecs & | getSpecs () 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. | |
ParamSet & | params () |
Get the parameters for this planner. | |
const ParamSet & | params () const |
Get the parameters for this planner. | |
const PlannerProgressProperties & | getPlannerProgressProperties () 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 | |
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. | |
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::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
Adaptively Informed Trees (AIT*)
AIT* (Adaptively Informed Trees) is an almost-surely asymptotically optimal path planner. It aims to find an initial solution quickly and asymptotically converge to the globally optimal solution.
AIT* views the planning problem as the two subproblems of approximation and search, and approximates the free state space with an increasingly dense, edge-implicit random geometric graph (RGG), similar to BIT* and ABIT*.
AIT* uses an asymmetric bidirectional search that simultaneously estimates and exploits an accurate, adaptive heuristic that is specific to each problem instance. The reverse search (goal to start) does not perform collision detection on the edges and estimates cost-to-go values for all states in the RGG that are processed with the forward search (start to goal) which does perform collision detection. Because AIT* uses LPA* as the reverse search algorithm, the heuristic is admissible in the context of the current RGG and can efficiently be updated when the forward search detects a collision on an edge that is in the reverse search tree (as this indicates a flawed heuristic).
This implementation of AIT* can solve problems with multiple start and goal states and supports adding start and goal states while the planner is running. One can also turn off repairing the reverse search tree upon collision detection, which might be beneficial for problems in which collision detection is computationally inexpensive.
- Associated publication:
M. P. Strub, J. D. Gammell. “Adaptively Informed Trees (AIT*): Fast Asymptotically Optimal Path Planning through Adaptive Heuristics” in Proceedings of the IEEE international conference on robotics and automation (ICRA), Paris, France, 31 May – 4 Jun. 2020.
DOI: arXiv:2002.06589 Video 1: ICRA submission video. Video 2: ICRA presentation video
The documentation for this class was generated from the following files:
- ompl/geometric/planners/informedtrees/AITstar.h
- ompl/geometric/planners/informedtrees/src/AITstar.cpp