Advanced Batch Informed Trees (ABIT*) More...
#include <ompl/geometric/planners/informedtrees/ABITstar.h>
Public Member Functions | |
ABITstar (const base::SpaceInformationPtr &spaceInfo, const std::string &name="ABITstar") | |
void | setInitialInflationFactor (double factor) |
Set the inflation factor for the initial search. | |
void | setInflationScalingParameter (double parameter) |
Set the parameter for the inflation factor update policy. | |
void | setTruncationScalingParameter (double parameter) |
Set the parameter for the truncation factor update policy. | |
double | getInitialInflationFactor () const |
Get the inflation factor for the initial search. | |
double | getInflationScalingParameter () const |
Get the inflation scaling parameter. | |
double | getTruncationScalingParameter () const |
Get the truncation scaling parameter. | |
double | getCurrentInflationFactor () const |
Get the inflation factor for the current search. | |
double | getCurrentTruncationFactor () const |
Get the truncation factor for the current search. | |
Public Member Functions inherited from ompl::geometric::BITstar | |
BITstar (const base::SpaceInformationPtr &spaceInfo, const std::string &name="kBITstar") | |
Construct with a pointer to the space information and an optional name. | |
virtual | ~BITstar () override=default |
Destruct using the default destructor. | |
void | setup () override |
Setup the algorithm. | |
void | clear () override |
Clear the algorithm's internal state. | |
base::PlannerStatus | solve (const base::PlannerTerminationCondition &terminationCondition) override |
Solve the problem given a termination condition. | |
void | getPlannerData (base::PlannerData &data) const override |
Get results. | |
std::pair< const ompl::base::State *, const ompl::base::State * > | getNextEdgeInQueue () |
Get the next edge to be processed. Causes vertices in the queue to be expanded (if necessary) and therefore effects the run timings of the algorithm, but helpful for some videos and debugging. | |
ompl::base::Cost | getNextEdgeValueInQueue () |
Get the value of the next edge to be processed. Causes vertices in the queue to be expanded (if necessary) and therefore effects the run timings of the algorithm, but helpful for some videos and debugging. | |
void | getEdgeQueue (VertexConstPtrPairVector *edgesInQueue) |
Get the whole messy set of edges in the queue. Expensive but helpful for some videos. | |
unsigned int | numIterations () const |
Get the number of iterations completed. | |
ompl::base::Cost | bestCost () const |
Retrieve the best exact-solution cost found. | |
unsigned int | numBatches () const |
Retrieve the number of batches processed as the raw data. | |
void | setRewireFactor (double rewireFactor) |
Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg*. | |
double | getRewireFactor () const |
Get the rewiring scale factor. | |
void | setAverageNumOfAllowedFailedAttemptsWhenSampling (std::size_t number) |
Set the average number of allowed failed attempts when sampling. | |
std::size_t | getAverageNumOfAllowedFailedAttemptsWhenSampling () const |
Get the average number of allowed failed attempts when sampling. | |
void | setSamplesPerBatch (unsigned int n) |
Set the number of samplers per batch. | |
unsigned int | getSamplesPerBatch () const |
Get the number of samplers per batch. | |
void | setUseKNearest (bool useKNearest) |
Enable a k-nearest search for instead of an r-disc search. | |
bool | getUseKNearest () const |
Get whether a k-nearest search is being used. | |
void | setStrictQueueOrdering (bool beStrict) |
Enable "strict sorting" of the edge queue. Rewirings can change the position in the queue of an edge. When strict sorting is enabled, the effected edges are resorted immediately, while disabling strict sorting delays this resorting until the end of the batch. | |
bool | getStrictQueueOrdering () const |
Get whether strict queue ordering is in use. | |
void | setPruning (bool prune) |
Enable pruning of vertices/samples that CANNOT improve the current solution. When a vertex in the graph is pruned, it's descendents are also pruned (if they also cannot improve the solution) or placed back in the set of free samples (if they could improve the solution). This assures that a uniform density is maintained. | |
bool | getPruning () const |
Get whether graph and sample pruning is in use. | |
void | setPruneThresholdFraction (double fractionalChange) |
Set the fractional change in the solution cost AND problem measure necessary for pruning to occur. | |
double | getPruneThresholdFraction () const |
Get the fractional change in the solution cost AND problem measure necessary for pruning to occur. | |
void | setDelayRewiringUntilInitialSolution (bool delayRewiring) |
Delay the consideration of rewiring edges until an initial solution is found. When multiple batches are required to find an initial solution, this can improve the time required to do so, by delaying improvements in the cost-to-come to a connected vertex. As the rewiring edges are considered once an initial solution is found, this has no effect on the theoretical asymptotic optimality of the planner. More... | |
bool | getDelayRewiringUntilInitialSolution () const |
Get whether BIT* is delaying rewiring until a solution is found. | |
void | setJustInTimeSampling (bool useJit) |
Delay the generation of samples until they are necessary. This only works when using an r-disc connection scheme, and is currently only implemented for problems seeking to minimize path length. This helps reduce the complexity of nearest-neighbour look ups, and can be particularly beneficial in unbounded planning problems where selecting an appropriate bounding box is difficult. With JIT sampling enabled, BIT* can solve planning problems whose state space has infinite boundaries. When enumerating outgoing edges from a vertex, BIT* uses JIT sampling to assure that the area within r of the vertex has been sampled during this batch. This is done in a way that maintains uniform sample distribution and has no effect on the theoretical asymptotic optimality of the planner. More... | |
bool | getJustInTimeSampling () const |
Get whether we're using just-in-time sampling. | |
void | setDropSamplesOnPrune (bool dropSamples) |
Drop all unconnected samples when pruning, regardless of their heuristic value. This provides a method for BIT* to remove samples that have not been connected to the graph and may be beneficial in problems where portions of the free space are unreachable (i.e., disconnected). BIT* calculates the connection radius for each batch from the underlying uniform distribution of states. The resulting larger connection radius may be detrimental in areas where the graph is dense, but maintains the theoretical asymptotic optimality of the planner. More... | |
bool | getDropSamplesOnPrune () const |
Get whether unconnected samples are dropped on pruning. | |
void | setStopOnSolnImprovement (bool stopOnChange) |
Stop the planner each time a solution improvement is found. Useful for examining the intermediate solutions found by BIT*. | |
bool | getStopOnSolnImprovement () const |
Get whether BIT* stops each time a solution is found. | |
void | setConsiderApproximateSolutions (bool findApproximate) |
Set BIT* to consider approximate solutions during its initial search. | |
bool | getConsiderApproximateSolutions () const |
Get whether BIT* is considering approximate solutions. | |
template<template< typename T > class NN> | |
void | setNearestNeighbors () |
Set a different nearest neighbours datastructure. | |
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::geometric::BITstar | |
using | VertexPtr = std::shared_ptr< Vertex > |
A shared pointer to a vertex. | |
using | VertexConstPtr = std::shared_ptr< const Vertex > |
A shared pointer to a const vertex. | |
using | VertexWeakPtr = std::weak_ptr< Vertex > |
A weak pointer to a vertex. | |
using | VertexPtrVector = std::vector< VertexPtr > |
A vector of shared pointers to vertices. | |
using | VertexConstPtrVector = std::vector< VertexConstPtr > |
A vector of shared pointers to const vertices. | |
using | VertexId = unsigned int |
The vertex id type. | |
using | VertexPtrPair = std::pair< VertexPtr, VertexPtr > |
A pair of vertices, i.e., an edge. | |
using | VertexConstPtrPair = std::pair< VertexConstPtr, VertexConstPtr > |
A pair of const vertices, i.e., an edge. | |
using | VertexPtrPairVector = std::vector< VertexPtrPair > |
A vector of pairs of vertices, i.e., a vector of edges. | |
using | VertexConstPtrPairVector = std::vector< VertexConstPtrPair > |
A vector of pairs of const vertices, i.e., a vector of edges. | |
using | VertexPtrNNPtr = std::shared_ptr< NearestNeighbors< VertexPtr > > |
The OMPL::NearestNeighbors structure. | |
using | NameFunc = std::function< std::string()> |
A utility functor for ImplicitGraph and SearchQueue. | |
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::geometric::BITstar | |
void | setInitialInflationFactor (double factor) |
Set the inflation for the initial search of RGG approximation. See ABIT*'s class description for more details about the inflation factor update policy. | |
void | setInflationScalingParameter (double parameter) |
The parameter that scales the inflation factor on the second search of each RGG approximation. See ABIT*'s class description for more details about the inflation factor update policy. | |
void | setTruncationScalingParameter (double parameter) |
Sets the parameter that scales the truncation factor for the searches of each RGG approximation. See ABIT*'s class description for more details about the truncation factor update policy. | |
void | enableCascadingRewirings (bool enable) |
Enable the cascading of rewirings. | |
double | getInitialInflationFactor () const |
Get the inflation factor for the initial search. | |
double | getInflationScalingParameter () const |
Get the inflation scaling parameter. | |
double | getTruncationScalingParameter () const |
Get the truncation factor parameter. | |
double | getCurrentInflationFactor () const |
Get the inflation factor for the current search. | |
double | getCurrentTruncationFactor () const |
Get the truncation factor for the current search. | |
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
Advanced Batch Informed Trees (ABIT*)
ABIT* (Advanced Batch Informed Trees) is an almost-surely asymptotically optimal path planner. It views the planning problem as the two subproblems of approximation and search. This perspective allows it use advanced graph-search techniques, such as inflation and truncation.
This implementation of ABIT* derives from BIT* which means it benefits from a couple of features not mentioned in the ABIT* publication. It can handle multiple starts, multiple goals, a variety of optimization objectives (e.g., path length), and with just-in-time sampling, infinite problem domains. Note that for some of optimization objectives, the user must specify a suitable heuristic and that when this heuristic is not specified, it will use the conservative/always admissible zero-heuristic.
This implementation also includes some new advancements, including the ability to prioritize exploration until an initial solution is found (Delayed rewiring), the ability to generate samples only when necessary (Just-in-time sampling), and the ability to periodically remove samples that have yet to be connected to the graph (Sample dropping). With just-in-time sampling, ABIT* can even solve planning problems with infinite state space boundaries, i.e., (-inf, inf).
The inflation and truncation factor update policies of this implementation reflect the policies used to create the experimental results in ABIT*'s publication. Each increasingly dense RGG is searched twice, once with a very high inflation factor (gABITstarSetInitialInflationFactor, 1'000'000 by default), and once with an inflation factor that scales as 1 + inflation_parameter / q, where inflation_parameter is a parameter that scales the inflation factor (gABITstarSetInflationScalingParameter, 10 by default) is and q is the number of samples. Each search is truncated with a truncation factor of 1 + truncation_parameter / q, where truncation_parameter is a parameter that influences the truncation factor (gABITstarSetTruncationScalingParameter, 5 by default) and q is the number of samples again. For more information see ABIT*'s publication.
- Associated publication:
M. P. Strub, J. D. Gammell. “Advanced BIT* (ABIT*): Sampling-based planning with advanced graph-search techniques.” 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
Definition at line 150 of file ABITstar.h.
The documentation for this class was generated from the following files:
- ompl/geometric/planners/informedtrees/ABITstar.h
- ompl/geometric/planners/informedtrees/src/ABITstar.cpp