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_RRT_RRT_CONNECT_
00038 #define OMPL_GEOMETRIC_PLANNERS_RRT_RRT_CONNECT_
00039
00040 #include "ompl/geometric/planners/PlannerIncludes.h"
00041 #include "ompl/datastructures/NearestNeighbors.h"
00042
00043 namespace ompl
00044 {
00045
00046 namespace geometric
00047 {
00048
00063 class RRTConnect : public base::Planner
00064 {
00065 public:
00066
00068 RRTConnect(const base::SpaceInformationPtr &si) : base::Planner(si, "RRTConnect")
00069 {
00070 type_ = base::PLAN_TO_GOAL_SAMPLEABLE_REGION;
00071 maxDistance_ = 0.0;
00072 }
00073
00074 virtual ~RRTConnect(void)
00075 {
00076 freeMemory();
00077 }
00078
00079 virtual void getPlannerData(base::PlannerData &data) const;
00080
00081 virtual bool solve(const base::PlannerTerminationCondition &ptc);
00082
00083 virtual void clear(void);
00084
00090 void setRange(double distance)
00091 {
00092 maxDistance_ = distance;
00093 }
00094
00096 double getRange(void) const
00097 {
00098 return maxDistance_;
00099 }
00100
00102 template<template<typename T> class NN>
00103 void setNearestNeighbors(void)
00104 {
00105 tStart_.reset(new NN<Motion*>());
00106 tGoal_.reset(new NN<Motion*>());
00107 }
00108
00109 virtual void setup(void);
00110
00111 protected:
00112
00114 class Motion
00115 {
00116 public:
00117
00118 Motion(void) : root(NULL), state(NULL), parent(NULL)
00119 {
00120 parent = NULL;
00121 state = NULL;
00122 }
00123
00124 Motion(const base::SpaceInformationPtr &si) : root(NULL), state(si->allocState()), parent(NULL)
00125 {
00126 }
00127
00128 ~Motion(void)
00129 {
00130 }
00131
00132 const base::State *root;
00133 base::State *state;
00134 Motion *parent;
00135
00136 };
00137
00139 typedef boost::shared_ptr< NearestNeighbors<Motion*> > TreeData;
00140
00142 struct TreeGrowingInfo
00143 {
00144 base::State *xstate;
00145 Motion *xmotion;
00146 };
00147
00149 enum GrowState
00150 {
00152 TRAPPED,
00154 ADVANCED,
00156 REACHED
00157 };
00158
00160 void freeMemory(void);
00161
00163 double distanceFunction(const Motion* a, const Motion* b) const
00164 {
00165 return si_->distance(a->state, b->state);
00166 }
00167
00169 GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion);
00170
00172 base::StateSamplerPtr sampler_;
00173
00175 TreeData tStart_;
00176
00178 TreeData tGoal_;
00179
00181 double maxDistance_;
00182
00184 RNG rng_;
00185 };
00186
00187 }
00188 }
00189
00190 #endif