Loading...
Searching...
No Matches

Optimal Transition-based Rapidly-exploring Random Trees. More...

#include <ompl/geometric/planners/rrt/TRRTstar.h>

Inheritance diagram for ompl::geometric::TRRTstar:

Classes

class  Motion
 Representation of a motion. More...
struct  CostIndexCompare

Public Member Functions

 TRRTstar (const base::SpaceInformationPtr &si)
void getPlannerData (base::PlannerData &data) const override
 Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).
base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc) override
 Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work for more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.
void clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
void setup () override
 Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving.
void setGoalBias (double goalBias)
 Set the goal bias.
double getGoalBias () const
 Get the goal bias the planner is using.
void setRange (double distance)
 Set the range the planner is supposed to use.
double getRange () const
 Get the range the planner is using.
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*).
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_rrg* > k_rrg*).
template<template< typename T > class NN>
void setNearestNeighbors ()
 Set a different nearest neighbors datastructure.
void setDelayCC (bool delayCC)
 Option that delays collision checking procedures. When it is enabled, all neighbors are sorted by cost. The planner then goes through this list, starting with the lowest cost, checking for collisions in order to find a parent. The planner stops iterating through the list when a collision free parent is found. This prevents the planner from collision checking each neighbor, reducing computation time in scenarios where collision checking procedures are expensive.
bool getDelayCC () const
 Get the state of the delayed collision checking option.
void setTreePruning (bool prune)
 Controls whether the tree is pruned during the search. This pruning removes a vertex if and only if it and all its descendents passes the pruning condition. The pruning condition is whether the lower-bounding estimate of a solution constrained to pass the the vertex is greater than the current solution. Considering the descendents of a vertex prevents removing a descendent that may actually be capable of later providing a better solution once its incoming path passes through a different vertex (e.g., a change in homotopy class).
bool getTreePruning () const
 Get the state of the pruning option.
void setPruneThreshold (const double pp)
 Set the fractional change in solution cost necessary for pruning to occur, i.e., prune if the new solution is at least X% better than the old solution. (e.g., 0.0 will prune after every new solution, while 1.0 will never prune.).
double getPruneThreshold () const
 Get the current prune states percentage threshold parameter.
void setAdmissibleCostToCome (const bool admissible)
 Controls whether pruning and new-state rejection uses an admissible cost-to-come estimate or not.
bool getAdmissibleCostToCome () const
 Get the admissibility of the pruning and new-state rejection heuristic.
void setBatchSize (unsigned int batchSize)
 Set the batch size used for sample ordering.
unsigned int getBatchSize () const
 Get the batch size used for sample ordering.
void setKNearest (bool useKNearest)
 Use a k-nearest search for rewiring instead of a r-disc search.
bool getKNearest () const
 Get the state of using a k-nearest search for rewiring.
void setNumSamplingAttempts (unsigned int numAttempts)
 Set the number of attempts to make while performing rejection or informed sampling.
unsigned int getNumSamplingAttempts () const
 Get the number of attempts to make while performing rejection or informed sampling.
unsigned int numIterations () const
ompl::base::Cost bestCost () const
void setTempChangeFactor (double factor)
 Set the factor by which the temperature is increased after a failed transition test. This value should be in the range (0, 1], typically close to zero (default is 0.1). This value is an exponential (e^factor) that is multiplied with the current temperature.
double getTempChangeFactor () const
 Get the factor by which the temperature rises based on current acceptance/rejection rate.
void setCostThreshold (double maxCost)
 Set the cost threshold (default is infinity). Any motion cost that is not better than this cost (according to the optimization objective) will not be expanded by the planner.
double getCostThreshold () const
 Get the cost threshold (default is infinity). Any motion cost that is not better than this cost (according to the optimization objective) will not be expanded by the planner.
void setInitTemperature (double initTemperature)
 Set the initial temperature at the beginning of the algorithm. Should be high to allow for initial exploration.
double getInitTemperature () const
 Get the temperature at the start of planning.
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.
template<class T>
const T * as () const
 Cast this instance to a desired type.
const SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using.
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve.
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve.
const PlannerInputStatesgetPlannerInputStates () 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 PlannerSpecsgetSpecs () 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.
ParamSetparams ()
 Get the parameters for this planner.
