All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends
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 <boost/thread/thread.hpp>
41 #include <limits>
42 
43 ompl::geometric::pRRT::pRRT(const base::SpaceInformationPtr &si) : base::Planner(si, "pRRT"),
44  samplerArray_(si)
45 {
47  specs_.multithreaded = true;
48  specs_.directed = true;
49 
50  setThreadCount(2);
51  goalBias_ = 0.05;
52  maxDistance_ = 0.0;
53  lastGoalMotion_ = NULL;
54 
55  Planner::declareParam<double>("range", this, &pRRT::setRange, &pRRT::getRange, "0.:1.:10000.");
56  Planner::declareParam<double>("goal_bias", this, &pRRT::setGoalBias, &pRRT::getGoalBias, "0.:.05:1.");
57  Planner::declareParam<unsigned int>("thread_count", this, &pRRT::setThreadCount, &pRRT::getThreadCount, "1:64");
58 }
59 
60 ompl::geometric::pRRT::~pRRT(void)
61 {
62  freeMemory();
63 }
64 
66 {
67  Planner::setup();
68  tools::SelfConfig sc(si_, getName());
69  sc.configurePlannerRange(maxDistance_);
70 
71  if (!nn_)
72  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion*>(si_->getStateSpace()));
73  nn_->setDistanceFunction(boost::bind(&pRRT::distanceFunction, this, _1, _2));
74 }
75 
77 {
78  Planner::clear();
79  samplerArray_.clear();
80  freeMemory();
81  if (nn_)
82  nn_->clear();
83  lastGoalMotion_ = NULL;
84 }
85 
86 void ompl::geometric::pRRT::freeMemory(void)
87 {
88  if (nn_)
89  {
90  std::vector<Motion*> motions;
91  nn_->list(motions);
92  for (unsigned int i = 0 ; i < motions.size() ; ++i)
93  {
94  if (motions[i]->state)
95  si_->freeState(motions[i]->state);
96  delete motions[i];
97  }
98  }
99 }
100 
101 void ompl::geometric::pRRT::threadSolve(unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol)
102 {
103  checkValidity();
104  base::Goal *goal = pdef_->getGoal().get();
105  base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion*>(goal);
106  RNG rng;
107 
108  Motion *rmotion = new Motion(si_);
109  base::State *rstate = rmotion->state;
110  base::State *xstate = si_->allocState();
111 
112  while (sol->solution == NULL && ptc == false)
113  {
114  /* sample random state (with goal biasing) */
115  if (goal_s && rng.uniform01() < goalBias_ && goal_s->canSample())
116  goal_s->sampleGoal(rstate);
117  else
118  samplerArray_[tid]->sampleUniform(rstate);
119 
120  /* find closest state in the tree */
121  nnLock_.lock();
122  Motion *nmotion = nn_->nearest(rmotion);
123  nnLock_.unlock();
124  base::State *dstate = rstate;
125 
126  /* find state to add */
127  double d = si_->distance(nmotion->state, rstate);
128  if (d > maxDistance_)
129  {
130  si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
131  dstate = xstate;
132  }
133 
134  if (si_->checkMotion(nmotion->state, dstate))
135  {
136  /* create a motion */
137  Motion *motion = new Motion(si_);
138  si_->copyState(motion->state, dstate);
139  motion->parent = nmotion;
140 
141  nnLock_.lock();
142  nn_->add(motion);
143  nnLock_.unlock();
144 
145  double dist = 0.0;
146  bool solved = goal->isSatisfied(motion->state, &dist);
147  if (solved)
148  {
149  sol->lock.lock();
150  sol->approxdif = dist;
151  sol->solution = motion;
152  sol->lock.unlock();
153  break;
154  }
155  if (dist < sol->approxdif)
156  {
157  sol->lock.lock();
158  if (dist < sol->approxdif)
159  {
160  sol->approxdif = dist;
161  sol->approxsol = motion;
162  }
163  sol->lock.unlock();
164  }
165  }
166  }
167 
168  si_->freeState(xstate);
169  if (rmotion->state)
170  si_->freeState(rmotion->state);
171  delete rmotion;
172 }
173 
175 {
176  base::GoalRegion *goal = dynamic_cast<base::GoalRegion*>(pdef_->getGoal().get());
177 
178  if (!goal)
179  {
180  OMPL_ERROR("Goal undefined");
182  }
183 
184  samplerArray_.resize(threadCount_);
185 
186  while (const base::State *st = pis_.nextStart())
187  {
188  Motion *motion = new Motion(si_);
189  si_->copyState(motion->state, st);
190  nn_->add(motion);
191  }
192 
193  if (nn_->size() == 0)
194  {
195  OMPL_ERROR("There are no valid initial states!");
197  }
198 
199  OMPL_INFORM("Starting with %u states", nn_->size());
200 
201  SolutionInfo sol;
202  sol.solution = NULL;
203  sol.approxsol = NULL;
204  sol.approxdif = std::numeric_limits<double>::infinity();
205 
206  std::vector<boost::thread*> th(threadCount_);
207  for (unsigned int i = 0 ; i < threadCount_ ; ++i)
208  th[i] = new boost::thread(boost::bind(&pRRT::threadSolve, this, i, ptc, &sol));
209  for (unsigned int i = 0 ; i < threadCount_ ; ++i)
210  {
211  th[i]->join();
212  delete th[i];
213  }
214 
215  bool solved = false;
216  bool approximate = false;
217  if (sol.solution == NULL)
218  {
219  sol.solution = sol.approxsol;
220  approximate = true;
221  }
222 
223  if (sol.solution != NULL)
224  {
225  lastGoalMotion_ = sol.solution;
226 
227  /* construct the solution path */
228  std::vector<Motion*> mpath;
229  while (sol.solution != NULL)
230  {
231  mpath.push_back(sol.solution);
232  sol.solution = sol.solution->parent;
233  }
234 
235  /* set the solution path */
236  PathGeometric *path = new PathGeometric(si_);
237  for (int i = mpath.size() - 1 ; i >= 0 ; --i)
238  path->append(mpath[i]->state);
239 
240  pdef_->addSolutionPath(base::PathPtr(path), approximate, sol.approxdif);
241  solved = true;
242  }
243 
244  OMPL_INFORM("Created %u states", nn_->size());
245 
246  return base::PlannerStatus(solved, approximate);
247 }
248 
250 {
251  Planner::getPlannerData(data);
252 
253  std::vector<Motion*> motions;
254  if (nn_)
255  nn_->list(motions);
256 
257  if (lastGoalMotion_)
258  data.addGoalVertex(base::PlannerDataVertex(lastGoalMotion_->state));
259 
260  for (unsigned int i = 0 ; i < motions.size() ; ++i)
261  {
262  if (motions[i]->parent == NULL)
263  data.addStartVertex(base::PlannerDataVertex(motions[i]->state));
264  else
265  data.addEdge(base::PlannerDataVertex(motions[i]->parent->state),
266  base::PlannerDataVertex(motions[i]->state));
267  }
268 }
269 
270 void ompl::geometric::pRRT::setThreadCount(unsigned int nthreads)
271 {
272  assert(nthreads > 0);
273  threadCount_ = nthreads;
274 }