Class EITstar
Defined in File EITstar.h
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Derived Type
public ompl::geometric::EIRMstar
(Class EIRMstar)
Class Documentation
-
class EITstar : public ompl::base::Planner
Effort Informed Trees (EIT*)
EIT* (Effort 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.
EIT* 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 AIT*.
EIT* uses an asymmetric bidirectional search that simultaneously calculates and exploits accurate, problem-specific cost and effort heuristics. The reverse search (goal to start) only performs sparse collision detection on the edges and does not evaluate true edge costs. It calculates cost-to-go and effort-to-go heuristics for all states in the RGG that are processed with the forward search (start to goal). This is achieved by integrating a priori cost and effort heuristics over the best reverse path to each state. The forward search (start to goal) performs collision detection and is informed by the heuristics calculated by the reverse search. The forward search in turn informes the reverse search when it detects collisions on an edge that was used to calculate the heuristics which causes the reverse search to update them. In this way, both searches in EIT* continuously inform each other with complementary information. This results in fast initial solution times and almost-sure asymptotic convergence towards the optimal solution.
This implementation of EIT* can solve problems with multiple start and goal states and supports adding start and goal states while the planner is running.
M. P. Strub, J. D. Gammell. “AIT* and EIT*: Asymmetric bidirectional sampling-based path planning” The International Journal of Robotics Research (IJRR), in revision, 2021.
- Associated publications:
arXiv: arXiv:2111.01877 Video 1: IJRR trailer Video 2: IJRR extension 2
Subclassed by ompl::geometric::EIRMstar
Public Functions
Constructs an instance of EIT* using the provided space information.
-
~EITstar()
Destructs this instance of EIT*.
-
virtual void setup() override
Setup the parts of the planner that rely on the problem definition being set.
-
virtual ompl::base::PlannerStatus solve(const ompl::base::PlannerTerminationCondition &terminationCondition) override
Solves the provided motion planning problem, respecting the given termination condition.
-
virtual void clear() override
Clears all internal planner structures but retains settings. Subsequent calls to solve() will start from scratch.
-
virtual void clearQuery() override
Clears all query-specific information, such as start and goal states and search trees. EIT* retains the samples and collision checking cache of previous queries.
-
void setBatchSize(unsigned int numSamples)
Sets the number of samples per batch.
-
unsigned int getBatchSize() const
Returns the number of samples per batch.
-
void setInitialNumberOfSparseCollisionChecks(std::size_t numChecks)
Sets the initial number of collision checks on the reverse search.
-
void setRadiusFactor(double factor)
Sets the radius factor.
-
double getRadiusFactor() const
Returns the radius factor.
-
void setSuboptimalityFactor(double factor)
Sets the (initial) suboptimality factor.
-
void enablePruning(bool prune)
Set whether pruning is enabled or not.
-
bool isPruningEnabled() const
Returns whether pruning is enabled or not.
-
void trackApproximateSolutions(bool track)
Sets whether to track approximate solutions or not.
-
bool areApproximateSolutionsTracked() const
Returns whether approximate solutions are tracked or not.
-
void setUseKNearest(bool useKNearest)
Set whether to use a k-nearest RGG connection model. If false, EIT* uses an r-disc model.
-
bool getUseKNearest() const
Returns whether to use a k-nearest RGG connection model. If false, EIT* uses an r-disc model.
-
void setMaxNumberOfGoals(unsigned int numberOfGoals)
Set the maximum number of goals EIT* will sample from sampleable goal regions.
-
unsigned int getMaxNumberOfGoals() const
Returns the maximum number of goals EIT* will sample from sampleable goal regions.
-
bool isForwardQueueEmpty() const
Returns true if the forward queue is empty.
-
unsigned int getForwardEffort() const
Returns the effort of the edge at the top of the forward queue.
-
bool isReverseQueueEmpty() const
Returns true if the reverse queue is empty.
Checks whether the state is a start state.
Checks whether the state is a goal state.
-
virtual void getPlannerData(base::PlannerData &data) const override
Returns the planner data.
Protected Functions
-
void enableMultiquery(bool multiquery)
Set wheter multiquery is enabled or not.
-
bool isMultiqueryEnabled() const
Get wheter multiquery is enabled or not.
-
void setStartGoalPruningThreshold(unsigned int threshold)
Set start/goal pruning threshold.
-
unsigned int getStartGoalPruningThreshold() const
Get threshold at which we prune starts/goals.