RRTConnect.h
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
double distanceBetweenTrees_
Distance between the nearest pair of start tree and goal tree nodes.
Definition: RRTConnect.h:193
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: RRTConnect.h:94
A shared pointer wrapper for ompl::base::StateSampler.
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: RRTConnect.cpp:103
bool getIntermediateStates() const
Return true if the intermediate states generated along motions are to be added to the tree itself...
Definition: RRTConnect.h:77
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition: PlannerTerminationCondition.h:63
bool addIntermediateStates_
Flag indicating whether intermediate states are added to the built tree of motions.
Definition: RRTConnect.h:184
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRTConnect.h:163
std::pair< base::State *, base::State * > connectionPoint_
The pair of states in each tree connected during planning. Used for PlannerData computation.
Definition: RRTConnect.h:190
RRTConnect(const base::SpaceInformationPtr &si, bool addIntermediateStates=false)
Constructor.
Definition: RRTConnect.cpp:42
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: RRTConnect.h:107
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: RRTConnect.h:181
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:56
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
A shared pointer wrapper for ompl::base::SpaceInformation.
the randomly sampled state was reached
Definition: RRTConnect.h:156
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRTConnect.cpp:62
Information attached to growing a tree of motions (used internally)
Definition: RRTConnect.h:141
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: RRTConnect.cpp:377
progress has been made towards the randomly sampled state
Definition: RRTConnect.h:154
std::shared_ptr< NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions.
Definition: RRTConnect.h:138
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition: RRTConnect.cpp:186
void setIntermediateStates(bool addIntermediateStates)
Specify whether the intermediate states generated along motions are to be added to the tree itself...
Definition: RRTConnect.h:84
GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion)
Grow a tree towards a random state.
Definition: RRTConnect.cpp:116