pRRT.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/pRRT.h"
38 #include "ompl/base/goals/GoalSampleableRegion.h"
39 #include "ompl/tools/config/SelfConfig.h"
40 #include <limits>
41 
42 ompl::geometric::pRRT::pRRT(const base::SpaceInformationPtr &si) : base::Planner(si, "pRRT"), samplerArray_(si)
43 {
45  specs_.multithreaded = true;
46  specs_.directed = true;
47 
48  setThreadCount(2);
49  goalBias_ = 0.05;
50  maxDistance_ = 0.0;
51  lastGoalMotion_ = nullptr;
52 
53  Planner::declareParam<double>("range", this, &pRRT::setRange, &pRRT::getRange, "0.:1.:10000.");
54  Planner::declareParam<double>("goal_bias", this, &pRRT::setGoalBias, &pRRT::getGoalBias, "0.:.05:1.");
55  Planner::declareParam<unsigned int>("thread_count", this, &pRRT::setThreadCount, &pRRT::getThreadCount, "1:64");
56 }
57 
58 ompl::geometric::pRRT::~pRRT()
59 {
60  freeMemory();
61 }
62 
64 {
65  Planner::setup();
68 
69  if (!nn_)
70  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
71  nn_->setDistanceFunction([this](const Motion *a, const Motion *b)
72  {
73  return distanceFunction(a, b);
74  });
75 }
76 
78 {
79  Planner::clear();
80  samplerArray_.clear();
81  freeMemory();
82  if (nn_)
83  nn_->clear();
84  lastGoalMotion_ = nullptr;
85 }
86 
87 void ompl::geometric::pRRT::freeMemory()
88 {
89  if (nn_)
90  {
91  std::vector<Motion *> motions;
92  nn_->list(motions);
93  for (auto &motion : motions)
94  {
95  if (motion->state)
96  si_->freeState(motion->state);
97  delete motion;
98  }
99  }
100 }
101 
102 void ompl::geometric::pRRT::threadSolve(unsigned int tid, const base::PlannerTerminationCondition &ptc,
103  SolutionInfo *sol)
104 {
105  base::Goal *goal = pdef_->getGoal().get();
106  base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
107  RNG rng;
108 
109  auto *rmotion = new Motion(si_);
110  base::State *rstate = rmotion->state;
111  base::State *xstate = si_->allocState();
112 
113  while (sol->solution == nullptr && ptc == false)
114  {
115  /* sample random state (with goal biasing) */
116  if (goal_s && rng.uniform01() < goalBias_ && goal_s->canSample())
117  goal_s->sampleGoal(rstate);
118  else
119  samplerArray_[tid]->sampleUniform(rstate);
120 
121  /* find closest state in the tree */
122  nnLock_.lock();
123  Motion *nmotion = nn_->nearest(rmotion);
124  nnLock_.unlock();
125  base::State *dstate = rstate;
126 
127  /* find state to add */
128  double d = si_->distance(nmotion->state, rstate);
129  if (d > maxDistance_)
130  {
131  si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
132  dstate = xstate;
133  }
134 
135  if (si_->checkMotion(nmotion->state, dstate))
136  {
137  /* create a motion */
138  auto *motion = new Motion(si_);
139  si_->copyState(motion->state, dstate);
140  motion->parent = nmotion;
141 
142  nnLock_.lock();
143  nn_->add(motion);
144  nnLock_.unlock();
145 
146  double dist = 0.0;
147  bool solved = goal->isSatisfied(motion->state, &dist);
148  if (solved)
149  {
150  sol->lock.lock();
151  sol->approxdif = dist;
152  sol->solution = motion;
153  sol->lock.unlock();
154  break;
155  }
156  if (dist < sol->approxdif)
157  {
158  sol->lock.lock();
159  if (dist < sol->approxdif)
160  {
161  sol->approxdif = dist;
162  sol->approxsol = motion;
163  }
164  sol->lock.unlock();
165  }
166  }
167  }
168 
169  si_->freeState(xstate);
170  if (rmotion->state)
171  si_->freeState(rmotion->state);
172  delete rmotion;
173 }
174 
176 {
177  checkValidity();
178 
179  base::GoalRegion *goal = dynamic_cast<base::GoalRegion *>(pdef_->getGoal().get());
180 
181  if (!goal)
182  {
183  OMPL_ERROR("%s: Unknow type of goal", getName().c_str());
185  }
186 
187  samplerArray_.resize(threadCount_);
188 
189  while (const base::State *st = pis_.nextStart())
190  {
191  auto *motion = new Motion(si_);
192  si_->copyState(motion->state, st);
193  nn_->add(motion);
194  }
195 
196  if (nn_->size() == 0)
197  {
198  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
200  }
201 
202  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
203 
204  SolutionInfo sol;
205  sol.solution = nullptr;
206  sol.approxsol = nullptr;
207  sol.approxdif = std::numeric_limits<double>::infinity();
208 
209  std::vector<std::thread *> th(threadCount_);
210  for (unsigned int i = 0; i < threadCount_; ++i)
211  th[i] = new std::thread([this, i, &ptc, &sol]
212  {
213  return threadSolve(i, ptc, &sol);
214  });
215  for (unsigned int i = 0; i < threadCount_; ++i)
216  {
217  th[i]->join();
218  delete th[i];
219  }
220 
221  bool solved = false;
222  bool approximate = false;
223  if (sol.solution == nullptr)
224  {
225  sol.solution = sol.approxsol;
226  approximate = true;
227  }
228 
229  if (sol.solution != nullptr)
230  {
231  lastGoalMotion_ = sol.solution;
232 
233  /* construct the solution path */
234  std::vector<Motion *> mpath;
235  while (sol.solution != nullptr)
236  {
237  mpath.push_back(sol.solution);
238  sol.solution = sol.solution->parent;
239  }
240 
241  /* set the solution path */
242  auto path(std::make_shared<PathGeometric>(si_));
243  for (int i = mpath.size() - 1; i >= 0; --i)
244  path->append(mpath[i]->state);
245 
246  pdef_->addSolutionPath(path, approximate, sol.approxdif, getName());
247  solved = true;
248  }
249 
250  OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
251 
252  return base::PlannerStatus(solved, approximate);
253 }
254 
256 {
257  Planner::getPlannerData(data);
258 
259  std::vector<Motion *> motions;
260  if (nn_)
261  nn_->list(motions);
262 
263  if (lastGoalMotion_)
265 
266  for (auto &motion : motions)
267  {
268  if (motion->parent == nullptr)
269  data.addStartVertex(base::PlannerDataVertex(motion->state));
270  else
271  data.addEdge(base::PlannerDataVertex(motion->parent->state), base::PlannerDataVertex(motion->state));
272  }
273 }
274 
275 void ompl::geometric::pRRT::setThreadCount(unsigned int nthreads)
276 {
277  assert(nthreads > 0);
278  threadCount_ = nthreads;
279 }
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:212
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
void freeMemory()
Free the memory allocated by this planner.
Definition: LBTRRT.cpp:102
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: LBTRRT.h:249
void setGoalBias(double goalBias)
Set the goal bias.
Definition: pRRT.h:90
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
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: LBTRRT.h:288
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: pRRT.cpp:77
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:418
bool multithreaded
Flag indicating whether multiple threads are used in the computation of the planner.
Definition: Planner.h:209
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 goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition: LBTRRT.h:285
void setThreadCount(unsigned int nthreads)
Set the number of threads the planner should use. Default is 2.
Definition: pRRT.cpp:275
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.
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: pRRT.cpp:63
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:58
The goal is of a type that a planner does not recognize.
Definition: PlannerStatus.h:60
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: LBTRRT.h:297
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: LBTRRT.h:275
bool canSample() const
Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: pRRT.h:106
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: pRRT.cpp:175
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...
double getRange() const
Get the range the planner is using.
Definition: pRRT.h:112
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
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
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: pRRT.cpp:255
double getGoalBias() const
Get the goal bias the planner is using.
Definition: pRRT.h:96
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
Definition of a goal region.
Definition: GoalRegion.h:47
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:415
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68