37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_pRRT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_pRRT_
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/base/StateSamplerArray.h"
42 #include "ompl/datastructures/NearestNeighbors.h"
43 #include <boost/thread/mutex.hpp>
79 virtual void clear(
void);
108 maxDistance_ = distance;
120 unsigned int getThreadCount(
void)
const
126 template<
template<
typename T>
class NN>
129 nn_.reset(
new NN<Motion*>());
132 virtual void setup(
void);
140 Motion(
void) : state(NULL), parent(NULL)
166 void freeMemory(
void);
168 double distanceFunction(
const Motion* a,
const Motion* b)
const
170 return si_->distance(a->state, b->state);
174 boost::shared_ptr< NearestNeighbors<Motion*> > nn_;
175 boost::mutex nnLock_;
177 unsigned int threadCount_;
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
void setGoalBias(double goalBias)
Set the goal bias.
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
virtual void clear(void)
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
void setThreadCount(unsigned int nthreads)
Set the number of threads the planner should use. Default is 2.
Base class for a planner.
void setRange(double distance)
Set the range the planner is supposed to use.
A class to store the exit status of Planner::solve()
Definition of an abstract state.
virtual void setup(void)
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
void setNearestNeighbors(void)
Set a different nearest neighbors datastructure.
double getRange(void) const
Get the range the planner is using.
SpaceInformationPtr si_
The space information for which planning is done.
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...
double getGoalBias(void) const
Get the goal bias the planner is using.