Base class for reading a standard ROS map from a YAML file and writing it to an OpenCV Image. More...
#include <map_loader.h>

| Public Member Functions | |
| void | drawMap (cv::Mat &image, uint32_t orig_x=0, uint32_t orig_y=0) | 
| Draw map_resp_ onto image starting at (orig_x, orig_y). Uses the overloaded drawMap internally. | |
| void | drawMap (cv::Mat &image, const nav_msgs::OccupancyGrid &map, uint32_t orig_x=0, uint32_t orig_y=0) | 
| Draw map onto image starting at (orig_x, orig_y) | |
| void | getMap (nav_msgs::OccupancyGrid &map) const | 
| void | getMapInfo (nav_msgs::MapMetaData &info) const | 
| MapLoader (const std::string &fname) | |
| Constructor. Initializes map_resp_ with the given file. | |
| Protected Attributes | |
| nav_msgs::GetMap::Response | map_resp_ | 
Base class for reading a standard ROS map from a YAML file and writing it to an OpenCV Image.
Definition at line 57 of file map_loader.h.
| bwi_mapper::MapLoader::MapLoader | ( | const std::string & | fname | ) | 
Constructor. Initializes map_resp_ with the given file.
| fname | absolute or relative system file location for the YAML file | 
Definition at line 64 of file map_loader.cpp.
| void bwi_mapper::MapLoader::drawMap | ( | cv::Mat & | image, | 
| uint32_t | orig_x = 0, | ||
| uint32_t | orig_y = 0 | ||
| ) | 
Draw map_resp_ onto image starting at (orig_x, orig_y). Uses the overloaded drawMap internally.
| image | OpenCV image we are writing the map onto | 
Definition at line 156 of file map_loader.cpp.
| void bwi_mapper::MapLoader::drawMap | ( | cv::Mat & | image, | 
| const nav_msgs::OccupancyGrid & | map, | ||
| uint32_t | orig_x = 0, | ||
| uint32_t | orig_y = 0 | ||
| ) | 
Draw map onto image starting at (orig_x, orig_y)
| image | OpenCV image we are writing the map onto | 
Definition at line 171 of file map_loader.cpp.
| void bwi_mapper::MapLoader::getMap | ( | nav_msgs::OccupancyGrid & | map | ) | const | 
Definition at line 164 of file map_loader.cpp.
| void bwi_mapper::MapLoader::getMapInfo | ( | nav_msgs::MapMetaData & | info | ) | const | 
Definition at line 160 of file map_loader.cpp.
| nav_msgs::GetMap::Response bwi_mapper::MapLoader::map_resp_  [protected] | 
/brief The base map being loaded by MapLoader. GetMap::Response is used to reuse code from map_server
Definition at line 89 of file map_loader.h.