const ParamSetparams () const
 Get the parameters for this planner.
const PlannerProgressPropertiesgetPlannerProgressProperties () 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.

Protected Member Functions

void allocSampler ()
 Create the samplers.
bool sampleUniform (base::State *statePtr)
 Generate a sample.
void freeMemory ()
 Free the memory allocated by this planner.
double distanceFunction (const Motion *a, const Motion *b) const
 Compute distance between motions (actually distance between contained states).
bool transitionTest (const base::Cost &motionCost)
 Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree.
void getNeighbors (Motion *motion, std::vector< Motion * > &nbh) const
 Gets the neighbours of a given motion, using either k-nearest of radius as appropriate.
void removeFromParent (Motion *m)
 Removes the given motion from the parent's child list.
void updateChildCosts (Motion *m)
 Updates the cost of the children of this node if the cost up to this node has changed.
int pruneTree (const base::Cost &pruneTreeCost)
 Prunes all those states which estimated total cost is higher than pruneTreeCost. Returns the number of motions pruned. Depends on the parameter set by setPruneStatesImprovementThreshold().
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 to go from the motion to the goal. If the parameter use_admissible_heuristic (setAdmissibleCostToCome()) is true, a heuristic estimate of the cost to come is used; otherwise, the current cost to come to the motion is used (which may overestimate the cost through the motion).
void addChildrenToList (std::queue< Motion *, std::deque< Motion * > > *motionList, Motion *motion)
 Add the children of a vertex to the given list.
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 pruning.
void calculateRewiringLowerBounds ()
 Calculate the k_RRG* and r_RRG* terms.
std::string numIterationsProperty () const
std::string bestCostProperty () const
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

base::StateSamplerPtr sampler_
 State sampler.
base::InformedSamplerPtr infSampler_
 An informed sampler.
std::shared_ptr< NearestNeighbors< Motion * > > nn_
 A nearest-neighbors datastructure containing the tree of motions.
double goalBias_ {.05}
 The fraction of time the goal is picked as the state to expand towards (if such a state is available).
double maxDistance_ {0.}
 The maximum length of a motion to be added to a tree.
RNG rng_
 The random number generator.
bool useKNearest_ {true}
 Option to use k-nearest search for rewiring.
double rewireFactor_ {1.1}
 The rewiring factor, s, so that r_rrt = s \times r_rrt* > r_rrt* (or k_rrt = s \times k_rrt* > k_rrt*).
double k_rrt_ {0u}
 A constant for k-nearest rewiring calculations.
double r_rrt_ {0.}
 A constant for r-disc rewiring calculations.
bool delayCC_ {true}
 Option to delay and reduce collision checking within iterations.
base::OptimizationObjectivePtr opt_
 Objective we're optimizing.
MotionbestGoalMotion_ {nullptr}
 The best goal motion.
std::vector< Motion * > goalMotions_
 A list of states in the tree that satisfy the goal condition.
bool useTreePruning_ {false}
 The status of the tree pruning option.
double pruneThreshold_ {.05}
 The tree is pruned when the change in solution cost is greater than this fraction.
bool useAdmissibleCostToCome_ {true}
 The admissibility of the new-state rejection heuristic.
unsigned int numSampleAttempts_ {100u}
 The number of attempts to make at informed sampling.
unsigned int batchSize_ {1u}
 The size of the batches.
std::vector< Motion * > startMotions_
 Stores the start states as Motions.
base::Cost bestCost_ {std::numeric_limits<double>::quiet_NaN()}
 Best cost found so far by algorithm.
base::Cost prunedCost_ {std::numeric_limits<double>::quiet_NaN()}
 The cost at which the graph was last pruned.
