/*This is RRT.cpp */
#include "ompl/geometric/planners/rrt/RRT.h"
#include "ompl/base/goals/GoalSampleableRegion.h"
#include "ompl/tools/config/SelfConfig.h"
#include <limits>
ompl::geometric::RRT::RRT(const base::SpaceInformationPtr &si) : base::Planner(si, "RRT")
{
specs_.approximateSolutions = true;
specs_.directed = true;
goalBias_ = 0.05;
maxDistance_ = 0.0;
lastGoalMotion_ = NULL;
Planner::declareParam<double>("range", this, &RRT::setRange, &RRT::getRange, "0.:1.:10000.");
Planner::declareParam<double>("goal_bias", this, &RRT::setGoalBias, &RRT::getGoalBias, "0.:.05:1.");
}
ompl::geometric::RRT::~RRT()
{
freeMemory();
}
void ompl::geometric::RRT::clear()
{
Planner::clear();
sampler_.reset();
freeMemory();
if (nn_)
nn_->clear();
if (tnn_)
tnn_->clear();
lastGoalMotion_ = NULL;
}
void ompl::geometric::RRT::setup()
{
Planner::setup();
tools::SelfConfig sc(si_, getName());
sc.configurePlannerRange(maxDistance_);
if (!nn_)
nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion*>(si_->getStateSpace()));
nn_->setDistanceFunction(boost::bind(&RRT::distanceFunction, this, _1, _2));
if (!tnn_)
tnn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion*>(si_->getStateSpace()));
tnn_->setDistanceFunction(boost::bind(&RRT::distanceFunction, this, _1, _2));
}
void ompl::geometric::RRT::freeMemory()
{
std::vector<Motion*> motions;
if (nn_)
{
nn_->list(motions);
for (unsigned int i = 0 ; i < motions.size() ; ++i)
{
if (motions[i]->state)
si_->freeState(motions[i]->state);
delete motions[i];
}
}
if (tnn_)
{
tnn_->list(motions);
for (unsigned int i = 0 ; i < motions.size() ; ++i)
{
if (motions[i]->state)
si_->freeState(motions[i]->state);
delete motions[i];
}
}
}
ompl::base::PlannerStatus ompl::geometric::RRT::solve(const base::PlannerTerminationCondition &ptc)
{
checkValidity();
base::Goal *goal = pdef_->getGoal().get();
base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion*>(goal);
while (const base::State *st = pis_.nextStart())
{
Motion *motion = new Motion(si_);
si_->copyState(motion->state, st);
nn_->add(motion);
}
if (nn_->size() == 0)
{
OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
return base::PlannerStatus::INVALID_START;
}
if (!sampler_)
sampler_ = si_->allocStateSampler();
OMPL_INFORM("%s: Starting planning with %u states already in datastructure ", getName().c_str(), nn_->size());
Motion *solution = NULL;
Motion *approxsol = NULL;
double approxdif = std::numeric_limits<double>::infinity();
Motion *rmotion = new Motion(si_);
base::State *rstate = rmotion->state;
base::State *xstate = si_->allocState();
while (ptc == false)
{
/* sample random state (with goal biasing) */
if (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample())
goal_s->sampleGoal(rstate);
else
sampler_->sampleUniform(rstate);
/* find closest state in the tree */
Motion *nmotion = nn_->nearest(rmotion);
base::State *dstate = rstate;
/* find state to add */
double d = si_->distance(nmotion->state, rstate);
if (d > maxDistance_)
{
si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
dstate = xstate;
}
if (si_->checkMotion(nmotion->state, dstate))
{
/* create a motion */
Motion *motion = new Motion(si_);
si_->copyState(motion->state, dstate);
motion->parent = nmotion;
nn_->add(motion);
double dist = 0.0;
bool sat = goal->isSatisfied(motion->state, &dist);
if (sat)
{
approxdif = dist;
solution = motion;
break;
}
if (dist < approxdif)
{
approxdif = dist;
approxsol = motion;
}
}
}
bool solved = false;
bool approximate = false;
if (solution == NULL)
{
solution = approxsol;
approximate = true;
}
if (solution != NULL)
{
lastGoalMotion_ = solution;
/* construct the solution path */
std::vector<Motion*> mpath;
while (solution != NULL)
{
mpath.push_back(solution);
solution = solution->parent;
}
/* set the solution path */
PathGeometric *path = new PathGeometric(si_);
for (int i = mpath.size() - 1 ; i >= 0 ; --i)
path->append(mpath[i]->state);
pdef_->addSolutionPath(base::PathPtr(path), approximate, approxdif, getName());
solved = true;
}
si_->freeState(xstate);
if (rmotion->state)
si_->freeState(rmotion->state);
delete rmotion;
OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
return base::PlannerStatus(solved, approximate);
}
void ompl::geometric::RRT::getPlannerData(base::PlannerData &data) const
{
Planner::getPlannerData(data);
std::vector<Motion*> motions;
if (nn_)
nn_->list(motions);
if (lastGoalMotion_)
data.addGoalVertex(base::PlannerDataVertex(lastGoalMotion_->state));
for (unsigned int i = 0 ; i < motions.size() ; ++i)
{
if (motions[i]->parent == NULL)
data.addStartVertex(base::PlannerDataVertex(motions[i]->state));
else
data.addEdge(base::PlannerDataVertex(motions[i]->parent->state),
base::PlannerDataVertex(motions[i]->state));
}
}
/* This is RRT.h */
#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_RRT_
#define OMPL_GEOMETRIC_PLANNERS_RRT_RRT_
#include "ompl/geometric/planners/PlannerIncludes.h"
#include "ompl/datastructures/NearestNeighbors.h"
namespace ompl
{
namespace geometric
{
/**
@anchor gRRT
@par Short description
RRT is a tree-based motion planner that uses the following
idea: RRT samples a random state @b qr in the state space,
then finds the state @b qc among the previously seen states
that is closest to @b qr and expands from @b qc towards @b
qr, until a state @b qm is reached. @b qm is then added to
the exploration tree.
@par External documentation
J. Kuffner and S.M. LaValle, RRT-connect: An efficient approach to single-query path planning, in <em>Proc. 2000 IEEE Intl. Conf. on Robotics and Automation</em>, pp. 995–1001, Apr. 2000. DOI: [10.1109/ROBOT.2000.844730](
http://dx.doi.org/10.1109/ROBOT.2000.844730)<br>
*/
/** \brief Rapidly-exploring Random Trees */
class RRT : public base::Planner
{
public:
/** \brief Constructor */
RRT(const base::SpaceInformationPtr &si);
virtual ~RRT();
virtual void getPlannerData(base::PlannerData &data) const;
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc);
virtual void clear();
/** \brief Set the goal bias
In the process of randomly selecting states in
the state space to attempt to go towards, the
algorithm may in fact choose the actual goal state, if
it knows it, with some probability. This probability
is a real number between 0.0 and 1.0; its value should
usually be around 0.05 and should not be too large. It
is probably a good idea to use the default value. */
void setGoalBias(double goalBias)
{
goalBias_ = goalBias;
}
/** \brief Get the goal bias the planner is using */
double getGoalBias() const
{
return goalBias_;
}
/** \brief Set the range the planner is supposed to use.
This parameter greatly influences the runtime of the
algorithm. It represents the maximum length of a
motion to be added in the tree of motions. */
void setRange(double distance)
{
maxDistance_ = distance;
}
/** \brief Get the range the planner is using */
double getRange() const
{
return maxDistance_;
}
/** \brief Set a different nearest neighbors datastructure */
template<template<typename T> class NN>
void setNearestNeighbors()
{
nn_.reset(new NN<Motion*>());
tnn_.reset(new NN<Motion*>());
}
virtual void setup();
protected:
/** \brief Representation of a motion
This only contains pointers to parent motions as we
only need to go backwards in the tree. */
class Motion
{
public:
Motion() : state(NULL), parent(NULL)
{
}
/** \brief Constructor that allocates memory for the state */
Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parent(NULL)
{
}
~Motion()
{
}
/** \brief The state contained by the motion */
base::State *state;
/** \brief The parent motion in the exploration tree */
Motion *parent;
};
/** \brief Free the memory allocated by this planner */
void freeMemory();
/** \brief Compute distance between motions (actually distance between contained states) */
double distanceFunction(const Motion *a, const Motion *b) const
{
return si_->distance(a->state, b->state);
}
/** \brief State sampler */
base::StateSamplerPtr sampler_;
/** \brief A nearest-neighbors datastructure containing the tree of motions */
typedef boost::shared_ptr< NearestNeighbors<Motion*> > TreeData;
TreeData nn_;
TreeData tnn_;
/** \brief The fraction of time the goal is picked as the state to expand towards (if such a state is available) */
double goalBias_;
/** \brief The maximum length of a motion to be added to a tree */
double maxDistance_;
/** \brief The random number generator */
RNG rng_;
/** \brief The most recent goal motion. Used for PlannerData computation */
Motion *lastGoalMotion_;
};
}
}
#endif