pRRT.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_RRT_pRRT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_pRRT_
39 
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/base/StateSamplerArray.h"
42 #include "ompl/datastructures/NearestNeighbors.h"
43 #include <boost/thread/mutex.hpp>
44 
45 namespace ompl
46 {
47 
48  namespace geometric
49  {
50 
67  class pRRT : public base::Planner
68  {
69  public:
70 
72 
73  virtual ~pRRT();
74 
75  virtual void getPlannerData(base::PlannerData &data) const;
76 
78 
79  virtual void clear();
80 
90  void setGoalBias(double goalBias)
91  {
92  goalBias_ = goalBias;
93  }
94 
96  double getGoalBias() const
97  {
98  return goalBias_;
99  }
100 
106  void setRange(double distance)
107  {
108  maxDistance_ = distance;
109  }
110 
112  double getRange() const
113  {
114  return maxDistance_;
115  }
116 
118  void setThreadCount(unsigned int nthreads);
119 
120  unsigned int getThreadCount() const
121  {
122  return threadCount_;
123  }
124 
126  template<template<typename T> class NN>
128  {
129  nn_.reset(new NN<Motion*>());
130  }
131 
132  virtual void setup();
133 
134  protected:
135 
136  class Motion
137  {
138  public:
139 
140  Motion() : state(NULL), parent(NULL)
141  {
142  }
143 
144  Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parent(NULL)
145  {
146  }
147 
148  ~Motion()
149  {
150  }
151 
152  base::State *state;
153  Motion *parent;
154 
155  };
156 
158  {
159  Motion *solution;
160  Motion *approxsol;
161  double approxdif;
162  boost::mutex lock;
163  };
164 
165  void threadSolve(unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol);
166  void freeMemory();
167 
168  double distanceFunction(const Motion *a, const Motion *b) const
169  {
170  return si_->distance(a->state, b->state);
171  }
172 
174  boost::shared_ptr< NearestNeighbors<Motion*> > nn_;
175  boost::mutex nnLock_;
176 
177  unsigned int threadCount_;
178 
179  double goalBias_;
180  double maxDistance_;
181 
184  };
185 
186  }
187 }
188 
189 #endif
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
void setGoalBias(double goalBias)
Set the goal bias.
Definition: pRRT.h:90
Class to ease the creation of a set of samplers. This is especially useful for multi-threaded planner...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: pRRT.h:183
void setThreadCount(unsigned int nthreads)
Set the number of threads the planner should use. Default is 2.
Definition: pRRT.cpp:271
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: pRRT.cpp:76
Main namespace. Contains everything in this library.
Definition: Cost.h:42
Base class for a planner.
Definition: Planner.h:232
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: pRRT.h:106
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: pRRT.h:127
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
double getRange() const
Get the range the planner is using.
Definition: pRRT.h:112
A boost shared pointer wrapper for ompl::base::SpaceInformation.
Definition of an abstract state.
Definition: State.h:50
Parallel RRT.
Definition: pRRT.h:67
double getGoalBias() const
Get the goal bias the planner is using.
Definition: pRRT.h:96
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
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