37 #include "ompl/geometric/planners/rrt/LazyRRT.h"
38 #include "ompl/base/goals/GoalSampleableRegion.h"
39 #include "ompl/tools/config/SelfConfig.h"
53 ompl::geometric::LazyRRT::~LazyRRT(
void)
65 nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion*>(si_->getStateSpace()));
76 lastGoalMotion_ = NULL;
83 std::vector<Motion*> motions;
85 for (
unsigned int i = 0 ; i < motions.size() ; ++i)
87 if (motions[i]->state)
88 si_->freeState(motions[i]->state);
103 si_->copyState(motion->
state, st);
104 motion->
valid =
true;
108 if (nn_->size() == 0)
110 OMPL_ERROR(
"%s: There are no valid initial states!", getName().c_str());
115 sampler_ = si_->allocStateSampler();
117 OMPL_INFORM(
"%s: Starting with %u states", getName().c_str(), nn_->size());
120 double distsol = -1.0;
125 bool solutionFound =
false;
127 while (ptc ==
false && !solutionFound)
130 if (goal_s && rng_.uniform01() < goalBias_ && goal_s->
canSample())
133 sampler_->sampleUniform(rstate);
136 Motion *nmotion = nn_->nearest(rmotion);
137 assert(nmotion != rmotion);
141 double d = si_->distance(nmotion->
state, rstate);
142 if (d > maxDistance_)
144 si_->getStateSpace()->interpolate(nmotion->
state, rstate, maxDistance_ / d, xstate);
150 si_->copyState(motion->
state, dstate);
152 nmotion->
children.push_back(motion);
160 solutionFound =
true;
161 lastGoalMotion_ = solution;
165 std::vector<Motion*> mpath;
166 while (solution != NULL)
168 mpath.push_back(solution);
169 solution = solution->parent;
173 for (
int i = mpath.size() - 1 ; i >= 0 && solutionFound; --i)
174 if (!mpath[i]->valid)
176 if (si_->checkMotion(mpath[i]->parent->state, mpath[i]->state))
177 mpath[i]->valid =
true;
180 removeMotion(mpath[i]);
181 solutionFound =
false;
182 lastGoalMotion_ = NULL;
190 for (
int i = mpath.size() - 1 ; i >= 0 ; --i)
191 path->
append(mpath[i]->state);
198 si_->freeState(xstate);
199 si_->freeState(rstate);
202 OMPL_INFORM(
"%s: Created %u states", getName().c_str(), nn_->size());
215 for (
unsigned int i = 0 ; i < motion->
parent->
children.size() ; ++i)
224 for (
unsigned int i = 0 ; i < motion->
children.size() ; ++i)
231 si_->freeState(motion->
state);
237 Planner::getPlannerData(data);
239 std::vector<Motion*> motions;
246 for (
unsigned int i = 0 ; i < motions.size() ; ++i)
248 if (motions[i]->parent == NULL)
254 data.
tagState(motions[i]->state, motions[i]->valid ? 1 : 0);
bool canSample(void) const
Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
The planner failed to find a solution.
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...
unsigned int addGoalVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Abstract definition of goals.
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 append(const base::State *state)
Append state to the end of this path. The memory for state is copied.
bool directed
Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...
virtual void sampleGoal(State *st) const =0
Sample a state in the goal region.
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.
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Invalid start state or no start state specified.
Abstract definition of a goal region that can be sampled.
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
void setRange(double distance)
Set the range the planner is supposed to use.
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
bool tagState(const State *st, int tag)
Set the integer tag associated with the given state. If the given state does not exist in a vertex...
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
The planner found an exact solution.
A class to store the exit status of Planner::solve()
virtual bool addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge=PlannerDataEdge(), Cost weight=Cost(1.0))
Adds a directed edge between the given vertex indexes. An optional edge structure and weight can be s...
unsigned int addStartVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Definition of an abstract state.
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
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.
PlannerSpecs specs_
The specifications of the planner (its capabilities)
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...
Definition of a geometric path.
Motion * parent
The parent motion in the exploration tree.
A boost shared pointer wrapper for ompl::base::Path.
#define OMPL_INFORM(fmt,...)
Log a formatted information string.