38 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_LAZY_RRT_
39 #define OMPL_GEOMETRIC_PLANNERS_RRT_LAZY_RRT_
41 #include "ompl/geometric/planners/PlannerIncludes.h"
42 #include "ompl/datastructures/NearestNeighbors.h"
91 virtual void clear(
void);
130 template<
template<
typename T>
class NN>
133 nn_.reset(
new NN<Motion*>());
136 virtual void setup(
void);
187 boost::shared_ptr< NearestNeighbors<Motion*> >
nn_;
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
void setGoalBias(double goalBias)
Set the goal biasing.
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...
A boost shared pointer wrapper for ompl::base::StateSampler.
boost::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
void freeMemory(void)
Free the memory allocated by this planner.
void removeMotion(Motion *motion)
Remove a motion from the tree datastructure.
double getGoalBias(void) const
Get the goal bias the planner is using.
std::vector< Motion * > children
The set of motions that descend from this one.
double maxDistance_
The maximum length of a motion to be added to a tree.
Representation of a motion.
void setNearestNeighbors(void)
Set a different nearest neighbors datastructure.
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
void setRange(double distance)
Set the range the planner is supposed to use.
Base class for a planner.
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
A class to store the exit status of Planner::solve()
RNG rng_
The random number generator.
Definition of an abstract state.
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
base::State * state
The state contained by the motion.
double getRange(void) const
Get the range the planner is using.
bool valid
Flag indicating whether this motion has been validated.
virtual void setup(void)
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
LazyRRT(const base::SpaceInformationPtr &si)
Constructor.
virtual void clear(void)
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
SpaceInformationPtr si_
The space information for which planning is done.
Motion * parent
The parent motion in the exploration tree.
base::StateSamplerPtr sampler_
State sampler.
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.