#include <hexagon_map.h>
Public Member Functions | |
| void | buildmap () |
| void | drawallmap () |
| void | drawplogon (const float &C_x, const float &C_y, const float &L, int count) |
| int | findindexoccpmap (CPoint2d becheckp) |
| nav_msgs::OccupancyGrid | getmap () |
| hexagon_map (float R, float resolution) | |
| bool | isInpointset (CPoint2d &Checkpoint) |
| CPoint2d | JudgeHexCenpoint (CPoint2d &Checkpoint) |
| void | updateMap (sensor_msgs::PointCloud2 &pointClouds_msg) |
| ~hexagon_map () | |
Public Attributes | |
| float | Cover_R |
| std::vector< int > | flagmap |
| nav_msgs::OccupancyGrid | gridmap |
| std::vector< GridData > | HexGridData |
| int | limitednum |
| std::queue< CPoint2d > | Pointqueue |
| std::vector< CPoint2d > | Pointset |
| float | RectangleL |
| float | RectangleW |
| float | Resulution_L |
| int | widthnum |
Definition at line 26 of file hexagon_map.h.
| hexagon_map::hexagon_map | ( | float | R, |
| float | resolution | ||
| ) |
Definition at line 5 of file hexagon_map.cpp.
Definition at line 70 of file hexagon_map.cpp.
| void hexagon_map::buildmap | ( | ) |
Definition at line 255 of file hexagon_map.cpp.
| void hexagon_map::drawallmap | ( | ) |
Definition at line 233 of file hexagon_map.cpp.
| void hexagon_map::drawplogon | ( | const float & | C_x, |
| const float & | C_y, | ||
| const float & | L, | ||
| int | count | ||
| ) |
Definition at line 171 of file hexagon_map.cpp.
| int hexagon_map::findindexoccpmap | ( | CPoint2d | becheckp | ) |
Definition at line 367 of file hexagon_map.cpp.
| nav_msgs::OccupancyGrid hexagon_map::getmap | ( | ) |
Definition at line 640 of file hexagon_map.cpp.
| bool hexagon_map::isInpointset | ( | CPoint2d & | Checkpoint | ) |
Definition at line 216 of file hexagon_map.cpp.
| CPoint2d hexagon_map::JudgeHexCenpoint | ( | CPoint2d & | Checkpoint | ) |
Definition at line 77 of file hexagon_map.cpp.
| void hexagon_map::updateMap | ( | sensor_msgs::PointCloud2 & | pointClouds_msg | ) |
Definition at line 384 of file hexagon_map.cpp.
| float hexagon_map::Cover_R |
Definition at line 31 of file hexagon_map.h.
| std::vector<int> hexagon_map::flagmap |
Definition at line 44 of file hexagon_map.h.
| nav_msgs::OccupancyGrid hexagon_map::gridmap |
Definition at line 42 of file hexagon_map.h.
| std::vector<GridData> hexagon_map::HexGridData |
Definition at line 46 of file hexagon_map.h.
Definition at line 34 of file hexagon_map.h.
| std::queue<CPoint2d> hexagon_map::Pointqueue |
Definition at line 45 of file hexagon_map.h.
| std::vector<CPoint2d> hexagon_map::Pointset |
Definition at line 43 of file hexagon_map.h.
| float hexagon_map::RectangleL |
Definition at line 36 of file hexagon_map.h.
| float hexagon_map::RectangleW |
Definition at line 37 of file hexagon_map.h.
Definition at line 32 of file hexagon_map.h.
Definition at line 33 of file hexagon_map.h.