double prunedMeasure_ {0.}
 The measure of the problem when we pruned it (if this isn't in use, it will be set to si_->getSpaceMeasure()).
unsigned int iterations_ {0u}
 Number of iterations the algorithm performed.
double temp_
 Temperature parameter used to control the difficulty level of transition tests. Low temperatures limit the expansion to a slightly positive slopes, high temps enable to climb the steeper slopes. Dynamically tuned according to the information acquired during exploration.
base::Cost worstCost_ {base::Cost(std::numeric_limits<double>::infinity())}
 The least desirable (e.g., maximum) cost value in the search tree.
base::Cost costThreshold_ {base::Cost(std::numeric_limits<double>::infinity())}
 All motion costs must be better than this cost (default is infinity).
double tempChangeFactor_ {.1}
 The value of the expression exp^T_rate. The temperature is increased by this factor whenever the transition test fails.
double initTemperature_ {100.0}
 The initial value of temp_.
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.

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.

Detailed Description

Optimal Transition-based Rapidly-exploring Random Trees.

Short description
T-RRT* is an asymptotically optimal version of T-RRT. T-RRT is a RRT variant and tree-based motion planner that takes into consideration state costs to compute low-cost paths that follow valleys and saddle points of the configuration-space costmap. It uses transition tests from stochastic optimization methods to accept or reject new potential states. The notion of optimality is with respect to a specified OptimizationObjective (set in the ProblemDefinition). If a solution path's cost is within a user-specified cost-threshold, the algorithm terminates before the elapsed time.
Example usage
Please see Dave Coleman's exampleto see how TRRT can be used. TRRT* and ATRRT are used in the same way.
External documentation
D. Devaurs, T. Siméon, J. Cortés, Efficient sampling-based approaches to optimal path planning in complex cost spaces, in Algorithmic Foundations of Robotics XI. Springer Tracts in Advanced Robotics, VOL. 107, pp.143-159, 2015. DOI: 10.1007/978-3-319-16595-0_9

D. Devaurs, T. Siméon, J. Cortés, Optimal Path Planning in Complex Cost Spaces with Sampling-Based Algorithms, in IEEE Transactions on Automation Science and Engineering, VOL. 13, NO. 2, APRIL 2016. DOI: 10.1109/TASE.2015.2487881
[PDF]

Definition at line 81 of file TRRTstar.h.

Constructor & Destructor Documentation

◆ TRRTstar()

ompl::geometric::TRRTstar::TRRTstar ( const base::SpaceInformationPtr & si)

Definition at line 49 of file TRRTstar.cpp.

◆ ~TRRTstar()

ompl::geometric::TRRTstar::~TRRTstar ( )
override

Definition at line 80 of file TRRTstar.cpp.

Member Function Documentation

◆ addChildrenToList()

void ompl::geometric::TRRTstar::addChildrenToList ( std::queue< Motion *, std::deque< Motion * > > * motionList,
Motion * motion )
protected

Add the children of a vertex to the given list.

Definition at line 865 of file TRRTstar.cpp.

◆ allocSampler()

void ompl::geometric::TRRTstar::allocSampler ( )
protected

Create the samplers.

Definition at line 928 of file TRRTstar.cpp.

◆ bestCost()

ompl::base::Cost ompl::geometric::TRRTstar::bestCost ( ) const
inline

Definition at line 259 of file TRRTstar.h.

◆ bestCostProperty()

std::string ompl::geometric::TRRTstar::bestCostProperty ( ) const
inlineprotected

Definition at line 514 of file TRRTstar.h.

◆ calculateRewiringLowerBounds()

void ompl::geometric::TRRTstar::calculateRewiringLowerBounds ( )
protected

Calculate the k_RRG* and r_RRG* terms.

Definition at line 943 of file TRRTstar.cpp.

◆ clear()

void ompl::geometric::TRRTstar::clear ( )
overridevirtual

Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.

Reimplemented from ompl::base::Planner.

Definition at line 135 of file TRRTstar.cpp.

◆ distanceFunction()

double ompl::geometric::TRRTstar::distanceFunction ( const Motion * a,
const Motion * b ) const
inlineprotected

Compute distance between motions (actually distance between contained states).

Definition at line 368 of file TRRTstar.h.

◆ freeMemory()

void ompl::geometric::TRRTstar::freeMemory ( )
protected

Free the memory allocated by this planner.

Definition at line 644 of file TRRTstar.cpp.

◆ getAdmissibleCostToCome()

bool ompl::geometric::TRRTstar::getAdmissibleCostToCome ( ) const
inline

Get the admissibility of the pruning and new-state rejection heuristic.

Definition at line 213 of file TRRTstar.h.

◆ getBatchSize()

unsigned int ompl::geometric::TRRTstar::getBatchSize ( ) const
inline

Get the batch size used for sample ordering.

Definition at line 225 of file TRRTstar.h.

◆ getCostThreshold()

double ompl::geometric::TRRTstar::getCostThreshold ( ) const
inline

Get the cost threshold (default is infinity). Any motion cost that is not better than this cost (according to the optimization objective) will not be expanded by the planner.

Definition at line 291 of file TRRTstar.h.

◆ getDelayCC()

bool ompl::geometric::TRRTstar::getDelayCC ( ) const
inline

Get the state of the delayed collision checking option.

Definition at line 171 of file TRRTstar.h.

◆ getGoalBias()

double ompl::geometric::TRRTstar::getGoalBias ( ) const
inline

Get the goal bias the planner is using.

Definition at line 111 of file TRRTstar.h.

◆ getInitTemperature()

double ompl::geometric::TRRTstar::getInitTemperature ( ) const
inline

Get the temperature at the start of planning.

Definition at line 305 of file TRRTstar.h.

◆ getKNearest()

bool ompl::geometric::TRRTstar::getKNearest ( ) const
inline

Get the state of using a k-nearest search for rewiring.

Definition at line 237 of file TRRTstar.h.

◆ getNeighbors()

void ompl::geometric::TRRTstar::getNeighbors ( Motion * motion,
std::vector< Motion * > & nbh ) const
protected

Gets the neighbours of a given motion, using either k-nearest of radius as appropriate.

Definition at line 606 of file TRRTstar.cpp.

◆ getNumSamplingAttempts()

unsigned int ompl::geometric::TRRTstar::getNumSamplingAttempts ( ) const
inline

Get the number of attempts to make while performing rejection or informed sampling.

Definition at line 249 of file TRRTstar.h.

◆ getPlannerData()

void ompl::geometric::TRRTstar::getPlannerData ( base::PlannerData & data) const
overridevirtual

Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).

