Class RLRT
Defined in File RLRT.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Class Documentation
-
class RLRT : public ompl::base::Planner
Range-Limited Random Tree (Ryan Luna’s Random Tree)
RLRT is a basic tree-based planner without any sophistic heuristics to guide the exploration. It should be used as a baseline for comparison against other tree-based planners. In high-dimensional search spaces it can sometimes perform surprisingly well.
- Associated publication:
R. Luna, M. Moll, J. Badger, and L. E. Kavraki, A Scalable Motion Planner for High-Dimensional Kinematic Systems, Intl. J. of Robotics Research, vol. 39, issue 4, pp. 361-388, Mar. 2020. DOI: 10.1177/0278364919890408[PDF]
Public Functions
-
RLRT(const base::SpaceInformationPtr &si)
-
virtual ~RLRT()
-
virtual void getPlannerData(base::PlannerData &data) const
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)
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()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
-
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.
-
inline void setRange(double distance)
Set the maximum distance between states in the tree.
-
inline double getRange() const
Get the maximum distance between states in the tree.
-
inline bool getKeepLast() const
If true, the planner will not have the range limitation. Instead, if a collision is detected, the last valid state is retained.
-
inline void setKeepLast(bool keepLast)
Set whether the planner will use the range or keep last heuristic. If keepLast = false, motions are limited in distance to range_, otherwise the last valid state is retained when a collision is detected.
-
virtual void setup()
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.
Protected Functions
-
void freeMemory()
Free the memory allocated by this planner.
Protected Attributes
-
base::StateSamplerPtr sampler_
State sampler.
-
double goalBias_ = {0.05}
The fraction of time the goal is picked as the state to expand towards (if such a state is available) */.
-
double range_ = {0.}
The maximum length of a motion to be added to a tree.
-
bool keepLast_ = {false}
If true, the planner will retain the last valid state during local planner. Default is false.
-
class Motion
A motion (tree node) with parent pointer.
Public Functions
-
inline Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
-
~Motion() = default
-
inline Motion(const base::SpaceInformationPtr &si)