Go to the documentation of this file.00001
00040 #ifndef MAP_LOADER_QANRO76Q
00041 #define MAP_LOADER_QANRO76Q
00042
00043 #include <string>
00044
00045 #include <nav_msgs/GetMap.h>
00046 #include <nav_msgs/GetMapResponse.h>
00047 #include <yaml-cpp/yaml.h>
00048 #include <opencv/cv.h>
00049
00050 namespace bwi_mapper {
00051
00057 class MapLoader {
00058
00059 public:
00060
00066 MapLoader (const std::string& fname);
00067
00073 void drawMap(cv::Mat &image, uint32_t orig_x = 0, uint32_t orig_y = 0);
00074
00075 void getMapInfo(nav_msgs::MapMetaData& info) const;
00076 void getMap(nav_msgs::OccupancyGrid& map) const;
00077
00082 void drawMap(cv::Mat &image, const nav_msgs::OccupancyGrid& map,
00083 uint32_t orig_x = 0, uint32_t orig_y = 0);
00084
00085 protected:
00086
00089 nav_msgs::GetMap::Response map_resp_;
00090
00091 };
00092
00093 }
00094
00095 #endif