Reimplemented from ompl::base::Planner.

Definition at line 659 of file TRRTstar.cpp.

◆ getPruneThreshold()

double ompl::geometric::TRRTstar::getPruneThreshold ( ) const
inline

Get the current prune states percentage threshold parameter.

Definition at line 200 of file TRRTstar.h.

◆ getRange()

double ompl::geometric::TRRTstar::getRange ( ) const
inline

Get the range the planner is using.

Definition at line 127 of file TRRTstar.h.

◆ getRewireFactor()

double ompl::geometric::TRRTstar::getRewireFactor ( ) const
inline

Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg* > r_rrg* (or k_rrg = s \times k_rrg* > k_rrg*).

Definition at line 142 of file TRRTstar.h.

◆ getTempChangeFactor()

double ompl::geometric::TRRTstar::getTempChangeFactor ( ) const
inline

Get the factor by which the temperature rises based on current acceptance/rejection rate.

Definition at line 275 of file TRRTstar.h.

◆ getTreePruning()

bool ompl::geometric::TRRTstar::getTreePruning ( ) const
inline

Get the state of the pruning option.

Definition at line 186 of file TRRTstar.h.

◆ keepCondition()

bool ompl::geometric::TRRTstar::keepCondition ( const Motion * motion,
const base::Cost & threshold ) const
protected

Check whether the given motion passes the specified cost threshold, meaning it will be kept during pruning.

Definition at line 874 of file TRRTstar.cpp.

◆ numIterations()

unsigned int ompl::geometric::TRRTstar::numIterations ( ) const
inline

Definition at line 254 of file TRRTstar.h.

◆ numIterationsProperty()

std::string ompl::geometric::TRRTstar::numIterationsProperty ( ) const
inlineprotected

Definition at line 510 of file TRRTstar.h.

◆ pruneTree()

int ompl::geometric::TRRTstar::pruneTree ( const base::Cost & pruneTreeCost)
protected

Prunes all those states which estimated total cost is higher than pruneTreeCost. Returns the number of motions pruned. Depends on the parameter set by setPruneStatesImprovementThreshold().

Definition at line 679 of file TRRTstar.cpp.

◆ removeFromParent()

void ompl::geometric::TRRTstar::removeFromParent ( Motion * m)
protected

Removes the given motion from the parent's child list.

