Class RRTConnect
Defined in File RRTConnect.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Class Documentation
-
class RRTConnect : public ompl::base::Planner
RRT-Connect (RRTConnect)
- Short description
The basic idea is to grow two RRTs, one from the start and one from the goal, and attempt to connect them.
- 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]
Public Functions
-
RRTConnect(const base::SpaceInformationPtr &si, bool addIntermediateStates = false)
Constructor.
-
~RRTConnect() 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 bool getIntermediateStates() const
Return true if the intermediate states generated along motions are to be added to the tree itself.
-
inline void setIntermediateStates(bool addIntermediateStates)
Specify whether the intermediate states generated along motions are to be added to the tree itself.
-
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 Types
-
enum GrowState
The state of the tree after an attempt to extend it.
Values:
-
enumerator TRAPPED
no progress has been made
-
enumerator ADVANCED
progress has been made towards the randomly sampled state
-
enumerator REACHED
the randomly sampled state was reached
-
enumerator TRAPPED
-
using TreeData = std::shared_ptr<NearestNeighbors<Motion*>>
A nearest-neighbor datastructure representing a tree of motions.
Protected Functions
-
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)
-
GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion)
Grow a tree towards a random state.
Protected Attributes
-
base::StateSamplerPtr sampler_
State sampler.
-
bool startTree_ = {true}
A flag that toggles between expanding the start tree (true) or goal tree (false).
-
double maxDistance_ = {0.}
The maximum length of a motion to be added to a tree.
-
bool addIntermediateStates_
Flag indicating whether intermediate states are added to the built tree of motions.
-
std::pair<base::State*, base::State*> connectionPoint_
The pair of states in each tree connected during planning. Used for PlannerData computation.
-
double distanceBetweenTrees_
Distance between the nearest pair of start tree and goal tree nodes.
-
class Motion
Representation of a motion.
Public Functions
-
Motion() = default
-
inline Motion(const base::SpaceInformationPtr &si)
-
~Motion() = default
-
Motion() = default
-
struct TreeGrowingInfo
Information attached to growing a tree of motions (used internally)