Class RRTXstatic
Defined in File RRTXstatic.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Derived Type
public ompl::geometric::RRTsharp
(Class RRTsharp)
Class Documentation
-
class RRTXstatic : public ompl::base::Planner
Optimal Rapidly-exploring Random Trees Maintaining A Pseudo Optimal Tree.
The queue is implemented only using a scalar (cost + heuristic) as a key for ordering. With random samples, the set {cost + heuristic = constant} should be of measure 0, so a more complex key is not needed.
- Short description
RRTXstatic is an asymptotically-optimal incremental sampling-based motion planning algorithm. It differs from the RRT*
algorithm by maintaining a pseudo-optimal tree.
When adding a new motion, any rewiring improving the cost by more than epsilon is done. While each iteration is more costly than one of
RRT*, the convergence is faster thanks to the pseudo-optimal tree.
Parameters are:
range: maximum size allowed for an edge
goal_bias: probability of sampling the goal region
rewire_factor: multiplicative factor for the size of the neighbor ball (or the number of neighbors)
use_k_nearest: use kNN instead of rNN
informed_sampling: direct sampling in the relevant region defined by the heuristic
sample_rejection: rejects sampled out of the relevant region defined by the heuristic
number_sampling_attempts: number of sampling attempts when using rejection sampling or informed sampling
epsilon: the minimum threshold for cost improvement required to rewire the tree
update_children: Force propagation of cost to children even if it is less than the threshold epsilon. It improves convergence with minimal extra computation.
rejection_variant: Variants of the rejection of samples, 0: no rejection, 1-3: variants from reference (3)
rejection_variant_alpha: Parameter alpha used for the rejection sampling, it allows to scale the non-admissible heuristic, see reference (3)
- Disclaimer
Only the static part of the RRTX algorithm is implemented. Dynamical obstacles and updates of the robot position are not available in this implementation.
- External documentation
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
O. Arslan, P. Tsiotras - The role of vertex consistency in sampling-based algorithms for optimal motion planning, https://arxiv.org/pdf/1204.6453
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
Subclassed by ompl::geometric::RRTsharp
Public Functions
-
RRTXstatic(const base::SpaceInformationPtr &si)
-
~RRTXstatic() override
-
virtual 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).
-
virtual 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.
-
virtual void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
-
virtual 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.
-
inline void setGoalBias(double goalBias)
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.
-
inline 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.
-
inline 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)
-
inline bool getSampleRejection() const
Get the state of the sample rejection option.
-
inline void setNumSamplingAttempts(unsigned int numAttempts)
Set the number of attempts to make while performing rejection or informed sampling.
-
inline unsigned int getNumSamplingAttempts() const
Get the number of attempts to make while performing rejection or informed sampling.
-
inline virtual void setEpsilon(double epsilon)
Set the threshold epsilon.
While propagating information, the propagation is done only if the cost enhancement is at least epsilon
-
inline double getEpsilon() const
Get the threshold epsilon the planner is using.
-
inline void setRange(double distance)
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.
-
inline double getRange() const
Get the range the planner is using.
-
inline 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*)
-
inline 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>
inline void setNearestNeighbors() Set a different nearest neighbors datastructure.
-
inline void setKNearest(bool useKNearest)
Use a k-nearest search for rewiring instead of a r-disc search.
-
inline bool getKNearest() const
Get the state of using a k-nearest search for rewiring.
-
inline void setUpdateChildren(bool val)
Set whether or not to always propagate cost updates to children.
-
inline bool getUpdateChildren() const
True if the cost is always propagate to children.
-
inline void setVariant(const int variant)
Set variant used for rejection sampling.
-
inline int getVariant() const
Get variant used for rejection sampling.
-
inline void setAlpha(const double a)
Set the value alpha used for rejection sampling.
-
inline double getAlpha() const
Get the value alpha used for rejection sampling.
-
inline unsigned int numIterations() const
Protected Functions
-
void allocSampler()
Create the samplers.
-
void freeMemory()
Free the memory allocated by this planner.
-
inline double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
-
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.
-
inline std::string numIterationsProperty() const
-
inline std::string bestCostProperty() const
-
inline std::string numMotionsProperty() const
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.
-
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.
-
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*, MotionCompare> q_
Queue to order the nodes to update.
-
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.
-
class Motion
Representation of a motion (node of the tree)
Public Functions
-
inline Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state. This constructor automatically allocates memory for state, cost, and incCost.
-
~Motion() = default
Public Members
-
std::vector<std::pair<Motion*, bool>> nbh
The set of neighbors of this motion with a boolean indicating if the feasibility of edge as been tested.
-
BinaryHeap<Motion*, MotionCompare>::Element *handle
Handle to identify the motion in the queue.
-
inline Motion(const base::SpaceInformationPtr &si)
-
struct MotionCompare
Defines the operator to compare motions.
Public Functions
-
inline MotionCompare(base::OptimizationObjectivePtr opt, base::ProblemDefinitionPtr pdef)
Constructor.
-
inline base::Cost costPlusHeuristic(const Motion *m) const
Combines the current cost of a motion and the heuritic to the goal.
Public Members
-
base::OptimizationObjectivePtr opt_
Pointer to the Optimization Objective.
-
base::ProblemDefinitionPtr pdef_
Pointer to the Problem Definition.
-
inline MotionCompare(base::OptimizationObjectivePtr opt, base::ProblemDefinitionPtr pdef)