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
00038 #ifndef EXPLORE_FRONTIER_H_
00039 #define EXPLORE_FRONTIER_H_
00040
00041 #include <nav_msgs/OccupancyGrid.h>
00042 #include <geometry_msgs/Pose.h>
00043 #include <visualization_msgs/MarkerArray.h>
00044 #include <tf/LinearMath/Vector3.h>
00045
00046 #include <explore/costmap_client.h>
00047
00048
00049
00050
00051
00052
00053
00054
00055 #include <explore/navfn_ros.h>
00056
00057 namespace explore {
00058
00059 struct FrontierPoint {
00060 size_t idx;
00061 tf::Vector3 d;
00062
00063 FrontierPoint() : idx(0) {}
00064 FrontierPoint(size_t idx_, const tf::Vector3& d_) : idx(idx_), d(d_) {}
00065 };
00066
00067 struct Frontier {
00068 size_t size;
00069 geometry_msgs::Pose pose;
00070
00071 Frontier() : size(0) {}
00072 Frontier(size_t size_, const geometry_msgs::Pose& pose_) : size(size_), pose(pose_) {}
00073 };
00074
00075 struct WeightedFrontier {
00076 double cost;
00077 Frontier frontier;
00078
00079 WeightedFrontier() : cost(1e9) {}
00080 WeightedFrontier(double cost_, const Frontier& frontier_) : cost(cost_), frontier(frontier_) {}
00081 bool operator<(const WeightedFrontier& o) const { return cost < o.cost; }
00082 };
00083
00088 class ExploreFrontier {
00089 private:
00090
00091 Costmap2DClient* const costmap_client_;
00092 costmap_2d::Costmap2D* const costmap_;
00093 navfn::NavfnROS* const planner_;
00094
00095 nav_msgs::OccupancyGrid map_;
00096 std::vector<Frontier> frontiers_;
00097
00098 size_t last_markers_count_;
00099
00103 void findFrontiers();
00104
00109 double getFrontierCost(const Frontier& frontier);
00110
00116 double getOrientationChange(const Frontier& frontier, const tf::Stamped<tf::Pose>& robot_pose) const;
00117
00122 double getFrontierGain(const Frontier& frontier) const;
00123
00124 public:
00131 ExploreFrontier(Costmap2DClient* costmap, navfn::NavfnROS* planner);
00132
00138 bool getFrontiers(std::vector<geometry_msgs::Pose>& frontiers);
00139
00157 bool getExplorationGoals(
00158 tf::Stamped<tf::Pose> start,
00159 std::vector<geometry_msgs::Pose>& goals,
00160 double cost_scale, double orientation_scale, double gain_scale
00161 );
00162
00167 void getVisualizationMarkers(visualization_msgs::MarkerArray& markers);
00168 };
00169
00170 }
00171
00172 #endif