Definition at line 623 of file TRRTstar.cpp.

◆ sampleUniform()

bool ompl::geometric::TRRTstar::sampleUniform ( base::State * statePtr)
protected

Generate a sample.

Definition at line 934 of file TRRTstar.cpp.

◆ setAdmissibleCostToCome()

void ompl::geometric::TRRTstar::setAdmissibleCostToCome ( const bool admissible)
inline

Controls whether pruning and new-state rejection uses an admissible cost-to-come estimate or not.

Definition at line 207 of file TRRTstar.h.

◆ setBatchSize()

void ompl::geometric::TRRTstar::setBatchSize ( unsigned int batchSize)
inline

Set the batch size used for sample ordering.

Definition at line 219 of file TRRTstar.h.

◆ setCostThreshold()

void ompl::geometric::TRRTstar::setCostThreshold ( double maxCost)
inline

Set the cost threshold (default is infinity). Any motion cost that is not better than this cost (according to the optimization objective) will not be expanded by the planner.

Definition at line 283 of file TRRTstar.h.

◆ setDelayCC()

void ompl::geometric::TRRTstar::setDelayCC ( bool delayCC)
inline

Option that delays collision checking procedures. When it is enabled, all neighbors are sorted by cost. The planner then goes through this list, starting with the lowest cost, checking for collisions in order to find a parent. The planner stops iterating through the list when a collision free parent is found. This prevents the planner from collision checking each neighbor, reducing computation time in scenarios where collision checking procedures are expensive.

Definition at line 165 of file TRRTstar.h.

◆ setGoalBias()

void ompl::geometric::TRRTstar::setGoalBias ( double goalBias)
inline

Set the goal bias.

In the process of randomly selecting states in the state space to attempt to go towards, the algorithm may in fact choose the actual goal state, if it knows it, with some probability. This probability is a real number between 0.0 and 1.0; its value should usually be around 0.05 and should not be too large. It is probably a good idea to use the default value.

Definition at line 105 of file TRRTstar.h.

◆ setInitTemperature()

void ompl::geometric::TRRTstar::setInitTemperature ( double initTemperature)
inline

Set the initial temperature at the beginning of the algorithm. Should be high to allow for initial exploration.

Definition at line 298 of file TRRTstar.h.

◆ setKNearest()

void ompl::geometric::TRRTstar::setKNearest ( bool useKNearest)
inline

Use a k-nearest search for rewiring instead of a r-disc search.

Definition at line 231 of file TRRTstar.h.

◆ setNearestNeighbors()

template<template< typename T > class NN>
void ompl::geometric::TRRTstar::setNearestNeighbors ( )
inline

Set a different nearest neighbors datastructure.

Definition at line 149 of file TRRTstar.h.

◆ setNumSamplingAttempts()

void ompl::geometric::TRRTstar::setNumSamplingAttempts ( unsigned int numAttempts)
inline

Set the number of attempts to make while performing rejection or informed sampling.

Definition at line 243 of file TRRTstar.h.

◆ setPruneThreshold()

void ompl::geometric::TRRTstar::setPruneThreshold ( const double pp)
inline

Set the fractional change in solution cost necessary for pruning to occur, i.e., prune if the new solution is at least X% better than the old solution. (e.g., 0.0 will prune after every new solution, while 1.0 will never prune.).

Definition at line 194 of file TRRTstar.h.

◆ setRange()

void ompl::geometric::TRRTstar::setRange ( double distance)
inline

Set the range the planner is supposed to use.

This parameter greatly influences the runtime of the algorithm. It represents the maximum length of a motion to be added in the tree of motions.

Definition at line 121 of file TRRTstar.h.

◆ setRewireFactor()

void ompl::geometric::TRRTstar::setRewireFactor ( double rewireFactor)
inline

Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg* (or k_rrg = s \times k_rrg*).

Definition at line 134 of file TRRTstar.h.

◆ setTempChangeFactor()

void ompl::geometric::TRRTstar::setTempChangeFactor ( double factor)
inline

Set the factor by which the temperature is increased after a failed transition test. This value should be in the range (0, 1], typically close to zero (default is 0.1). This value is an exponential (e^factor) that is multiplied with the current temperature.

Definition at line 269 of file TRRTstar.h.

