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_PRM_BASIC_PRM_
00038 #define OMPL_GEOMETRIC_PLANNERS_PRM_BASIC_PRM_
00039
00040 #include "ompl/geometric/planners/PlannerIncludes.h"
00041 #include "ompl/datastructures/NearestNeighbors.h"
00042 #include <utility>
00043 #include <vector>
00044 #include <map>
00045
00046 namespace ompl
00047 {
00048
00049 namespace geometric
00050 {
00051
00078 class BasicPRM : public base::Planner
00079 {
00080 public:
00081
00083 BasicPRM(const base::SpaceInformationPtr &si) : base::Planner(si, "BasicPRM")
00084 {
00085 type_ = base::PLAN_TO_GOAL_SAMPLEABLE_REGION;
00086
00087 maxNearestNeighbors_ = 10;
00088 componentCount_ = 0;
00089 lastStart_ = NULL;
00090 lastGoal_ = NULL;
00091 }
00092
00093 virtual ~BasicPRM(void)
00094 {
00095 freeMemory();
00096 }
00097
00098 virtual void setProblemDefinition(const base::ProblemDefinitionPtr &pdef);
00099
00103 void setMaxNearestNeighbors(unsigned int maxNearestNeighbors)
00104 {
00105 maxNearestNeighbors_ = maxNearestNeighbors;
00106 }
00107
00111 unsigned int getMaxNearestNeighbors(void) const
00112 {
00113 return maxNearestNeighbors_;
00114 }
00115
00116 virtual void getPlannerData(base::PlannerData &data) const;
00117
00121 virtual void growRoadmap(double growTime);
00122
00123 virtual bool solve(const base::PlannerTerminationCondition &ptc);
00124
00128 virtual void reconstructLastSolution(void);
00129
00130 virtual void clear(void);
00131
00133 template<template<typename T> class NN>
00134 void setNearestNeighbors(void)
00135 {
00136 nn_.reset(new NN<Milestone*>());
00137 }
00138
00139 virtual void setup(void);
00140
00141 protected:
00142
00143
00145 class Milestone
00146 {
00147 public:
00148
00149 Milestone(void) : state(NULL), index(0)
00150 {
00151 }
00152
00154 Milestone(const base::SpaceInformationPtr &si) : state(si->allocState()), index(0)
00155 {
00156 }
00157
00158 ~Milestone(void)
00159 {
00160 }
00161
00163 base::State *state;
00164
00166 unsigned int index;
00167
00169 unsigned long component;
00170
00172 std::vector<Milestone*> adjacent;
00173
00175 std::vector<double> costs;
00176 };
00177
00179 void freeMemory(void);
00180
00182 virtual void nearestNeighbors(Milestone *milestone, std::vector<Milestone*> &nbh);
00183
00185 Milestone* addMilestone(base::State *state);
00186
00188 void uniteComponents(Milestone *m1, Milestone *m2);
00189
00191 void growRoadmap(const std::vector<Milestone*> &start, const std::vector<Milestone*> &goal, const base::PlannerTerminationCondition &ptc, base::State *workState);
00192
00194 bool haveSolution(const std::vector<Milestone*> &start, const std::vector<Milestone*> &goal, std::pair<Milestone*, Milestone*> *endpoints = NULL);
00195
00197 void constructSolution(const Milestone* start, const Milestone* goal);
00198
00200 double distanceFunction(const Milestone* a, const Milestone* b) const
00201 {
00202 return si_->distance(a->state, b->state);
00203 }
00204
00206 base::ValidStateSamplerPtr sampler_;
00207
00209 boost::shared_ptr< NearestNeighbors<Milestone*> > nn_;
00210
00212 std::vector<Milestone*> milestones_;
00213
00215 std::vector<Milestone*> startM_;
00216
00218 std::vector<Milestone*> goalM_;
00219
00221 const Milestone *lastStart_;
00222
00224 const Milestone *lastGoal_;
00225
00227 unsigned int maxNearestNeighbors_;
00228
00230 std::map<unsigned long, unsigned long> componentSizes_;
00231
00233 unsigned long componentCount_;
00234
00236 RNG rng_;
00237 };
00238
00239 }
00240 }
00241
00242 #endif