37 #ifndef OMPL_CONTROL_PLANNERS_RRT_RRT_
38 #define OMPL_CONTROL_PLANNERS_RRT_RRT_
40 #include "ompl/control/planners/PlannerIncludes.h"
41 #include "ompl/datastructures/NearestNeighbors.h"
81 virtual void clear(
void);
116 template<
template<
typename T>
class NN>
119 nn_.reset(
new NN<Motion*>());
122 virtual void setup(
void);
180 boost::shared_ptr< NearestNeighbors<Motion*> >
nn_;
DirectedControlSamplerPtr controlSampler_
Control sampler.
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition of an abstract control.
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 base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
Continue solving for some amount of time. Return true if solution was found.
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
base::State * state
The state contained by the motion.
RRT(const SpaceInformationPtr &si)
Constructor.
void setNearestNeighbors(void)
Set a different nearest neighbors datastructure.
bool addIntermediateStates_
Flag indicating whether intermediate states are added to the built tree of motions.
void setIntermediateStates(bool addIntermediateStates)
Specify whether the intermediate states generated along motions are to be added to the tree itself...
double getGoalBias(void) const
Get the goal bias the planner is using.
base::StateSamplerPtr sampler_
State sampler.
Motion * parent
The parent motion in the exploration tree.
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.
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Base class for a planner.
Control * control
The control contained by the motion.
A boost shared pointer wrapper for ompl::control::DirectedControlSampler.
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
A class to store the exit status of Planner::solve()
void freeMemory(void)
Free the memory allocated by this planner.
bool getIntermediateStates(void) const
Return true if the intermediate states generated along motions are to be added to the tree itself...
Definition of an abstract state.
Motion(const SpaceInformation *si)
Constructor that allocates memory for the state and the control.
virtual void clear(void)
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
void setGoalBias(double goalBias)
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Rapidly-exploring Random Tree.
const SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
SpaceInformationPtr si_
The space information for which planning is done.
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 goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
unsigned int steps
The number of steps the control is applied for.
RNG rng_
The random number generator.