Loading...
Searching...
No Matches
TRRTstar.h
484 // *********************************************************************************************************
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition RandomNumbers.h:57
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
Abstract definition of optimization objectives.
Definition OptimizationObjective.h:72
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition PlannerData.h:175
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition PlannerTerminationCondition.h:64
base::Cost incCost
The incremental cost of this motion's parent to this motion (this is stored to save distance computat...
Definition TRRTstar.h:337
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state. This constructor automatically allocates memory for ...
Definition TRRTstar.h:317
std::vector< Motion * > children
The set of motions descending from the current motion.
Definition TRRTstar.h:340
base::Cost worstCost_
The least desirable (e.g., maximum) cost value in the search tree.
Definition TRRTstar.h:496
void setAdmissibleCostToCome(const bool admissible)
Controls whether pruning and new-state rejection uses an admissible cost-to-come estimate or not.
Definition TRRTstar.h:207
void setTempChangeFactor(double factor)
Set the factor by which the temperature is increased after a failed transition test....
Definition TRRTstar.h:269
void setNumSamplingAttempts(unsigned int numAttempts)
Set the number of attempts to make while performing rejection or informed sampling.
Definition TRRTstar.h:243
base::Cost solutionHeuristic(const Motion *motion) const
Computes the solution cost heuristically as the cost to come from start to the motion plus the cost t...
Definition TRRTstar.cpp:888
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition TRRTstar.cpp:659
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition TRRTstar.h:416
void calculateRewiringLowerBounds()
Calculate the k_RRG* and r_RRG* terms.
Definition TRRTstar.cpp:943
bool delayCC_
Option to delay and reduce collision checking within iterations.
Definition TRRTstar.h:442
double pruneThreshold_
The tree is pruned when the change in solution cost is greater than this fraction.
Definition TRRTstar.h:457
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition TRRTstar.h:420
std::vector< Motion * > goalMotions_
A list of states in the tree that satisfy the goal condition.
Definition TRRTstar.h:451
bool useAdmissibleCostToCome_
The admissibility of the new-state rejection heuristic.
Definition TRRTstar.h:460
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition TRRTstar.cpp:85
double getPruneThreshold() const
Get the current prune states percentage threshold parameter.
Definition TRRTstar.h:200
double getRewireFactor() const
Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg* > r_rrg* (or k_rrg = s \times k_r...
Definition TRRTstar.h:142
void removeFromParent(Motion *m)
Removes the given motion from the parent's child list.
Definition TRRTstar.cpp:623
bool getDelayCC() const
Get the state of the delayed collision checking option.
Definition TRRTstar.h:171
bool getAdmissibleCostToCome() const
Get the admissibility of the pruning and new-state rejection heuristic.
Definition TRRTstar.h:213
void setRewireFactor(double rewireFactor)
Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg* (or k_rrg = s \times k_rrg*).
Definition TRRTstar.h:134
double rewireFactor_
The rewiring factor, s, so that r_rrt = s \times r_rrt* > r_rrt* (or k_rrt = s \times k_rrt* > k_rrt*...
Definition TRRTstar.h:433
void setKNearest(bool useKNearest)
Use a k-nearest search for rewiring instead of a r-disc search.
Definition TRRTstar.h:231
double getInitTemperature() const
Get the temperature at the start of planning.
Definition TRRTstar.h:305
double prunedMeasure_
The measure of the problem when we pruned it (if this isn't in use, it will be set to si_->getSpaceMe...
Definition TRRTstar.h:479
void getNeighbors(Motion *motion, std::vector< Motion * > &nbh) const
Gets the neighbours of a given motion, using either k-nearest of radius as appropriate.
Definition TRRTstar.cpp:606
bool keepCondition(const Motion *motion, const base::Cost &threshold) const
Check whether the given motion passes the specified cost threshold, meaning it will be kept during pr...
Definition TRRTstar.cpp:874
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition TRRTstar.cpp:135
void addChildrenToList(std::queue< Motion *, std::deque< Motion * > > *motionList, Motion *motion)
Add the children of a vertex to the given list.
Definition TRRTstar.cpp:865
int pruneTree(const base::Cost &pruneTreeCost)
Prunes all those states which estimated total cost is higher than pruneTreeCost. Returns the number o...
Definition TRRTstar.cpp:679
double getTempChangeFactor() const
Get the factor by which the temperature rises based on current acceptance/rejection rate.
Definition TRRTstar.h:275
double temp_
Temperature parameter used to control the difficulty level of transition tests. Low temperatures limi...
Definition TRRTstar.h:493
bool getKNearest() const
Get the state of using a k-nearest search for rewiring.
Definition TRRTstar.h:237
void setCostThreshold(double maxCost)
Set the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...
Definition TRRTstar.h:283
base::Cost costThreshold_
All motion costs must be better than this cost (default is infinity).
Definition TRRTstar.h:499
void setDelayCC(bool delayCC)
Option that delays collision checking procedures. When it is enabled, all neighbors are sorted by cos...
Definition TRRTstar.h:165
unsigned int getNumSamplingAttempts() const
Get the number of attempts to make while performing rejection or informed sampling.
Definition TRRTstar.h:249
void setPruneThreshold(const double pp)
Set the fractional change in solution cost necessary for pruning to occur, i.e., prune if the new sol...
Definition TRRTstar.h:194
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states).
Definition TRRTstar.h:368
void setInitTemperature(double initTemperature)
Set the initial temperature at the beginning of the algorithm. Should be high to allow for initial ex...
Definition TRRTstar.h:298
void setRange(double distance)
Set the range the planner is supposed to use.
Definition TRRTstar.h:121
void updateChildCosts(Motion *m)
Updates the cost of the children of this node if the cost up to this node has changed.
Definition TRRTstar.cpp:635
void setTreePruning(bool prune)
Controls whether the tree is pruned during the search. This pruning removes a vertex if and only if i...
Definition TRRTstar.cpp:914
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition TRRTstar.cpp:157
void setBatchSize(unsigned int batchSize)
Set the batch size used for sample ordering.
Definition TRRTstar.h:219
unsigned int numSampleAttempts_
The number of attempts to make at informed sampling.
Definition TRRTstar.h:463
unsigned int getBatchSize() const
Get the batch size used for sample ordering.
Definition TRRTstar.h:225
double tempChangeFactor_
The value of the expression exp^T_rate. The temperature is increased by this factor whenever the tran...
Definition TRRTstar.h:503
bool transitionTest(const base::Cost &motionCost)
Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree.
Definition TRRTstar.cpp:957
double getCostThreshold() const
Get the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...
Definition TRRTstar.h:291
This namespace contains code that is specific to planning under geometric constraints.
Definition GeneticSearch.h:48
Main namespace. Contains everything in this library.
Definition MultiLevelPlanarManipulatorDemo.cpp:66
A class to store the exit status of Planner::solve().
Definition PlannerStatus.h:49