pSBL.h
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 #ifndef OMPL_GEOMETRIC_PLANNERS_SBL_pSBL_
38 #define OMPL_GEOMETRIC_PLANNERS_SBL_pSBL_
39 
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/base/ProjectionEvaluator.h"
42 #include "ompl/base/StateSamplerArray.h"
43 #include "ompl/datastructures/Grid.h"
44 #include "ompl/datastructures/PDF.h"
45 #include <boost/thread/mutex.hpp>
46 #include <vector>
47 
48 namespace ompl
49 {
50 
51  namespace geometric
52  {
53 
87  class pSBL : public base::Planner
88  {
89  public:
90 
92 
93  virtual ~pSBL();
94 
97  void setProjectionEvaluator(const base::ProjectionEvaluatorPtr &projectionEvaluator)
98  {
99  projectionEvaluator_ = projectionEvaluator;
100  }
101 
104  void setProjectionEvaluator(const std::string &name)
105  {
106  projectionEvaluator_ = si_->getStateSpace()->getProjection(name);
107  }
108 
111  {
112  return projectionEvaluator_;
113  }
114 
120  void setRange(double distance)
121  {
122  maxDistance_ = distance;
123  }
124 
126  double getRange() const
127  {
128  return maxDistance_;
129  }
130 
132  void setThreadCount(unsigned int nthreads);
133 
135  unsigned int getThreadCount() const
136  {
137  return threadCount_;
138  }
139 
140  virtual void setup();
141 
143 
144  virtual void clear();
145 
146  virtual void getPlannerData(base::PlannerData &data) const;
147 
148  protected:
149 
150  class Motion;
151  struct MotionInfo;
152 
155 
158 
159  class Motion
160  {
161  public:
162 
163  Motion() : root(NULL), state(NULL), parent(NULL), valid(false)
164  {
165  }
166 
167  Motion(const base::SpaceInformationPtr &si) : root(NULL), state(si->allocState()), parent(NULL), valid(false)
168  {
169  }
170 
171  ~Motion()
172  {
173  }
174 
175  const base::State *root;
176  base::State *state;
177  Motion *parent;
178  bool valid;
179  std::vector<Motion*> children;
180  boost::mutex lock;
181  };
182 
184  struct MotionInfo
185  {
186  Motion* operator[](unsigned int i)
187  {
188  return motions_[i];
189  }
190  std::vector<Motion*>::iterator begin()
191  {
192  return motions_.begin();
193  }
194  void erase(std::vector<Motion*>::iterator iter)
195  {
196  motions_.erase(iter);
197  }
198  void push_back(Motion *m)
199  {
200  motions_.push_back(m);
201  }
202  unsigned int size() const
203  {
204  return motions_.size();
205  }
206  bool empty() const
207  {
208  return motions_.empty();
209  }
210  std::vector<Motion*> motions_;
211  CellPDF::Element *elem_;
212  };
213 
214  struct TreeData
215  {
216  TreeData() : grid(0), size(0)
217  {
218  }
219 
220  Grid<MotionInfo> grid;
221  unsigned int size;
222  CellPDF pdf;
223  boost::mutex lock;
224  };
225 
227  {
228  std::vector<Motion*> solution;
229  bool found;
230  boost::mutex lock;
231  };
232 
234  {
235  TreeData *tree;
236  Motion *motion;
237  };
238 
240  {
241  std::vector<PendingRemoveMotion> motions;
242  boost::mutex lock;
243  };
244 
245  void threadSolve(unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol);
246 
247  void freeMemory()
248  {
249  freeGridMotions(tStart_.grid);
250  freeGridMotions(tGoal_.grid);
251  }
252 
253  void freeGridMotions(Grid<MotionInfo> &grid);
254 
255  void addMotion(TreeData &tree, Motion *motion);
256  Motion* selectMotion(RNG &rng, TreeData &tree);
257  void removeMotion(TreeData &tree, Motion *motion, std::map<Motion*, bool> &seen);
258  bool isPathValid(TreeData &tree, Motion *motion);
259  bool checkSolution(RNG &rng, bool start, TreeData &tree, TreeData &otherTree, Motion *motion, std::vector<Motion*> &solution);
260 
261 
263  base::ProjectionEvaluatorPtr projectionEvaluator_;
264 
265  TreeData tStart_;
266  TreeData tGoal_;
267 
268  MotionsToBeRemoved removeList_;
269  boost::mutex loopLock_;
270  boost::mutex loopLockCounter_;
271  unsigned int loopCounter_;
272 
273  double maxDistance_;
274 
275  unsigned int threadCount_;
276 
278  std::pair<base::State*, base::State*> connectionPoint_;
279  };
280 
281  }
282 }
283 
284 #endif
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
Representation of a simple grid.
Definition: Grid.h:51
void setThreadCount(unsigned int nthreads)
Set the number of threads the planner should use. Default is 2.
Definition: pSBL.cpp:482
void setProjectionEvaluator(const std::string &name)
Set the projection evaluator (select one from the ones registered with the state space).
Definition: pSBL.h:104
void setProjectionEvaluator(const base::ProjectionEvaluatorPtr &projectionEvaluator)
Set the projection evaluator. This class is able to compute the projection of a given state...
Definition: pSBL.h:97
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Main namespace. Contains everything in this library.
Definition: Cost.h:42
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: pSBL.cpp:193
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: pSBL.cpp:73
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:54
Base class for a planner.
Definition: Planner.h:232
A boost shared pointer wrapper for ompl::base::ProjectionEvaluator.
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
const base::ProjectionEvaluatorPtr & getProjectionEvaluator() const
Get the projection evaluator.
Definition: pSBL.h:110
A boost shared pointer wrapper for ompl::base::SpaceInformation.
Definition of an abstract state.
Definition: State.h:50
Definition of a cell in this grid.
Definition: Grid.h:59
unsigned int getThreadCount() const
Get the thread count.
Definition: pSBL.h:135
PDF< GridCell * > CellPDF
A PDF of grid cells.
Definition: pSBL.h:157
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: pSBL.cpp:453
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: pSBL.h:120
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: pSBL.cpp:62
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:397
Grid< MotionInfo >::Cell GridCell
A grid cell.
Definition: pSBL.h:151
Parallel Single-query Bi-directional Lazy collision checking planner.
Definition: pSBL.h:87
A struct containing an array of motions and a corresponding PDF element.
Definition: pSBL.h:184
double getRange() const
Get the range the planner is using.
Definition: pSBL.h:126
std::pair< base::State *, base::State * > connectionPoint_
The pair of states in each tree connected during planning. Used for PlannerData computation.
Definition: pSBL.h:278