#include <geotiff_writer.h>

| Public Member Functions | |
| void | drawBackgroundCheckerboard () | 
| void | drawCoords () | 
| void | drawMap (const nav_msgs::OccupancyGrid &map, bool draw_explored_space_grid=true) | 
| void | drawObjectOfInterest (const Eigen::Vector2f &coords, const std::string &txt, const Color &color) | 
| virtual void | drawPath (const Eigen::Vector3f &start, const std::vector< Eigen::Vector2f > &points) | 
| void | drawPath (const Eigen::Vector3f &start, const std::vector< Eigen::Vector2f > &points, int color_r, int color_g, int color_b) | 
| GeotiffWriter (bool useCheckerboardCacheIn=false) | |
| std::string | getBasePathAndFileName () const | 
| void | setMapFileName (const std::string &mapFileName) | 
| void | setMapFilePath (const std::string &mapFilePath) | 
| void | setupImageSize () | 
| bool | setupTransforms (const nav_msgs::OccupancyGrid &map) | 
| void | setUseUtcTimeSuffix (bool useSuffix) | 
| void | writeGeotiffImage () | 
| virtual | ~GeotiffWriter () | 
| Protected Member Functions | |
| void | drawArrow (QPainter &painter) | 
| void | drawCoordSystem (QPainter &painter) | 
| void | drawCross (QPainter &painter, const Eigen::Vector2f &coords) | 
| void | transformPainterToImgCoords (QPainter &painter) | 
| Protected Attributes | |
| QApplication * | app | 
| nav_msgs::MapMetaData | cached_map_meta_data_ | 
| QImage | checkerboard_cache | 
| int | fake_argc_ | 
| char ** | fake_argv_ | 
| Eigen::Vector2i | geoTiffSizePixels | 
| QImage | image | 
| Eigen::Vector2f | leftTopMarginMeters | 
| QFont | map_draw_font_ | 
| std::string | map_file_name_ | 
| std::string | map_file_path_ | 
| HectorMapTools::CoordinateTransformer < float > | map_geo_transformer_ | 
| Eigen::Vector2f | mapEndInGeotiff | 
| Eigen::Vector2f | mapOrigInGeotiff | 
| Eigen::Vector2i | maxCoordsMap | 
| Eigen::Vector2i | minCoordsMap | 
| Eigen::Vector2f | origin | 
| float | pixelsPerGeoTiffMeter | 
| float | pixelsPerMapMeter | 
| float | resolution | 
| int | resolutionFactor | 
| float | resolutionFactorf | 
| Eigen::Vector2f | rightBottomMarginMeters | 
| Eigen::Vector2i | rightBottomMarginPixels | 
| Eigen::Vector2f | rightBottomMarginPixelsf | 
| Eigen::Vector2i | sizeMap | 
| Eigen::Vector2f | sizeMapf | 
| Eigen::Vector2f | totalMeters | 
| bool | use_utc_time_suffix_ | 
| bool | useCheckerboardCache | 
| HectorMapTools::CoordinateTransformer < float > | world_geo_transformer_ | 
| HectorMapTools::CoordinateTransformer < float > | world_map_transformer_ | 
Definition at line 50 of file geotiff_writer.h.
| hector_geotiff::GeotiffWriter::GeotiffWriter | ( | bool | useCheckerboardCacheIn = false | ) | 
Definition at line 43 of file geotiff_writer.cpp.
| hector_geotiff::GeotiffWriter::~GeotiffWriter | ( | ) |  [virtual] | 
Definition at line 60 of file geotiff_writer.cpp.
| void hector_geotiff::GeotiffWriter::drawArrow | ( | QPainter & | painter | ) |  [protected] | 
Definition at line 555 of file geotiff_writer.cpp.
Definition at line 230 of file geotiff_writer.cpp.
Definition at line 518 of file geotiff_writer.cpp.
| void hector_geotiff::GeotiffWriter::drawCoordSystem | ( | QPainter & | painter | ) |  [protected] | 
Definition at line 575 of file geotiff_writer.cpp.
| void hector_geotiff::GeotiffWriter::drawCross | ( | QPainter & | painter, | 
| const Eigen::Vector2f & | coords | ||
| ) |  [protected] | 
Definition at line 549 of file geotiff_writer.cpp.
| void hector_geotiff::GeotiffWriter::drawMap | ( | const nav_msgs::OccupancyGrid & | map, | 
| bool | draw_explored_space_grid = true | ||
| ) | 
Definition at line 272 of file geotiff_writer.cpp.
| void hector_geotiff::GeotiffWriter::drawObjectOfInterest | ( | const Eigen::Vector2f & | coords, | 
| const std::string & | txt, | ||
| const Color & | color | ||
| ) |  [virtual] | 
Implements hector_geotiff::MapWriterInterface.
Definition at line 353 of file geotiff_writer.cpp.
| virtual void hector_geotiff::GeotiffWriter::drawPath | ( | const Eigen::Vector3f & | start, | 
| const std::vector< Eigen::Vector2f > & | points | ||
| ) |  [inline, virtual] | 
Reimplemented from hector_geotiff::MapWriterInterface.
Definition at line 67 of file geotiff_writer.h.
| void hector_geotiff::GeotiffWriter::drawPath | ( | const Eigen::Vector3f & | start, | 
| const std::vector< Eigen::Vector2f > & | points, | ||
| int | color_r, | ||
| int | color_g, | ||
| int | color_b | ||
| ) |  [virtual] | 
Implements hector_geotiff::MapWriterInterface.
Definition at line 406 of file geotiff_writer.cpp.
| std::string hector_geotiff::GeotiffWriter::getBasePathAndFileName | ( | ) | const  [virtual] | 
Implements hector_geotiff::MapWriterInterface.
Definition at line 448 of file geotiff_writer.cpp.
| void hector_geotiff::GeotiffWriter::setMapFileName | ( | const std::string & | mapFileName | ) | 
Definition at line 65 of file geotiff_writer.cpp.
| void hector_geotiff::GeotiffWriter::setMapFilePath | ( | const std::string & | mapFilePath | ) | 
Definition at line 79 of file geotiff_writer.cpp.
Definition at line 207 of file geotiff_writer.cpp.
| bool hector_geotiff::GeotiffWriter::setupTransforms | ( | const nav_msgs::OccupancyGrid & | map | ) | 
Definition at line 90 of file geotiff_writer.cpp.
| void hector_geotiff::GeotiffWriter::setUseUtcTimeSuffix | ( | bool | useSuffix | ) | 
Definition at line 84 of file geotiff_writer.cpp.
| void hector_geotiff::GeotiffWriter::transformPainterToImgCoords | ( | QPainter & | painter | ) |  [protected] | 
Definition at line 511 of file geotiff_writer.cpp.
Definition at line 453 of file geotiff_writer.cpp.
| QApplication* hector_geotiff::GeotiffWriter::app  [protected] | 
Definition at line 119 of file geotiff_writer.h.
| nav_msgs::MapMetaData hector_geotiff::GeotiffWriter::cached_map_meta_data_  [protected] | 
Definition at line 126 of file geotiff_writer.h.
| QImage hector_geotiff::GeotiffWriter::checkerboard_cache  [protected] | 
Definition at line 118 of file geotiff_writer.h.
| int hector_geotiff::GeotiffWriter::fake_argc_  [protected] | 
Definition at line 128 of file geotiff_writer.h.
| char** hector_geotiff::GeotiffWriter::fake_argv_  [protected] | 
Definition at line 129 of file geotiff_writer.h.
| Eigen::Vector2i hector_geotiff::GeotiffWriter::geoTiffSizePixels  [protected] | 
Definition at line 109 of file geotiff_writer.h.
| QImage hector_geotiff::GeotiffWriter::image  [protected] | 
Definition at line 117 of file geotiff_writer.h.
| Eigen::Vector2f hector_geotiff::GeotiffWriter::leftTopMarginMeters  [protected] | 
Definition at line 105 of file geotiff_writer.h.
| QFont hector_geotiff::GeotiffWriter::map_draw_font_  [protected] | 
Definition at line 120 of file geotiff_writer.h.
| std::string hector_geotiff::GeotiffWriter::map_file_name_  [protected] | 
Definition at line 114 of file geotiff_writer.h.
| std::string hector_geotiff::GeotiffWriter::map_file_path_  [protected] | 
Definition at line 115 of file geotiff_writer.h.
| HectorMapTools::CoordinateTransformer<float> hector_geotiff::GeotiffWriter::map_geo_transformer_  [protected] | 
Definition at line 123 of file geotiff_writer.h.
| Eigen::Vector2f hector_geotiff::GeotiffWriter::mapEndInGeotiff  [protected] | 
Definition at line 112 of file geotiff_writer.h.
| Eigen::Vector2f hector_geotiff::GeotiffWriter::mapOrigInGeotiff  [protected] | 
Definition at line 111 of file geotiff_writer.h.
| Eigen::Vector2i hector_geotiff::GeotiffWriter::maxCoordsMap  [protected] | 
Definition at line 96 of file geotiff_writer.h.
| Eigen::Vector2i hector_geotiff::GeotiffWriter::minCoordsMap  [protected] | 
Definition at line 95 of file geotiff_writer.h.
| Eigen::Vector2f hector_geotiff::GeotiffWriter::origin  [protected] | 
Definition at line 84 of file geotiff_writer.h.
| float hector_geotiff::GeotiffWriter::pixelsPerGeoTiffMeter  [protected] | 
Definition at line 93 of file geotiff_writer.h.
| float hector_geotiff::GeotiffWriter::pixelsPerMapMeter  [protected] | 
Definition at line 92 of file geotiff_writer.h.
| float hector_geotiff::GeotiffWriter::resolution  [protected] | 
Definition at line 83 of file geotiff_writer.h.
| int hector_geotiff::GeotiffWriter::resolutionFactor  [protected] | 
Definition at line 86 of file geotiff_writer.h.
| float hector_geotiff::GeotiffWriter::resolutionFactorf  [protected] | 
Definition at line 87 of file geotiff_writer.h.
| Eigen::Vector2f hector_geotiff::GeotiffWriter::rightBottomMarginMeters  [protected] | 
Definition at line 101 of file geotiff_writer.h.
| Eigen::Vector2i hector_geotiff::GeotiffWriter::rightBottomMarginPixels  [protected] | 
Definition at line 103 of file geotiff_writer.h.
| Eigen::Vector2f hector_geotiff::GeotiffWriter::rightBottomMarginPixelsf  [protected] | 
Definition at line 102 of file geotiff_writer.h.
| Eigen::Vector2i hector_geotiff::GeotiffWriter::sizeMap  [protected] | 
Definition at line 98 of file geotiff_writer.h.
| Eigen::Vector2f hector_geotiff::GeotiffWriter::sizeMapf  [protected] | 
Definition at line 99 of file geotiff_writer.h.
| Eigen::Vector2f hector_geotiff::GeotiffWriter::totalMeters  [protected] | 
Definition at line 107 of file geotiff_writer.h.
| bool hector_geotiff::GeotiffWriter::use_utc_time_suffix_  [protected] | 
Definition at line 90 of file geotiff_writer.h.
| bool hector_geotiff::GeotiffWriter::useCheckerboardCache  [protected] | 
Definition at line 89 of file geotiff_writer.h.
| HectorMapTools::CoordinateTransformer<float> hector_geotiff::GeotiffWriter::world_geo_transformer_  [protected] | 
Definition at line 124 of file geotiff_writer.h.
| HectorMapTools::CoordinateTransformer<float> hector_geotiff::GeotiffWriter::world_map_transformer_  [protected] | 
Definition at line 122 of file geotiff_writer.h.