37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_RRT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_RRT_
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/datastructures/NearestNeighbors.h"
78 virtual void clear(
void);
117 template<
template<
typename T>
class NN>
120 nn_.reset(
new NN<Motion*>());
123 virtual void setup(
void);
170 boost::shared_ptr< NearestNeighbors<Motion*> >
nn_;
double maxDistance_
The maximum length of a motion to be added to a tree.
base::StateSamplerPtr sampler_
State sampler.
double getGoalBias(void) const
Get the goal bias the planner is using.
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
void freeMemory(void)
Free the memory allocated by this planner.
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Motion * parent
The parent motion in the exploration tree.
A boost shared pointer wrapper for ompl::base::StateSampler.
void setRange(double distance)
Set the range the planner is supposed to use.
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
double getRange(void) const
Get the range the planner is using.
boost::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
RNG rng_
The random number generator.
Base class for a planner.
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
virtual void clear(void)
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
A class to store the exit status of Planner::solve()
Rapidly-exploring Random Trees.
Definition of an abstract state.
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
virtual void setup(void)
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Representation of a motion.
RRT(const base::SpaceInformationPtr &si)
Constructor.
void setNearestNeighbors(void)
Set a different nearest neighbors datastructure.
SpaceInformationPtr si_
The space information for which planning is done.
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
void setGoalBias(double goalBias)
Set the goal bias.
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
Function that can solve the motion planning problem. This function can be called multiple times on th...
base::State * state
The state contained by the motion.