00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef OMPL_GEOMETRIC_PLANNERS_SBL_pSBL_
00038 #define OMPL_GEOMETRIC_PLANNERS_SBL_pSBL_
00039
00040 #include "ompl/geometric/planners/PlannerIncludes.h"
00041 #include "ompl/base/ProjectionEvaluator.h"
00042 #include "ompl/base/StateSamplerArray.h"
00043 #include "ompl/datastructures/Grid.h"
00044 #include <boost/thread/mutex.hpp>
00045 #include <vector>
00046
00047 namespace ompl
00048 {
00049
00050 namespace geometric
00051 {
00052
00088 class pSBL : public base::Planner
00089 {
00090 public:
00091
00092 pSBL(const base::SpaceInformationPtr &si) : base::Planner(si, "pSBL"),
00093 samplerArray_(si)
00094 {
00095 type_ = base::PLAN_TO_GOAL_STATE;
00096 maxDistance_ = 0.0;
00097 setThreadCount(2);
00098 }
00099
00100 virtual ~pSBL(void)
00101 {
00102 freeMemory();
00103 }
00104
00107 void setProjectionEvaluator(const base::ProjectionEvaluatorPtr &projectionEvaluator)
00108 {
00109 projectionEvaluator_ = projectionEvaluator;
00110 }
00111
00114 void setProjectionEvaluator(const std::string &name)
00115 {
00116 projectionEvaluator_ = si_->getStateSpace()->getProjection(name);
00117 }
00118
00120 const base::ProjectionEvaluatorPtr& getProjectionEvaluator(void) const
00121 {
00122 return projectionEvaluator_;
00123 }
00124
00130 void setRange(double distance)
00131 {
00132 maxDistance_ = distance;
00133 }
00134
00136 double getRange(void) const
00137 {
00138 return maxDistance_;
00139 }
00140
00142 void setThreadCount(unsigned int nthreads);
00143
00145 unsigned int getThreadCount(void) const
00146 {
00147 return threadCount_;
00148 }
00149
00150 virtual void setup(void);
00151
00152 virtual bool solve(const base::PlannerTerminationCondition &ptc);
00153
00154 virtual void clear(void);
00155
00156 virtual void getPlannerData(base::PlannerData &data) const;
00157
00158 protected:
00159
00160 class Motion;
00161 typedef std::vector<Motion*> MotionSet;
00162
00163 class Motion
00164 {
00165 public:
00166
00167 Motion(void) : root(NULL), state(NULL), parent(NULL), valid(false)
00168 {
00169 }
00170
00171 Motion(const base::SpaceInformationPtr &si) : root(NULL), state(si->allocState()), parent(NULL), valid(false)
00172 {
00173 }
00174
00175 ~Motion(void)
00176 {
00177 }
00178
00179 const base::State *root;
00180 base::State *state;
00181 Motion *parent;
00182 bool valid;
00183 MotionSet children;
00184 boost::mutex lock;
00185 };
00186
00187 struct TreeData
00188 {
00189 TreeData(void) : grid(0), size(0)
00190 {
00191 }
00192
00193 Grid<MotionSet> grid;
00194 unsigned int size;
00195 boost::mutex lock;
00196 };
00197
00198 struct SolutionInfo
00199 {
00200 std::vector<Motion*> solution;
00201 bool found;
00202 boost::mutex lock;
00203 };
00204
00205 struct PendingRemoveMotion
00206 {
00207 TreeData *tree;
00208 Motion *motion;
00209 };
00210
00211 struct MotionsToBeRemoved
00212 {
00213 std::vector<PendingRemoveMotion> motions;
00214 boost::mutex lock;
00215 };
00216
00217 void threadSolve(unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol);
00218
00219 void freeMemory(void)
00220 {
00221 freeGridMotions(tStart_.grid);
00222 freeGridMotions(tGoal_.grid);
00223 }
00224
00225 void freeGridMotions(Grid<MotionSet> &grid);
00226
00227 void addMotion(TreeData &tree, Motion *motion);
00228 Motion* selectMotion(RNG &rng, TreeData &tree);
00229 void removeMotion(TreeData &tree, Motion *motion, std::map<Motion*, bool> &seen);
00230 bool isPathValid(TreeData &tree, Motion *motion);
00231 bool checkSolution(RNG &rng, bool start, TreeData &tree, TreeData &otherTree, Motion *motion, std::vector<Motion*> &solution);
00232
00233
00234 base::StateSamplerArray<base::ValidStateSampler> samplerArray_;
00235 base::ProjectionEvaluatorPtr projectionEvaluator_;
00236
00237 TreeData tStart_;
00238 TreeData tGoal_;
00239
00240 MotionsToBeRemoved removeList_;
00241 boost::mutex loopLock_;
00242 boost::mutex loopLockCounter_;
00243 unsigned int loopCounter_;
00244
00245 double maxDistance_;
00246
00247 unsigned int threadCount_;
00248 };
00249
00250 }
00251 }
00252
00253 #endif