00001 #ifndef hexagon_map_H 00002 #define hexagon_map_H 00003 #include "nav_msgs/OccupancyGrid.h" 00004 #include "hexagon_map/point.h" 00005 #include <vector> 00006 #include <vector> 00007 #include <deque> 00008 #include <set> 00009 #include <queue> 00010 #include <sensor_msgs/PointCloud.h> 00011 #include <sensor_msgs/PointCloud2.h> 00012 #include <pcl/point_cloud.h> 00013 #include <pcl_ros/point_cloud.h> 00014 #include <pcl_conversions/pcl_conversions.h> 00015 00016 struct GridData 00017 { 00018 GridData():top(-9999),bottom(9999),numPoint(0){} 00019 CPoint2d Centerp; //六边形栅格中心点 00020 float top;//栅格内点云高程的最大值 00021 float bottom;//栅格内点云高程的最小值 00022 uint32_t numPoint;//栅格内包含点的个数 00023 }; 00024 00025 00026 class hexagon_map 00027 { 00028 00029 public: 00030 00031 float Cover_R; //六边形地图覆盖的半径 00032 float Resulution_L; //每个六边形的边长,六边形栅格的分辨率 00033 int widthnum; //最终六边形地图最外一圈六边形个数 00034 int limitednum; //生成地图过程中用于控制生成六边形过程 00035 00036 float RectangleL; //投影时使用的矩形栅格长 00037 float RectangleW; //投影时使用的矩形栅格宽 00038 00039 // int count; 00040 00041 00042 nav_msgs::OccupancyGrid gridmap; //基于底层的ros栅格地图生成六边形地图 00043 std::vector<CPoint2d> Pointset; //主螺旋线上六边形的中心点 00044 std::vector<int> flagmap; //和栅格地图大小相同用来表示这些栅格是否已经被六边形占据或者六边形的属性 00045 std::queue<CPoint2d> Pointqueue; //六边形生成地图过程中用于保存位于主螺旋线上未被生成六边形的中心点 00046 std::vector<GridData> HexGridData; //存储投影到六边形的栅格信息 00047 00048 00049 hexagon_map(float R,float resolution); 00050 ~hexagon_map(); 00051 void buildmap(); 00052 bool isInpointset(CPoint2d &Checkpoint); 00053 void drawplogon(const float &C_x,const float &C_y,const float &L,int count); 00054 void drawallmap(); 00055 void updateMap(sensor_msgs::PointCloud2 &pointClouds_msg); 00056 int findindexoccpmap(CPoint2d becheckp); 00057 CPoint2d JudgeHexCenpoint(CPoint2d &Checkpoint); 00058 nav_msgs::OccupancyGrid getmap(); 00059 }; 00060 #endif