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  goalBias_ = 0.05;
48  maxDistance_ = 0.0;
49  lastGoalMotion_ = nullptr;
50 
51  Planner::declareParam<double>("range", this, &RRT::setRange, &RRT::getRange, "0.:1.:10000.");
52  Planner::declareParam<double>("goal_bias", this, &RRT::setGoalBias, &RRT::getGoalBias, "0.:.05:1.");
53 }
54 
55 ompl::geometric::RRT::~RRT()
56 {
57  freeMemory();
58 }
59 
61 {
62  Planner::clear();
63  sampler_.reset();
64  freeMemory();
65  if (nn_)
66  nn_->clear();
67  lastGoalMotion_ = nullptr;
68 }
69 
71 {
72  Planner::setup();
75 
76  if (!nn_)
77  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
78  nn_->setDistanceFunction([this](const Motion *a, const Motion *b)
79  {
80  return distanceFunction(a, b);
81  });
82 }
83 
85 {
86  if (nn_)
87  {
88  std::vector<Motion *> motions;
89  nn_->list(motions);
90  for (auto &motion : motions)
91  {
92  if (motion->state)
93  si_->freeState(motion->state);
94  delete motion;
95  }
96  }
97 }
98 
100 {
101  checkValidity();
102  base::Goal *goal = pdef_->getGoal().get();
103  base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
104 
105  while (const base::State *st = pis_.nextStart())
106  {
107  auto *motion = new Motion(si_);
108  si_->copyState(motion->state, st);
109  nn_->add(motion);
110  }
111 
112  if (nn_->size() == 0)
113  {
114  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
116  }
117 
118  if (!sampler_)
119  sampler_ = si_->allocStateSampler();
120 
121  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
122 
123  Motion *solution = nullptr;
124  Motion *approxsol = nullptr;
125  double approxdif = std::numeric_limits<double>::infinity();
126  auto *rmotion = new Motion(si_);
127  base::State *rstate = rmotion->state;
128  base::State *xstate = si_->allocState();
129 
130  while (ptc == false)
131  {
132  /* sample random state (with goal biasing) */
133  if (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample())
134  goal_s->sampleGoal(rstate);
135  else
136  sampler_->sampleUniform(rstate);
137 
138  /* find closest state in the tree */
139  Motion *nmotion = nn_->nearest(rmotion);
140  base::State *dstate = rstate;
141 
142  /* find state to add */
143  double d = si_->distance(nmotion->state, rstate);
144  if (d > maxDistance_)
145  {
146  si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
147  dstate = xstate;
148  }
149 
150  if (si_->checkMotion(nmotion->state, dstate))
151  {
152  /* create a motion */
153  auto *motion = new Motion(si_);
154  si_->copyState(motion->state, dstate);
155  motion->parent = nmotion;
156 
157  nn_->add(motion);
158  double dist = 0.0;
159  bool sat = goal->isSatisfied(motion->state, &dist);
160  if (sat)
161  {
162  approxdif = dist;
163  solution = motion;
164  break;
165  }
166  if (dist < approxdif)
167  {
168  approxdif = dist;
169  approxsol = motion;
170  }
171  }
172  }
173 
174  bool solved = false;
175  bool approximate = false;
176  if (solution == nullptr)
177  {
178  solution = approxsol;
179  approximate = true;
180  }
181 
182  if (solution != nullptr)
183  {
184  lastGoalMotion_ = solution;
185 
186  /* construct the solution path */
187  std::vector<Motion *> mpath;
188  while (solution != nullptr)
189  {
190  mpath.push_back(solution);
191  solution = solution->parent;
192  }
193 
194  /* set the solution path */
195  auto path(std::make_shared<PathGeometric>(si_));
196  for (int i = mpath.size() - 1; i >= 0; --i)
197  path->append(mpath[i]->state);
198  pdef_->addSolutionPath(path, approximate, approxdif, getName());
199  solved = true;
200  }
201 
202  si_->freeState(xstate);
203  if (rmotion->state)
204  si_->freeState(rmotion->state);
205  delete rmotion;
206 
207  OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
208 
209  return base::PlannerStatus(solved, approximate);
210 }
211 
213 {
214  Planner::getPlannerData(data);
215 
216  std::vector<Motion *> motions;
217  if (nn_)
218  nn_->list(motions);
219 
220  if (lastGoalMotion_)
222 
223  for (auto &motion : motions)
224  {
225  if (motion->parent == nullptr)
226  data.addStartVertex(base::PlannerDataVertex(motion->state));
227  else
228  data.addEdge(base::PlannerDataVertex(motion->parent->state), base::PlannerDataVertex(motion->state));
229  }
230 }
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: RRT.h:174
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:212
base::StateSamplerPtr sampler_
State sampler.
Definition: RRT.h:164
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:167
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:70
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:60
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:418
bool directed
Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...
Definition: Planner.h:222
virtual void sampleGoal(State *st) const =0
Sample a state in the goal region.
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:177
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
bool canSample() const
Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
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:99
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:84
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRT.h:158
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:180
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:421
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:427
const State * nextStart()
Return the next valid start state or nullptr if no more valid start states are available.
Definition: Planner.cpp:230
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:212
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:415
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:171
void setGoalBias(double goalBias)
Set the goal bias.
Definition: RRT.h:88
base::State * state
The state contained by the motion.
Definition: RRT.h:148
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68