Public Member Functions | Protected Attributes
bwi_mapper::MapLoader Class Reference

Base class for reading a standard ROS map from a YAML file and writing it to an OpenCV Image. More...

#include <map_loader.h>

Inheritance diagram for bwi_mapper::MapLoader:
Inheritance graph
[legend]

List of all members.

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_

Detailed Description

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.


Constructor & Destructor Documentation

bwi_mapper::MapLoader::MapLoader ( const std::string &  fname)

Constructor. Initializes map_resp_ with the given file.

Parameters:
fnameabsolute or relative system file location for the YAML file

Definition at line 64 of file map_loader.cpp.


Member Function Documentation

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.

Parameters:
imageOpenCV 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)

Parameters:
imageOpenCV 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.


Member Data Documentation

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.


The documentation for this class was generated from the following files:


bwi_mapper
Author(s): Piyush Khandelwal
autogenerated on Fri Aug 28 2015 10:14:35