29 #ifndef _GEOTIFFWRITER_H__    30 #define _GEOTIFFWRITER_H__    34 #include <Eigen/Geometry>    36 #include <nav_msgs/OccupancyGrid.h>    37 #include <nav_msgs/MapMetaData.h>    39 #include <QtGui/QImage>    40 #include <QtGui/QApplication>    41 #include <QtGui/QFont>    65   void drawMap(
const nav_msgs::OccupancyGrid& map, 
bool draw_explored_space_grid = 
true);
    67   inline virtual void drawPath(
const Eigen::Vector3f& start, 
const std::vector<Eigen::Vector2f>& points){
    70   void drawPath(
const Eigen::Vector3f& 
start, 
const std::vector<Eigen::Vector2f>& points, 
int color_r, 
int color_g, 
int color_b);
    79   void drawCross(QPainter& painter, 
const Eigen::Vector2f& coords);
 Eigen::Vector2f rightBottomMarginPixelsf
float pixelsPerGeoTiffMeter
HectorMapTools::CoordinateTransformer< float > world_map_transformer_
bool useCheckerboardCache
void drawMap(const nav_msgs::OccupancyGrid &map, bool draw_explored_space_grid=true)
Eigen::Vector2f mapEndInGeotiff
void drawObjectOfInterest(const Eigen::Vector2f &coords, const std::string &txt, const Color &color, const Shape &shape)
Eigen::Vector2f leftTopMarginMeters
GeotiffWriter(bool useCheckerboardCacheIn=false)
void setUseUtcTimeSuffix(bool useSuffix)
void drawCross(QPainter &painter, const Eigen::Vector2f &coords)
Eigen::Vector2i rightBottomMarginPixels
virtual void drawPath(const Eigen::Vector3f &start, const std::vector< Eigen::Vector2f > &points)
std::string map_file_name_
Eigen::Vector2f mapOrigInGeotiff
bool setupTransforms(const nav_msgs::OccupancyGrid &map)
Eigen::Vector2f rightBottomMarginMeters
Eigen::Vector2i minCoordsMap
void drawCoordSystem(QPainter &painter)
void setMapFilePath(const std::string &mapFilePath)
nav_msgs::MapMetaData cached_map_meta_data_
void setMapFileName(const std::string &mapFileName)
std::string getBasePathAndFileName() const
void drawArrow(QPainter &painter)
bool use_utc_time_suffix_
std::string map_file_path_
void transformPainterToImgCoords(QPainter &painter)
void drawBackgroundCheckerboard()
Eigen::Vector2i maxCoordsMap
Eigen::Vector2f totalMeters
HectorMapTools::CoordinateTransformer< float > world_geo_transformer_
QImage checkerboard_cache
HectorMapTools::CoordinateTransformer< float > map_geo_transformer_
Eigen::Vector2i geoTiffSizePixels