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()
61 {
62  freeMemory();
63 }
64 
66 {
67  Planner::setup();
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()
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  base::Goal *goal = pdef_->getGoal().get();
104  base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion*>(goal);
105  RNG rng;
106 
107  Motion *rmotion = new Motion(si_);
108  base::State *rstate = rmotion->state;
109  base::State *xstate = si_->allocState();
110 
111  while (sol->solution == NULL && ptc == false)
112  {
113  /* sample random state (with goal biasing) */
114  if (goal_s && rng.uniform01() < goalBias_ && goal_s->canSample())
115  goal_s->sampleGoal(rstate);
116  else
117  samplerArray_[tid]->sampleUniform(rstate);
118 
119  /* find closest state in the tree */
120  nnLock_.lock();
121  Motion *nmotion = nn_->nearest(rmotion);
122  nnLock_.unlock();
123  base::State *dstate = rstate;
124 
125  /* find state to add */
126  double d = si_->distance(nmotion->state, rstate);
127  if (d > maxDistance_)
128  {
129  si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
130  dstate = xstate;
131  }
132 
133  if (si_->checkMotion(nmotion->state, dstate))
134  {
135  /* create a motion */
136  Motion *motion = new Motion(si_);
137  si_->copyState(motion->state, dstate);
138  motion->parent = nmotion;
139 
140  nnLock_.lock();
141  nn_->add(motion);
142  nnLock_.unlock();
143 
144  double dist = 0.0;
145  bool solved = goal->isSatisfied(motion->state, &dist);
146  if (solved)
147  {
148  sol->lock.lock();
149  sol->approxdif = dist;
150  sol->solution = motion;
151  sol->lock.unlock();
152  break;
153  }
154  if (dist < sol->approxdif)
155  {
156  sol->lock.lock();
157  if (dist < sol->approxdif)
158  {
159  sol->approxdif = dist;
160  sol->approxsol = motion;
161  }
162  sol->lock.unlock();
163  }
164  }
165  }
166 
167  si_->freeState(xstate);
168  if (rmotion->state)
169  si_->freeState(rmotion->state);
170  delete rmotion;
171 }
172 
174 {
175  checkValidity();
176 
177  base::GoalRegion *goal = dynamic_cast<base::GoalRegion*>(pdef_->getGoal().get());
178 
179  if (!goal)
180  {
181  OMPL_ERROR("%s: Unknow type of goal", getName().c_str());
183  }
184 
185  samplerArray_.resize(threadCount_);
186 
187  while (const base::State *st = pis_.nextStart())
188  {
189  Motion *motion = new Motion(si_);
190  si_->copyState(motion->state, st);
191  nn_->add(motion);
192  }
193 
194  if (nn_->size() == 0)
195  {
196  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
198  }
199 
200  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
201 
202  SolutionInfo sol;
203  sol.solution = NULL;
204  sol.approxsol = NULL;
205  sol.approxdif = std::numeric_limits<double>::infinity();
206 
207  std::vector<boost::thread*> th(threadCount_);
208  for (unsigned int i = 0 ; i < threadCount_ ; ++i)
209  th[i] = new boost::thread(boost::bind(&pRRT::threadSolve, this, i, ptc, &sol));
210  for (unsigned int i = 0 ; i < threadCount_ ; ++i)
211  {
212  th[i]->join();
213  delete th[i];
214  }
215 
216  bool solved = false;
217  bool approximate = false;
218  if (sol.solution == NULL)
219  {
220  sol.solution = sol.approxsol;
221  approximate = true;
222  }
223 
224  if (sol.solution != NULL)
225  {
226  lastGoalMotion_ = sol.solution;
227 
228  /* construct the solution path */
229  std::vector<Motion*> mpath;
230  while (sol.solution != NULL)
231  {
232  mpath.push_back(sol.solution);
233  sol.solution = sol.solution->parent;
234  }
235 
236  /* set the solution path */
237  PathGeometric *path = new PathGeometric(si_);
238  for (int i = mpath.size() - 1 ; i >= 0 ; --i)
239  path->append(mpath[i]->state);
240 
241  pdef_->addSolutionPath(base::PathPtr(path), approximate, sol.approxdif, getName());
242  solved = true;
243  }
244 
245  OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
246 
247  return base::PlannerStatus(solved, approximate);
248 }
249 
251 {
252  Planner::getPlannerData(data);
253 
254  std::vector<Motion*> motions;
255  if (nn_)
256  nn_->list(motions);
257 
258  if (lastGoalMotion_)
260 
261  for (unsigned int i = 0 ; i < motions.size() ; ++i)
262  {
263  if (motions[i]->parent == NULL)
264  data.addStartVertex(base::PlannerDataVertex(motions[i]->state));
265  else
266  data.addEdge(base::PlannerDataVertex(motions[i]->parent->state),
267  base::PlannerDataVertex(motions[i]->state));
268  }
269 }
270 
271 void ompl::geometric::pRRT::setThreadCount(unsigned int nthreads)
272 {
273  assert(nthreads > 0);
274  threadCount_ = nthreads;
275 }
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:214
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
void freeMemory()
Free the memory allocated by this planner.
Definition: LBTRRT.cpp:122
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:63
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:254
base::State * state
The state contained by the motion.
Definition: LBTRRT.h:178
void append(const base::State *state)
Append state to the end of this path. The memory for state is copied.
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:400
bool multithreaded
Flag indicating whether multiple threads are used in the computation of the planner.
Definition: Planner.h:211
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:251
void setThreadCount(unsigned int nthreads)
Set the number of threads the planner should use. Default is 2.
Definition: pRRT.cpp:271
double uniform01()
Generate a random real between 0 and 1.
Definition: RandomNumbers.h:62
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:60
Invalid start state or no start state specified.
Definition: PlannerStatus.h:56
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: pRRT.cpp:76
Abstract definition of a goal region that can be sampled.
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:54
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:266
#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.
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: pRRT.h:106
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:50
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:100
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:403
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:409
const State * nextStart()
Return the next valid start state or NULL if no more valid start states are available.
Definition: Planner.cpp:230
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:55
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
Definition: SelfConfig.cpp:232
This class contains methods that automatically configure various parameters for motion planning...
Definition: SelfConfig.h:58
Definition of a goal region.
Definition: GoalRegion.h:50
boost::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: LBTRRT.h:248
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: pRRT.cpp:250
Definition of a geometric path.
Definition: PathGeometric.h:60
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:397
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition: pRRT.cpp:173
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: pRRT.cpp:65
A boost shared pointer wrapper for ompl::base::Path.
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68