◆ setTreePruning()

void ompl::geometric::TRRTstar::setTreePruning ( bool prune)

Controls whether the tree is pruned during the search. This pruning removes a vertex if and only if it and all its descendents passes the pruning condition. The pruning condition is whether the lower-bounding estimate of a solution constrained to pass the the vertex is greater than the current solution. Considering the descendents of a vertex prevents removing a descendent that may actually be capable of later providing a better solution once its incoming path passes through a different vertex (e.g., a change in homotopy class).

Definition at line 914 of file TRRTstar.cpp.

◆ setup()

void ompl::geometric::TRRTstar::setup ( )
overridevirtual

Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving.

Reimplemented from ompl::base::Planner.

Definition at line 85 of file TRRTstar.cpp.

◆ solutionHeuristic()

ompl::base::Cost ompl::geometric::TRRTstar::solutionHeuristic ( const Motion * motion) const
protected

Computes the solution cost heuristically as the cost to come from start to the motion plus the cost to go from the motion to the goal. If the parameter use_admissible_heuristic (setAdmissibleCostToCome()) is true, a heuristic estimate of the cost to come is used; otherwise, the current cost to come to the motion is used (which may overestimate the cost through the motion).

Definition at line 888 of file TRRTstar.cpp.

◆ solve()

ompl::base::PlannerStatus ompl::geometric::TRRTstar::solve ( const base::PlannerTerminationCondition & ptc)
overridevirtual

Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work for more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.

Implements ompl::base::Planner.

Definition at line 157 of file TRRTstar.cpp.

◆ transitionTest()

bool ompl::geometric::TRRTstar::transitionTest ( const base::Cost & motionCost)
protected

Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree.

Parameters
motionCost- cost of the motion to be evaluated

Definition at line 957 of file TRRTstar.cpp.

◆ updateChildCosts()

void ompl::geometric::TRRTstar::updateChildCosts ( Motion * m)
protected

Updates the cost of the children of this node if the cost up to this node has changed.

Definition at line 635 of file TRRTstar.cpp.

Member Data Documentation

◆ batchSize_

unsigned int ompl::geometric::TRRTstar::batchSize_ {1u}
protected

The size of the batches.

Definition at line 466 of file TRRTstar.h.

◆ bestCost_

base::Cost ompl::geometric::TRRTstar::bestCost_ {std::numeric_limits<double>::quiet_NaN()}
protected

Best cost found so far by algorithm.

Definition at line 472 of file TRRTstar.h.

◆ bestGoalMotion_

Motion* ompl::geometric::TRRTstar::bestGoalMotion_ {nullptr}
protected

The best goal motion.

Definition at line 448 of file TRRTstar.h.

◆ costThreshold_

base::Cost ompl::geometric::TRRTstar::costThreshold_ {base::Cost(std::numeric_limits<double>::infinity())}
protected

All motion costs must be better than this cost (default is infinity).

Definition at line 499 of file TRRTstar.h.

◆ delayCC_

bool ompl::geometric::TRRTstar::delayCC_ {true}
protected

Option to delay and reduce collision checking within iterations.

Definition at line 442 of file TRRTstar.h.

◆ goalBias_

double ompl::geometric::TRRTstar::goalBias_ {.05}
protected

The fraction of time the goal is picked as the state to expand towards (if such a state is available).

Definition at line 420 of file TRRTstar.h.

◆ goalMotions_

std::vector<Motion *> ompl::geometric::TRRTstar::goalMotions_
protected

A list of states in the tree that satisfy the goal condition.

Definition at line 451 of file TRRTstar.h.

◆ infSampler_

base::InformedSamplerPtr ompl::geometric::TRRTstar::infSampler_
protected

An informed sampler.

Definition at line 413 of file TRRTstar.h.

◆ initTemperature_

double ompl::geometric::TRRTstar::initTemperature_ {100.0}
protected

The initial value of temp_.

Definition at line 506 of file TRRTstar.h.

◆ iterations_

unsigned int ompl::geometric::TRRTstar::iterations_ {0u}
protected

Number of iterations the algorithm performed.

Definition at line 482 of file TRRTstar.h.

◆ k_rrt_

double ompl::geometric::TRRTstar::k_rrt_ {0u}
protected

