Class LazyRRT
Defined in File LazyRRT.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Class Documentation
-
class LazyRRT : public ompl::base::Planner
Lazy RRT.
- Short description
RRT is a tree-based motion planner that uses the following idea: RRT samples a random state qr in the state space, then finds the state qc among the previously seen states that is closest to qr and expands from qc towards qr, until a state qm is reached. qm is then added to the exploration tree. The difference between RRT and LazyRRT is that when moving towards the new state qm, LazyRRT does not check to make sure the path is valid. Instead, it is optimistic and attempts to find a path as soon as possible. Once a path is found, it is checked for collision. If collisions are found, the invalid path segments are removed and the search process is continued.
- External documentation
J. Kuffner and S.M. LaValle, RRT-connect: An efficient approach to single-query path planning, in Proc. 2000 IEEE Intl. Conf. on Robotics and Automation, pp. 995–1001, Apr. 2000. DOI: 10.1109/ROBOT.2000.844730[PDF] [more]
R. Bohlin and L.E. Kavraki, A Randomized Algorithm for Robot Path Planning Based on Lazy Evaluation, in Handbook on Randomized Computing, pp. 221–249, 2001.[PDF]
R. Bohlin and L.E. Kavraki, Path planning using lazy PRM, in Proc. 2000 IEEE Intl. Conf. on Robotics and Automation, pp. 521–528, 2000. DOI: 10.1109/ROBOT.2000.844107[PDF]
Public Functions
-
LazyRRT(const base::SpaceInformationPtr &si)
Constructor.
-
~LazyRRT() 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.
-
inline void setGoalBias(double goalBias)
Set the goal biasing.
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 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.
-
template<template<typename T> class NN>
inline void setNearestNeighbors() Set a different nearest neighbors datastructure.
-
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.
Protected Functions
-
void freeMemory()
Free the memory allocated by this planner.
Protected Attributes
-
base::StateSamplerPtr sampler_
State 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.