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_SBL_
00038 #define OMPL_GEOMETRIC_PLANNERS_SBL_SBL_
00039
00040 #include "ompl/geometric/planners/PlannerIncludes.h"
00041 #include "ompl/base/ProjectionEvaluator.h"
00042 #include "ompl/datastructures/Grid.h"
00043 #include <vector>
00044
00045 namespace ompl
00046 {
00047
00048 namespace geometric
00049 {
00050
00086 class SBL : public base::Planner
00087 {
00088 public:
00089
00091 SBL(const base::SpaceInformationPtr &si) : base::Planner(si, "SBL")
00092 {
00093 type_ = base::PLAN_TO_GOAL_SAMPLEABLE_REGION;
00094
00095 maxDistance_ = 0.0;
00096 }
00097
00098 virtual ~SBL(void)
00099 {
00100 freeMemory();
00101 }
00102
00105 void setProjectionEvaluator(const base::ProjectionEvaluatorPtr &projectionEvaluator)
00106 {
00107 projectionEvaluator_ = projectionEvaluator;
00108 }
00109
00112 void setProjectionEvaluator(const std::string &name)
00113 {
00114 projectionEvaluator_ = si_->getStateSpace()->getProjection(name);
00115 }
00116
00118 const base::ProjectionEvaluatorPtr& getProjectionEvaluator(void) const
00119 {
00120 return projectionEvaluator_;
00121 }
00122
00128 void setRange(double distance)
00129 {
00130 maxDistance_ = distance;
00131 }
00132
00134 double getRange(void) const
00135 {
00136 return maxDistance_;
00137 }
00138
00139 virtual void setup(void);
00140
00141 virtual bool solve(const base::PlannerTerminationCondition &ptc);
00142
00143 virtual void clear(void);
00144
00145 virtual void getPlannerData(base::PlannerData &data) const;
00146
00147 protected:
00148
00149 class Motion;
00150
00152 typedef std::vector<Motion*> MotionSet;
00153
00155 class Motion
00156 {
00157 public:
00158
00160 Motion(void) : root(NULL), state(NULL), parent(NULL), valid(false)
00161 {
00162 }
00163
00165 Motion(const base::SpaceInformationPtr &si) : root(NULL), state(si->allocState()), parent(NULL), valid(false)
00166 {
00167 }
00168
00169 ~Motion(void)
00170 {
00171 }
00172
00174 const base::State *root;
00175
00177 base::State *state;
00178
00180 Motion *parent;
00181
00183 bool valid;
00184
00186 MotionSet children;
00187 };
00188
00190 struct TreeData
00191 {
00192 TreeData(void) : grid(0), size(0)
00193 {
00194 }
00195
00197 Grid<MotionSet> grid;
00198
00200 unsigned int size;
00201 };
00202
00204 void freeMemory(void)
00205 {
00206 freeGridMotions(tStart_.grid);
00207 freeGridMotions(tGoal_.grid);
00208 }
00209
00211 void freeGridMotions(Grid<MotionSet> &grid);
00212
00214 void addMotion(TreeData &tree, Motion *motion);
00215
00217 Motion* selectMotion(TreeData &tree);
00218
00220 void removeMotion(TreeData &tree, Motion *motion);
00221
00227 bool isPathValid(TreeData &tree, Motion *motion);
00228
00230 bool checkSolution(bool start, TreeData &tree, TreeData &otherTree, Motion *motion, std::vector<Motion*> &solution);
00231
00233 base::ValidStateSamplerPtr sampler_;
00234
00236 base::ProjectionEvaluatorPtr projectionEvaluator_;
00237
00239 TreeData tStart_;
00240
00242 TreeData tGoal_;
00243
00245 double maxDistance_;
00246
00248 RNG rng_;
00249 };
00250
00251 }
00252 }
00253
00254 #endif