A constant for k-nearest rewiring calculations.

Definition at line 436 of file TRRTstar.h.

◆ maxDistance_

double ompl::geometric::TRRTstar::maxDistance_ {0.}
protected

The maximum length of a motion to be added to a tree.

Definition at line 423 of file TRRTstar.h.

◆ nn_

std::shared_ptr<NearestNeighbors<Motion *> > ompl::geometric::TRRTstar::nn_
protected

A nearest-neighbors datastructure containing the tree of motions.

Definition at line 416 of file TRRTstar.h.

◆ numSampleAttempts_

unsigned int ompl::geometric::TRRTstar::numSampleAttempts_ {100u}
protected

The number of attempts to make at informed sampling.

Definition at line 463 of file TRRTstar.h.

◆ opt_

base::OptimizationObjectivePtr ompl::geometric::TRRTstar::opt_
protected

Objective we're optimizing.

Definition at line 445 of file TRRTstar.h.

◆ prunedCost_

base::Cost ompl::geometric::TRRTstar::prunedCost_ {std::numeric_limits<double>::quiet_NaN()}
protected

The cost at which the graph was last pruned.

Definition at line 475 of file TRRTstar.h.

◆ prunedMeasure_

double ompl::geometric::TRRTstar::prunedMeasure_ {0.}
protected

The measure of the problem when we pruned it (if this isn't in use, it will be set to si_->getSpaceMeasure()).

Definition at line 479 of file TRRTstar.h.

◆ pruneThreshold_

double ompl::geometric::TRRTstar::pruneThreshold_ {.05}
protected

The tree is pruned when the change in solution cost is greater than this fraction.

Definition at line 457 of file TRRTstar.h.

◆ r_rrt_

double ompl::geometric::TRRTstar::r_rrt_ {0.}
protected

A constant for r-disc rewiring calculations.

Definition at line 439 of file TRRTstar.h.

◆ rewireFactor_

double ompl::geometric::TRRTstar::rewireFactor_ {1.1}
protected

The rewiring factor, s, so that r_rrt = s \times r_rrt* > r_rrt* (or k_rrt = s \times k_rrt* > k_rrt*).

Definition at line 433 of file TRRTstar.h.

◆ rng_

RNG ompl::geometric::TRRTstar::rng_
protected

The random number generator.

Definition at line 426 of file TRRTstar.h.

◆ sampler_

base::StateSamplerPtr ompl::geometric::TRRTstar::sampler_
protected

State sampler.

Definition at line 410 of file TRRTstar.h.

◆ startMotions_

std::vector<Motion *> ompl::geometric::TRRTstar::startMotions_
protected

Stores the start states as Motions.

Definition at line 469 of file TRRTstar.h.

◆ temp_

double ompl::geometric::TRRTstar::temp_
protected

Temperature parameter used to control the difficulty level of transition tests. Low temperatures limit the expansion to a slightly positive slopes, high temps enable to climb the steeper slopes. Dynamically tuned according to the information acquired during exploration.

Definition at line 493 of file TRRTstar.h.

◆ tempChangeFactor_

double ompl::geometric::TRRTstar::tempChangeFactor_ {.1}
protected

The value of the expression exp^T_rate. The temperature is increased by this factor whenever the transition test fails.

Definition at line 503 of file TRRTstar.h.

◆ useAdmissibleCostToCome_

bool ompl::geometric::TRRTstar::useAdmissibleCostToCome_ {true}
protected

The admissibility of the new-state rejection heuristic.

Definition at line 460 of file TRRTstar.h.

◆ useKNearest_

bool ompl::geometric::TRRTstar::useKNearest_ {true}
protected

Option to use k-nearest search for rewiring.

Definition at line 429 of file TRRTstar.h.

◆ useTreePruning_

bool ompl::geometric::TRRTstar::useTreePruning_ {false}
protected

The status of the tree pruning option.

Definition at line 454 of file TRRTstar.h.

◆ worstCost_

base::Cost ompl::geometric::TRRTstar::worstCost_ {base::Cost(std::numeric_limits<double>::infinity())}
protected

The least desirable (e.g., maximum) cost value in the search tree.

Definition at line 496 of file TRRTstar.h.


The documentation for this class was generated from the following files: