RRT.cpp
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #include "ompl/geometric/planners/rrt/RRT.h"
38 #include <limits>
39 #include "ompl/base/goals/GoalSampleableRegion.h"
40 #include "ompl/tools/config/SelfConfig.h"
41 
42 ompl::geometric::RRT::RRT(const base::SpaceInformationPtr &si, bool addIntermediateStates)
43  : base::Planner(si, addIntermediateStates ? "RRTintermediate" : "RRT")
44 {
46  specs_.directed = true;
47 
48  Planner::declareParam<double>("range", this, &RRT::setRange, &RRT::getRange, "0.:1.:10000.");
49  Planner::declareParam<double>("goal_bias", this, &RRT::setGoalBias, &RRT::getGoalBias, "0.:.05:1.");
50  Planner::declareParam<bool>("intermediate_states", this, &RRT::setIntermediateStates, &RRT::getIntermediateStates,
51  "0,1");
52 
53  addIntermediateStates_ = addIntermediateStates;
54 }
55 
56 ompl::geometric::RRT::~RRT()
57 {
58  freeMemory();
59 }
60 
62 {
63  Planner::clear();
64  sampler_.reset();
65  freeMemory();
66  if (nn_)
67  nn_->clear();
68  lastGoalMotion_ = nullptr;
69 }
70 
72 {
73  Planner::setup();
74  tools::SelfConfig sc(si_, getName());
75  sc.configurePlannerRange(maxDistance_);
76 
77  if (!nn_)
78  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
79  nn_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
80 }
81 
83 {
84  if (nn_)
85  {
86  std::vector<Motion *> motions;
87  nn_->list(motions);
88  for (auto &motion : motions)
89  {
90  if (motion->state != nullptr)
91  si_->freeState(motion->state);
92  delete motion;
93  }
94  }
95 }
96 
98 {
99  checkValidity();
100  base::Goal *goal = pdef_->getGoal().get();
101  auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
102 
103  while (const base::State *st = pis_.nextStart())
104  {
105  auto *motion = new Motion(si_);
106  si_->copyState(motion->state, st);
107  nn_->add(motion);
108  }
109 
110  if (nn_->size() == 0)
111  {
112  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
114  }
115 
116  if (!sampler_)
117  sampler_ = si_->allocStateSampler();
118 
119  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
120 
121  Motion *solution = nullptr;
122  Motion *approxsol = nullptr;
123  double approxdif = std::numeric_limits<double>::infinity();
124  auto *rmotion = new Motion(si_);
125  base::State *rstate = rmotion->state;
126  base::State *xstate = si_->allocState();
127 
128  while (!ptc)
129  {
130  /* sample random state (with goal biasing) */
131  if ((goal_s != nullptr) && rng_.uniform01() < goalBias_ && goal_s->canSample())
132  goal_s->sampleGoal(rstate);
133  else
134  sampler_->sampleUniform(rstate);
135 
136  /* find closest state in the tree */
137  Motion *nmotion = nn_->nearest(rmotion);
138  base::State *dstate = rstate;
139 
140  /* find state to add */
141  double d = si_->distance(nmotion->state, rstate);
142  if (d > maxDistance_)
143  {
144  si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
145  dstate = xstate;
146  }
147 
148  if (si_->checkMotion(nmotion->state, dstate))
149  {
150  if (addIntermediateStates_)
151  {
152  std::vector<base::State *> states;
153  const unsigned int count = si_->getStateSpace()->validSegmentCount(nmotion->state, dstate);
154 
155  if (si_->getMotionStates(nmotion->state, dstate, states, count, true, true))
156  si_->freeState(states[0]);
157 
158  for (std::size_t i = 1; i < states.size(); ++i)
159  {
160  auto *motion = new Motion;
161  motion->state = states[i];
162  motion->parent = nmotion;
163  nn_->add(motion);
164 
165  nmotion = motion;
166  }
167  }
168  else
169  {
170  auto *motion = new Motion(si_);
171  si_->copyState(motion->state, dstate);
172  motion->parent = nmotion;
173  nn_->add(motion);
174 
175  nmotion = motion;
176  }
177 
178  double dist = 0.0;
179  bool sat = goal->isSatisfied(nmotion->state, &dist);
180  if (sat)
181  {
182  approxdif = dist;
183  solution = nmotion;
184  break;
185  }
186  if (dist < approxdif)
187  {
188  approxdif = dist;
189  approxsol = nmotion;
190  }
191  }
192  }
193 
194  bool solved = false;
195  bool approximate = false;
196  if (solution == nullptr)
197  {
198  solution = approxsol;
199  approximate = true;
200  }
201 
202  if (solution != nullptr)
203  {
204  lastGoalMotion_ = solution;
205 
206  /* construct the solution path */
207  std::vector<Motion *> mpath;
208  while (solution != nullptr)
209  {
210  mpath.push_back(solution);
211  solution = solution->parent;
212  }
213 
214  /* set the solution path */
215  auto path(std::make_shared<PathGeometric>(si_));
216  for (int i = mpath.size() - 1; i >= 0; --i)
217  path->append(mpath[i]->state);
218  pdef_->addSolutionPath(path, approximate, approxdif, getName());
219  solved = true;
220  }
221 
222  si_->freeState(xstate);
223  if (rmotion->state != nullptr)
224  si_->freeState(rmotion->state);
225  delete rmotion;
226 
227  OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
228 
229  return {solved, approximate};
230 }
231 
233 {
234  Planner::getPlannerData(data);
235 
236  std::vector<Motion *> motions;
237  if (nn_)
238  nn_->list(motions);
239 
240  if (lastGoalMotion_ != nullptr)
241  data.addGoalVertex(base::PlannerDataVertex(lastGoalMotion_->state));
242 
243  for (auto &motion : motions)
244  {
245  if (motion->parent == nullptr)
246  data.addStartVertex(base::PlannerDataVertex(motion->state));
247  else
248  data.addEdge(base::PlannerDataVertex(motion->parent->state), base::PlannerDataVertex(motion->state));
249  }
250 }
double getRange() const
Get the range the planner is using.
Definition: RRT.h:220
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
Definition: SelfConfig.cpp:225
Definition of an abstract state.
Definition: State.h:113
This class contains methods that automatically configure various parameters for motion planning....
Definition: SelfConfig.h:123
void freeMemory()
Free the memory allocated by this planner.
Definition: RRT.cpp:82
Motion * parent
The parent motion in the exploration tree.
Definition: RRT.h:259
base::State * state
The state contained by the motion.
Definition: RRT.h:256
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRT.cpp:71
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: RRT.cpp:61
void setIntermediateStates(bool addIntermediateStates)
Specify whether the intermediate states generated along motions are to be added to the tree itself.
Definition: RRT.h:204
RRT(const base::SpaceInformationPtr &si, bool addIntermediateStates=false)
Constructor.
Definition: RRT.cpp:42
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:238
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:486
bool directed
Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...
Definition: Planner.h:269
bool addIntermediateStates_
Flag indicating whether intermediate states are added to the built tree of motions.
Definition: RRT.h:285
A class to store the exit status of Planner::solve()
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: RRT.cpp:232
Representation of a motion.
Definition: RRT.h:243
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
Abstract definition of goals.
Definition: Goal.h:126
bool getIntermediateStates() const
Return true if the intermediate states generated along motions are to be added to the tree itself.
Definition: RRT.h:197
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...
void setGoalBias(double goalBias)
Set the goal bias.
Definition: RRT.h:184
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: RRT.h:214
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:259
double getGoalBias() const
Get the goal bias the planner is using.
Definition: RRT.h:190
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition: RRT.cpp:97
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 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 a goal region that can be sampled.
@ INVALID_START
Invalid start state or no start state specified.
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:122