RRTConnect.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/RRTConnect.h"
38 #include "ompl/base/goals/GoalSampleableRegion.h"
39 #include "ompl/tools/config/SelfConfig.h"
40 
42  : base::Planner(si, addIntermediateStates ? "RRTConnectIntermediate" : "RRTConnect")
43 {
45  specs_.directed = true;
46 
47  Planner::declareParam<double>("range", this, &RRTConnect::setRange, &RRTConnect::getRange, "0.:1.:10000.");
48  Planner::declareParam<bool>("intermediate_states", this, &RRTConnect::setIntermediateStates,
50 
51  connectionPoint_ = std::make_pair<base::State *, base::State *>(nullptr, nullptr);
52  distanceBetweenTrees_ = std::numeric_limits<double>::infinity();
53  addIntermediateStates_ = addIntermediateStates;
54 }
55 
56 ompl::geometric::RRTConnect::~RRTConnect()
57 {
58  freeMemory();
59 }
60 
62 {
63  Planner::setup();
64  tools::SelfConfig sc(si_, getName());
65  sc.configurePlannerRange(maxDistance_);
66 
67  if (!tStart_)
68  tStart_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
69  if (!tGoal_)
70  tGoal_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
71  tStart_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
72  tGoal_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
73 }
74 
76 {
77  std::vector<Motion *> motions;
78 
79  if (tStart_)
80  {
81  tStart_->list(motions);
82  for (auto &motion : motions)
83  {
84  if (motion->state != nullptr)
85  si_->freeState(motion->state);
86  delete motion;
87  }
88  }
89 
90  if (tGoal_)
91  {
92  tGoal_->list(motions);
93  for (auto &motion : motions)
94  {
95  if (motion->state != nullptr)
96  si_->freeState(motion->state);
97  delete motion;
98  }
99  }
100 }
101 
103 {
104  Planner::clear();
105  sampler_.reset();
106  freeMemory();
107  if (tStart_)
108  tStart_->clear();
109  if (tGoal_)
110  tGoal_->clear();
111  connectionPoint_ = std::make_pair<base::State *, base::State *>(nullptr, nullptr);
112  distanceBetweenTrees_ = std::numeric_limits<double>::infinity();
113 }
114 
116  Motion *rmotion)
117 {
118  /* find closest state in the tree */
119  Motion *nmotion = tree->nearest(rmotion);
120 
121  /* assume we can reach the state we go towards */
122  bool reach = true;
123 
124  /* find state to add */
125  base::State *dstate = rmotion->state;
126  double d = si_->distance(nmotion->state, rmotion->state);
127  if (d > maxDistance_)
128  {
129  si_->getStateSpace()->interpolate(nmotion->state, rmotion->state, maxDistance_ / d, tgi.xstate);
130 
131  /* Check if we have moved at all. Due to some stranger state spaces (e.g., the constrained state spaces),
132  * interpolate can fail and no progress is made. Without this check, the algorithm gets stuck in a loop as it
133  * thinks it is making progress, when none is actually occurring. */
134  if (si_->equalStates(nmotion->state, tgi.xstate))
135  return TRAPPED;
136 
137  dstate = tgi.xstate;
138  reach = false;
139  }
140 
141  bool validMotion = tgi.start ? si_->checkMotion(nmotion->state, dstate) :
142  si_->isValid(dstate) && si_->checkMotion(dstate, nmotion->state);
143 
144  if (!validMotion)
145  return TRAPPED;
146 
147  if (addIntermediateStates_)
148  {
149  const base::State *astate = tgi.start ? nmotion->state : dstate;
150  const base::State *bstate = tgi.start ? dstate : nmotion->state;
151 
152  std::vector<base::State *> states;
153  const unsigned int count = si_->getStateSpace()->validSegmentCount(astate, bstate);
154 
155  if (si_->getMotionStates(astate, bstate, states, count, true, true))
156  si_->freeState(states[0]);
157 
158  for (std::size_t i = 1; i < states.size(); ++i)
159  {
160  Motion *motion = new Motion;
161  motion->state = states[i];
162  motion->parent = nmotion;
163  motion->root = nmotion->root;
164  tree->add(motion);
165 
166  nmotion = motion;
167  }
168 
169  tgi.xmotion = nmotion;
170  }
171  else
172  {
173  Motion *motion = new Motion(si_);
174  si_->copyState(motion->state, dstate);
175  motion->parent = nmotion;
176  motion->root = nmotion->root;
177  tree->add(motion);
178 
179  tgi.xmotion = motion;
180  }
181 
182  return reach ? REACHED : ADVANCED;
183 }
184 
186 {
187  checkValidity();
188  auto *goal = dynamic_cast<base::GoalSampleableRegion *>(pdef_->getGoal().get());
189 
190  if (goal == nullptr)
191  {
192  OMPL_ERROR("%s: Unknown type of goal", getName().c_str());
194  }
195 
196  while (const base::State *st = pis_.nextStart())
197  {
198  auto *motion = new Motion(si_);
199  si_->copyState(motion->state, st);
200  motion->root = motion->state;
201  tStart_->add(motion);
202  }
203 
204  if (tStart_->size() == 0)
205  {
206  OMPL_ERROR("%s: Motion planning start tree could not be initialized!", getName().c_str());
208  }
209 
210  if (!goal->couldSample())
211  {
212  OMPL_ERROR("%s: Insufficient states in sampleable goal region", getName().c_str());
214  }
215 
216  if (!sampler_)
217  sampler_ = si_->allocStateSampler();
218 
219  OMPL_INFORM("%s: Starting planning with %d states already in datastructure", getName().c_str(),
220  (int)(tStart_->size() + tGoal_->size()));
221 
222  TreeGrowingInfo tgi;
223  tgi.xstate = si_->allocState();
224 
225  Motion *approxsol = nullptr;
226  double approxdif = std::numeric_limits<double>::infinity();
227  auto *rmotion = new Motion(si_);
228  base::State *rstate = rmotion->state;
229  bool startTree = true;
230  bool solved = false;
231 
232  while (!ptc)
233  {
234  TreeData &tree = startTree ? tStart_ : tGoal_;
235  tgi.start = startTree;
236  startTree = !startTree;
237  TreeData &otherTree = startTree ? tStart_ : tGoal_;
238 
239  if (tGoal_->size() == 0 || pis_.getSampledGoalsCount() < tGoal_->size() / 2)
240  {
241  const base::State *st = tGoal_->size() == 0 ? pis_.nextGoal(ptc) : pis_.nextGoal();
242  if (st != nullptr)
243  {
244  auto *motion = new Motion(si_);
245  si_->copyState(motion->state, st);
246  motion->root = motion->state;
247  tGoal_->add(motion);
248  }
249 
250  if (tGoal_->size() == 0)
251  {
252  OMPL_ERROR("%s: Unable to sample any valid states for goal tree", getName().c_str());
253  break;
254  }
255  }
256 
257  /* sample random state */
258  sampler_->sampleUniform(rstate);
259 
260  GrowState gs = growTree(tree, tgi, rmotion);
261 
262  if (gs != TRAPPED)
263  {
264  /* remember which motion was just added */
265  Motion *addedMotion = tgi.xmotion;
266 
267  /* attempt to connect trees */
268 
269  /* if reached, it means we used rstate directly, no need top copy again */
270  if (gs != REACHED)
271  si_->copyState(rstate, tgi.xstate);
272 
273  GrowState gsc = ADVANCED;
274  tgi.start = startTree;
275  while (gsc == ADVANCED)
276  gsc = growTree(otherTree, tgi, rmotion);
277 
278  /* update distance between trees */
279  const double newDist = tree->getDistanceFunction()(addedMotion, otherTree->nearest(addedMotion));
280  if (newDist < distanceBetweenTrees_)
281  {
282  distanceBetweenTrees_ = newDist;
283  // OMPL_INFORM("Estimated distance to go: %f", distanceBetweenTrees_);
284  }
285 
286  Motion *startMotion = startTree ? tgi.xmotion : addedMotion;
287  Motion *goalMotion = startTree ? addedMotion : tgi.xmotion;
288 
289  /* if we connected the trees in a valid way (start and goal pair is valid)*/
290  if (gsc == REACHED && goal->isStartGoalPairValid(startMotion->root, goalMotion->root))
291  {
292  // it must be the case that either the start tree or the goal tree has made some progress
293  // so one of the parents is not nullptr. We go one step 'back' to avoid having a duplicate state
294  // on the solution path
295  if (startMotion->parent != nullptr)
296  startMotion = startMotion->parent;
297  else
298  goalMotion = goalMotion->parent;
299 
300  connectionPoint_ = std::make_pair(startMotion->state, goalMotion->state);
301 
302  /* construct the solution path */
303  Motion *solution = startMotion;
304  std::vector<Motion *> mpath1;
305  while (solution != nullptr)
306  {
307  mpath1.push_back(solution);
308  solution = solution->parent;
309  }
310 
311  solution = goalMotion;
312  std::vector<Motion *> mpath2;
313  while (solution != nullptr)
314  {
315  mpath2.push_back(solution);
316  solution = solution->parent;
317  }
318 
319  auto path(std::make_shared<PathGeometric>(si_));
320  path->getStates().reserve(mpath1.size() + mpath2.size());
321  for (int i = mpath1.size() - 1; i >= 0; --i)
322  path->append(mpath1[i]->state);
323  for (auto &i : mpath2)
324  path->append(i->state);
325 
326  pdef_->addSolutionPath(path, false, 0.0, getName());
327  solved = true;
328  break;
329  }
330  else
331  {
332  // We didn't reach the goal, but if we were extending the start
333  // tree, then we can mark/improve the approximate path so far.
334  if (!startTree)
335  {
336  // We were working from the startTree.
337  double dist = 0.0;
338  goal->isSatisfied(tgi.xmotion->state, &dist);
339  if (dist < approxdif)
340  {
341  approxdif = dist;
342  approxsol = tgi.xmotion;
343  }
344  }
345  }
346  }
347  }
348 
349  si_->freeState(tgi.xstate);
350  si_->freeState(rstate);
351  delete rmotion;
352 
353  OMPL_INFORM("%s: Created %u states (%u start + %u goal)", getName().c_str(), tStart_->size() + tGoal_->size(),
354  tStart_->size(), tGoal_->size());
355 
356  if (approxsol && !solved)
357  {
358  /* construct the solution path */
359  std::vector<Motion *> mpath;
360  while (approxsol != nullptr)
361  {
362  mpath.push_back(approxsol);
363  approxsol = approxsol->parent;
364  }
365 
366  auto path(std::make_shared<PathGeometric>(si_));
367  for (int i = mpath.size() - 1; i >= 0; --i)
368  path->append(mpath[i]->state);
369  pdef_->addSolutionPath(path, true, approxdif, getName());
371  }
372 
374 }
375 
377 {
378  Planner::getPlannerData(data);
379 
380  std::vector<Motion *> motions;
381  if (tStart_)
382  tStart_->list(motions);
383 
384  for (auto &motion : motions)
385  {
386  if (motion->parent == nullptr)
387  data.addStartVertex(base::PlannerDataVertex(motion->state, 1));
388  else
389  {
390  data.addEdge(base::PlannerDataVertex(motion->parent->state, 1), base::PlannerDataVertex(motion->state, 1));
391  }
392  }
393 
394  motions.clear();
395  if (tGoal_)
396  tGoal_->list(motions);
397 
398  for (auto &motion : motions)
399  {
400  if (motion->parent == nullptr)
401  data.addGoalVertex(base::PlannerDataVertex(motion->state, 2));
402  else
403  {
404  // The edges in the goal tree are reversed to be consistent with start tree
405  data.addEdge(base::PlannerDataVertex(motion->state, 2), base::PlannerDataVertex(motion->parent->state, 2));
406  }
407  }
408 
409  // Add the edge connecting the two trees
410  data.addEdge(data.vertexIndex(connectionPoint_.first), data.vertexIndex(connectionPoint_.second));
411 
412  // Add some info.
413  data.properties["approx goal distance REAL"] = std::to_string(distanceBetweenTrees_);
414 }
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
double distanceBetweenTrees_
Distance between the nearest pair of start tree and goal tree nodes.
Definition: RRTConnect.h:193
The planner failed to find a solution.
Definition: PlannerStatus.h:62
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: RRTConnect.h:94
GoalType recognizedGoal
The type of goal specification the planner can use.
Definition: Planner.h:197
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...
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: RRTConnect.cpp:102
bool getIntermediateStates() const
Return true if the intermediate states generated along motions are to be added to the tree itself...
Definition: RRTConnect.h:77
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
unsigned int vertexIndex(const PlannerDataVertex &v) const
Return the index for the vertex associated with the given data. INVALID_INDEX is returned if this ver...
bool addIntermediateStates_
Flag indicating whether intermediate states are added to the built tree of motions.
Definition: RRTConnect.h:184
void freeMemory()
Free the memory allocated by this planner.
Definition: RRTConnect.cpp:75
std::pair< base::State *, base::State * > connectionPoint_
The pair of states in each tree connected during planning. Used for PlannerData computation.
Definition: RRTConnect.h:190
RRTConnect(const base::SpaceInformationPtr &si, bool addIntermediateStates=false)
Constructor.
Definition: RRTConnect.cpp:41
bool directed
Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...
Definition: Planner.h:213
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:58
Invalid start state or no start state specified.
Definition: PlannerStatus.h:56
Abstract definition of a goal region that can be sampled.
double getRange() const
Get the range the planner is using.
Definition: RRTConnect.h:100
The goal is of a type that a planner does not recognize.
Definition: PlannerStatus.h:60
Representation of a motion.
Definition: RRTConnect.h:121
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
The planner found an exact solution.
Definition: PlannerStatus.h:66
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
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...
A shared pointer wrapper for ompl::base::SpaceInformation.
GrowState
The state of the tree after an attempt to extend it.
Definition: RRTConnect.h:149
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.
Definition: State.h:49
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:418
The planner found an approximate solution.
Definition: PlannerStatus.h:64
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRTConnect.cpp:61
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
Definition: SelfConfig.cpp:225
This class contains methods that automatically configure various parameters for motion planning...
Definition: SelfConfig.h:59
Information attached to growing a tree of motions (used internally)
Definition: RRTConnect.h:141
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: RRTConnect.cpp:376
std::shared_ptr< NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions.
Definition: RRTConnect.h:138
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: RRTConnect.cpp:185
void setIntermediateStates(bool addIntermediateStates)
Specify whether the intermediate states generated along motions are to be added to the tree itself...
Definition: RRTConnect.h:84
GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion)
Grow a tree towards a random state.
Definition: RRTConnect.cpp:115
std::map< std::string, std::string > properties
Any extra properties (key-value pairs) the planner can set.
Definition: PlannerData.h:410
This bit is set if casting to sampleable goal regions (ompl::base::GoalSampleableRegion) is possible...
Definition: GoalTypes.h:56
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68