ompl::geometric::RRTsharp Class Reference

Optimal Rapidly-exploring Random Trees Maintaining An Optimal Tree. More...

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

Inheritance diagram for ompl::geometric::RRTsharp:

Public Member Functions

 RRTsharp (const base::SpaceInformationPtr &si)
 
void setEpsilon (double) override
 Overwrite of RRTXstatic setEpsilon. It does nothing but warn the user that this parameter cannot be changed.
 
- Public Member Functions inherited from ompl::geometric::RRTXstatic
 RRTXstatic (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. More...
 
double getGoalBias () const
 Get the goal bias the planner is using.
 
void setInformedSampling (bool informedSampling)
 Use direct sampling of the heuristic for the generation of random samples (e.g., x_rand). If a direct sampling method is not defined for the objective, rejection sampling will be used by default.
 
bool getInformedSampling () const
 Get the state direct heuristic sampling.
 
void setSampleRejection (bool reject)
 Controls whether heuristic rejection is used on samples (e.g., x_rand)
 
bool getSampleRejection () const
 Get the state of the sample rejection option.
 
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.
 
double getEpsilon () const
 Get the threshold epsilon the planner is using.
 
void setRange (double distance)
 Set the range the planner is supposed to use. More...
 
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 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 setUpdateChildren (bool val)
 Set whether or not to always propagate cost updates to children.
 
bool getUpdateChildren () const
 True if the cost is always propagate to children.
 
void setVariant (const int variant)
 Set variant used for rejection sampling.
 
int getVariant () const
 Get variant used for rejection sampling.
 
void setAlpha (const double a)
 Set the value alpha used for rejection sampling.
 
double getAlpha () const
 Get the value alpha used for rejection sampling.
 
unsigned int numIterations () const
 
ompl::base::Cost bestCost () const
 
- Public Member Functions inherited from ompl::base::Planner
 Planner (const Planner &)=delete
 
Planneroperator= (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 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.
 

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.
 
- Protected Member Functions inherited from ompl::geometric::RRTXstatic
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)
 
void updateQueue (Motion *x)
 Update (or add) a motion in the queue.
 
void removeFromParent (Motion *m)
 Removes the given motion from the parent's child list.
 
void getNeighbors (Motion *motion) const
 Gets the neighbours of a given motion, using either k-nearest of radius as appropriate.
 
void calculateRewiringLowerBounds ()
 Calculate the k_RRG* and r_RRG* terms.
 
void calculateRRG ()
 Calculate the rrg_r_ and rrg_k_ terms.
 
bool includeVertex (const Motion *x) const
 Test if the vertex should be included according to the variant in use.
 
std::string numIterationsProperty () const
 
std::string bestCostProperty () const
 
std::string numMotionsProperty () 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 inherited from ompl::geometric::RRTXstatic
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_rrg = s \times r_rrg* > r_rrg* (or k_rrg = s \times k_rrg* > k_rrg*)
 
double k_rrt_ {0u}
 A constant for k-nearest rewiring calculations.
 
double r_rrt_ {0.}
 A constant for r-disc rewiring calculations.
 
base::OptimizationObjectivePtr opt_
 Objective we're optimizing.
 
MotionlastGoalMotion_ {nullptr}
 The most recent goal motion. Used for PlannerData computation.
 
std::vector< Motion * > goalMotions_
 A list of states in the tree that satisfy the goal condition.
 
base::Cost bestCost_ {std::numeric_limits<double>::quiet_NaN()}
 Best cost found so far by algorithm.
 
unsigned int iterations_ {0u}
 Number of iterations the algorithm performed.
 
MotionCompare mc_
 Comparator of motions, used to order the queue.
 
BinaryHeap< Motion *, MotionCompareq_
 Queue to order the nodes to update.
 
base::Cost epsilonCost_ {0.}
 Threshold for the propagation of information.
 
bool updateChildren_ {true}
 Whether or not to propagate the cost to children if the update is less than epsilon.
 
double rrg_r_
 Current value of the radius used for the neighbors.
 
unsigned int rrg_k_
 Current value of the number of neighbors used.
 
int variant_ {0}
 Variant used for rejection sampling.
 
double alpha_ {1.}
 Alpha parameter, scaling the rejection sampling tests.
 
bool useInformedSampling_ {false}
 Option to use informed sampling.
 
bool useRejectionSampling_ {false}
 The status of the sample rejection parameter.
 
unsigned int numSampleAttempts_ {100u}
 The number of attempts to make at informed sampling.
 
- 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

Optimal Rapidly-exploring Random Trees Maintaining An Optimal Tree.

Short description
RRT# is an asymptotically-optimal incremental sampling-based motion planning algorithm. It is similar from RRTXstatic but maintains an optimal tree, same as RRTXstatic with a treshold 0.
The parameters are the same as RRTXstatic except for the parameter epsilon.
External documentation
  1. M. Otte & E. Frazzoli - RRTX : Real-Time Motion Planning/Replanning for Environments with Unpredictable Obstacles, Algorithmic Foundations of Robotics XI, Volume 107 of the series Springer Tracts in Advanced Robotics pp 461-478
  2. O. Arslan, P. Tsiotras - The role of vertex consistency in sampling-based algorithms for optimal motion planning, https://arxiv.org/pdf/1204.6453
  3. O. Arslan, P. Tsiotras - Dynamic programming guided exploration for sampling-based motion planning algorithms, 2015 IEEE International Conference on Robotics and Automation (ICRA), pp 4819-4826

Definition at line 131 of file RRTsharp.h.


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