EITstar.h
231 bool continueSolving(const ompl::base::PlannerTerminationCondition &terminationCondition) const;
void enableMultiquery(bool multiquery)
Set wheter multiquery is enabled or not.
Definition: EITstar.cpp:316
void clear() override
Clears all internal planner structures but retains settings. Subsequent calls to solve() will start f...
Definition: EITstar.cpp:213
void clearQuery() override
Clears all query-specific information, such as start and goal states and search trees....
Definition: EITstar.cpp:248
eitstar::Edge getNextForwardEdge() const
Returns the next edge in the forward queue.
Definition: EITstar.cpp:429
unsigned int getForwardEffort() const
Returns the effort of the edge at the top of the forward queue.
Definition: EITstar.cpp:850
ompl::base::Cost bestCost() const
Returns the cost of the current best solution.
Definition: EITstar.cpp:279
bool getUseKNearest() const
Returns whether to use a k-nearest RGG connection model. If false, EIT* uses an r-disc model.
Definition: EITstar.cpp:362
void setStartGoalPruningThreshold(unsigned int threshold)
Set start/goal pruning threshold.
Definition: EITstar.cpp:327
unsigned int getStartGoalPruningThreshold() const
Get threshold at which we prune starts/goals.
Definition: EITstar.cpp:332
std::vector< eitstar::Edge > getReverseQueue() const
Returns a copy of the reverse queue.
Definition: EITstar.cpp:394
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:111
bool isReverseQueueEmpty() const
Returns true if the reverse queue is empty.
Definition: EITstar.cpp:383
bool isStart(const std::shared_ptr< eitstar::State > &state) const
Checks whether the state is a start state.
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:238
void setup() override
Setup the parts of the planner that rely on the problem definition being set.
Definition: EITstar.cpp:96
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition: PlannerTerminationCondition.h:127
bool areApproximateSolutionsTracked() const
Returns whether approximate solutions are tracked or not.
Definition: EITstar.cpp:352
EITstar(const std::shared_ptr< ompl::base::SpaceInformation > &spaceInfo)
Constructs an instance of EIT* using the provided space information.
Definition: EITstar.cpp:52
void trackApproximateSolutions(bool track)
Sets whether to track approximate solutions or not.
Definition: EITstar.cpp:347
std::vector< eitstar::Edge > getReverseTree() const
Returns copies of the edges in the reverse tree.
Definition: EITstar.cpp:399
void setBatchSize(unsigned int numSamples)
Sets the number of samples per batch.
Definition: EITstar.cpp:284
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:112
ompl::base::PlannerStatus solve(const ompl::base::PlannerTerminationCondition &terminationCondition) override
Solves the provided motion planning problem, respecting the given termination condition.
Definition: EITstar.cpp:173
std::vector< eitstar::Edge > getForwardQueue() const
Returns a copy of the forward queue.
Definition: EITstar.cpp:389
unsigned int getMaxNumberOfGoals() const
Returns the maximum number of goals EIT* will sample from sampleable goal regions.
Definition: EITstar.cpp:372
void setUseKNearest(bool useKNearest)
Set whether to use a k-nearest RGG connection model. If false, EIT* uses an r-disc model.
Definition: EITstar.cpp:357
void setInitialNumberOfSparseCollisionChecks(std::size_t numChecks)
Sets the initial number of collision checks on the reverse search.
Definition: EITstar.cpp:294
bool isGoal(const std::shared_ptr< eitstar::State > &state) const
Checks whether the state is a goal state.
bool isForwardQueueEmpty() const
Returns true if the forward queue is empty.
Definition: EITstar.cpp:377
void setMaxNumberOfGoals(unsigned int numberOfGoals)
Set the maximum number of goals EIT* will sample from sampleable goal regions.
Definition: EITstar.cpp:367
eitstar::Edge getNextReverseEdge() const
Returns the next edge in the reverse queue.
Definition: EITstar.cpp:439
void setSuboptimalityFactor(double factor)
Sets the (initial) suboptimality factor.
Definition: EITstar.cpp:311
void getPlannerData(base::PlannerData &data) const override
Returns the planner data.
Definition: EITstar.cpp:449
unsigned int getBatchSize() const
Returns the number of samples per batch.
Definition: EITstar.cpp:289