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 "ompl/base/goals/GoalSampleableRegion.h"
39 #include "ompl/tools/config/SelfConfig.h"
40 #include <limits>
41 
42 ompl::geometric::RRT::RRT(const base::SpaceInformationPtr &si) : base::Planner(si, "RRT")
43 {
45  specs_.directed = true;
46 
47  Planner::declareParam<double>("range", this, &RRT::setRange, &RRT::getRange, "0.:1.:10000.");
48  Planner::declareParam<double>("goal_bias", this, &RRT::setGoalBias, &RRT::getGoalBias, "0.:.05:1.");
49 }
50 
51 ompl::geometric::RRT::~RRT()
52 {
53  freeMemory();
54 }
55 
57 {
58  Planner::clear();
59  sampler_.reset();
60  freeMemory();
61  if (nn_)
62  nn_->clear();
63  lastGoalMotion_ = nullptr;
64 }
65 
67 {
68  Planner::setup();
71 
72  if (!nn_)
73  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
74  nn_->setDistanceFunction([this](const Motion *a, const Motion *b)
75  {
76  return distanceFunction(a, b);
77  });
78 }
79 
81 {
82  if (nn_)
83  {
84  std::vector<Motion *> motions;
85  nn_->list(motions);
86  for (auto &motion : motions)
87  {
88  if (motion->state != nullptr)
89  si_->freeState(motion->state);
90  delete motion;
91  }
92  }
93 }
94 
96 {
97  checkValidity();
98  base::Goal *goal = pdef_->getGoal().get();
99  auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
100 
101  while (const base::State *st = pis_.nextStart())
102  {
103  auto *motion = new Motion(si_);
104  si_->copyState(motion->state, st);
105  nn_->add(motion);
106  }
107 
108  if (nn_->size() == 0)
109  {
110  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
112  }
113 
114  if (!sampler_)
115  sampler_ = si_->allocStateSampler();
116 
117  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
118 
119  Motion *solution = nullptr;
120  Motion *approxsol = nullptr;
121  double approxdif = std::numeric_limits<double>::infinity();
122  auto *rmotion = new Motion(si_);
123  base::State *rstate = rmotion->state;
124  base::State *xstate = si_->allocState();
125 
126  while (!ptc)
127  {
128  /* sample random state (with goal biasing) */
129  if ((goal_s != nullptr) && rng_.uniform01() < goalBias_ && goal_s->canSample())
130  goal_s->sampleGoal(rstate);
131  else
132  sampler_->sampleUniform(rstate);
133 
134  /* find closest state in the tree */
135  Motion *nmotion = nn_->nearest(rmotion);
136  base::State *dstate = rstate;
137 
138  /* find state to add */
139  double d = si_->distance(nmotion->state, rstate);
140  if (d > maxDistance_)
141  {
142  si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
143  dstate = xstate;
144  }
145 
146  if (si_->checkMotion(nmotion->state, dstate))
147  {
148  /* create a motion */
149  auto *motion = new Motion(si_);
150  si_->copyState(motion->state, dstate);
151  motion->parent = nmotion;
152 
153  nn_->add(motion);
154  double dist = 0.0;
155  bool sat = goal->isSatisfied(motion->state, &dist);
156  if (sat)
157  {
158  approxdif = dist;
159  solution = motion;
160  break;
161  }
162  if (dist < approxdif)
163  {
164  approxdif = dist;
165  approxsol = motion;
166  }
167  }
168  }
169 
170  bool solved = false;
171  bool approximate = false;
172  if (solution == nullptr)
173  {
174  solution = approxsol;
175  approximate = true;
176  }
177 
178  if (solution != nullptr)
179  {
180  lastGoalMotion_ = solution;
181 
182  /* construct the solution path */
183  std::vector<Motion *> mpath;
184  while (solution != nullptr)
185  {
186  mpath.push_back(solution);
187  solution = solution->parent;
188  }
189 
190  /* set the solution path */
191  auto path(std::make_shared<PathGeometric>(si_));
192  for (int i = mpath.size() - 1; i >= 0; --i)
193  path->append(mpath[i]->state);
194  pdef_->addSolutionPath(path, approximate, approxdif, getName());
195  solved = true;
196  }
197 
198  si_->freeState(xstate);
199  if (rmotion->state != nullptr)
200  si_->freeState(rmotion->state);
201  delete rmotion;
202 
203  OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
204 
205  return base::PlannerStatus(solved, approximate);
206 }
207 
209 {
210  Planner::getPlannerData(data);
211 
212  std::vector<Motion *> motions;
213  if (nn_)
214  nn_->list(motions);
215 
216  if (lastGoalMotion_ != nullptr)
218 
219  for (auto &motion : motions)
220  {
221  if (motion->parent == nullptr)
222  data.addStartVertex(base::PlannerDataVertex(motion->state));
223  else
224  data.addEdge(base::PlannerDataVertex(motion->parent->state), base::PlannerDataVertex(motion->state));
225  }
226 }
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: RRT.h:172
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:203
base::StateSamplerPtr sampler_
State sampler.
Definition: RRT.h:162
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: RRT.h:165
double getGoalBias() const
Get the goal bias the planner is using.
Definition: RRT.h:94
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: RRT.h:104
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.
Definition: Goal.h:62
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRT.cpp:66
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: RRT.cpp:56
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:409
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
double uniform01()
Generate a random real between 0 and 1.
Definition: RandomNumbers.h:68
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.
RNG rng_
The random number generator.
Definition: RRT.h:175
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
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:95
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.
void freeMemory()
Free the memory allocated by this planner.
Definition: RRT.cpp:80
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRT.h:156
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
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: RRT.h:178
virtual void checkValidity()
Check to see if the planner is in a working state (setup has been called, a goal was set...
Definition: Planner.cpp:101
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
PlannerInputStates pis_
Utility class to extract valid input states.
Definition: Planner.h:412
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:418
const State * nextStart()
Return the next valid start state or nullptr if no more valid start states are available.
Definition: Planner.cpp:227
const std::string & getName() const
Get the name of the planner.
Definition: Planner.cpp:56
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
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:208
double getRange() const
Get the range the planner is using.
Definition: RRT.h:110
Representation of a motion.
Definition: RRT.h:133
RRT(const base::SpaceInformationPtr &si)
Constructor.
Definition: RRT.cpp:42
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:406
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition: RRT.h:169
void setGoalBias(double goalBias)
Set the goal bias.
Definition: RRT.h:88
base::State * state
The state contained by the motion.
Definition: RRT.h:146
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68