Go to the documentation of this file.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 EXPLORE_FRONTIER_H_
00038 #define EXPLORE_FRONTIER_H_
00039 
00040 #include <nav_msgs/GetMap.h>
00041 #include <nav_msgs/OccupancyGrid.h>
00042 #include <geometry_msgs/Pose.h>
00043 #include <visualization_msgs/Marker.h>
00044 
00045 #include <LinearMath/btVector3.h>
00046 
00047 #include <costmap_2d/costmap_2d_ros.h>
00048 #include <navfn/navfn_ros.h>
00049 #include <tf/transform_listener.h>
00050 
00051 namespace explore {
00052 
00053 struct FrontierPoint{
00054   int idx;     
00055   btVector3 d; 
00056 
00057   FrontierPoint(int idx_, btVector3 d_) : idx(idx_), d(d_) {};
00058 };
00059 
00060 struct Frontier {
00061   geometry_msgs::Pose pose;
00062   int size;
00063   Frontier():pose(),size(0) {}
00064   Frontier(const Frontier& copy) { pose = copy.pose; size = copy.size; }
00065 };
00066 
00067 struct WeightedFrontier {
00068   Frontier frontier;
00069   float cost;
00070   bool operator<(const WeightedFrontier& o) const { return cost < o.cost; }
00071   WeightedFrontier():frontier(),cost(1e9) {}
00072   WeightedFrontier(const WeightedFrontier& copy) { frontier = copy.frontier; cost = copy.cost; }
00073 };
00074 
00079 class ExploreFrontier {
00080 private:
00081   nav_msgs::OccupancyGrid map_;
00082 
00083   uint lastMarkerCount_;
00084   float costmapResolution_;
00085 
00086   navfn::NavfnROS* planner_;
00087 protected:
00088   std::vector<Frontier> frontiers_;
00089 
00094   virtual void findFrontiers(costmap_2d::Costmap2DROS& costmap_);
00095 
00100   virtual float getFrontierCost(const Frontier& frontier);
00101 
00107   virtual double getOrientationChange(const Frontier& frontier, const tf::Stamped<tf::Pose>& robot_pose);
00108 
00113   virtual float getFrontierGain(const Frontier& frontier, double map_resolution);
00114 
00115 public:
00116   ExploreFrontier();
00117   virtual ~ExploreFrontier();
00118 
00125   virtual bool getFrontiers(costmap_2d::Costmap2DROS& costmap, std::vector<geometry_msgs::Pose>& frontiers);
00126 
00146   virtual bool getExplorationGoals(costmap_2d::Costmap2DROS& costmap, tf::Stamped<tf::Pose> robot_pose, navfn::NavfnROS* planner, std::vector<geometry_msgs::Pose>& goals, double cost_scale, double orientation_scale, double gain_scale);
00147 
00152   virtual void getVisualizationMarkers(std::vector<visualization_msgs::Marker>& markers);
00153 };
00154 
00155 }
00156 
00157 #endif