#include <geotiff_writer.h>
Definition at line 50 of file geotiff_writer.h.
 
◆ GeotiffWriter()
      
        
          | hector_geotiff::GeotiffWriter::GeotiffWriter | ( | bool | useCheckerboardCacheIn = false | ) |  | 
      
 
 
◆ ~GeotiffWriter()
  
  | 
        
          | hector_geotiff::GeotiffWriter::~GeotiffWriter | ( |  | ) |  |  | virtual | 
 
 
◆ drawArrow()
  
  | 
        
          | void hector_geotiff::GeotiffWriter::drawArrow | ( | QPainter & | painter | ) |  |  | protected | 
 
 
◆ drawBackgroundCheckerboard()
      
        
          | void hector_geotiff::GeotiffWriter::drawBackgroundCheckerboard | ( |  | ) |  | 
      
 
 
◆ drawCoords()
      
        
          | void hector_geotiff::GeotiffWriter::drawCoords | ( |  | ) |  | 
      
 
 
◆ drawCoordSystem()
  
  | 
        
          | void hector_geotiff::GeotiffWriter::drawCoordSystem | ( | QPainter & | painter | ) |  |  | protected | 
 
 
◆ drawCross()
  
  | 
        
          | void hector_geotiff::GeotiffWriter::drawCross | ( | QPainter & | painter, |  
          |  |  | const Eigen::Vector2f & | coords |  
          |  | ) |  |  |  | protected | 
 
 
◆ drawMap()
      
        
          | void hector_geotiff::GeotiffWriter::drawMap | ( | const nav_msgs::OccupancyGrid & | map, | 
        
          |  |  | bool | draw_explored_space_grid = true | 
        
          |  | ) |  |  | 
      
 
 
◆ drawObjectOfInterest()
  
  | 
        
          | void hector_geotiff::GeotiffWriter::drawObjectOfInterest | ( | const Eigen::Vector2f & | coords, |  
          |  |  | const std::string & | txt, |  
          |  |  | const Color & | color, |  
          |  |  | const Shape & | shape |  
          |  | ) |  |  |  | virtual | 
 
 
◆ drawPath() [1/2]
  
  | 
        
          | virtual void hector_geotiff::GeotiffWriter::drawPath | ( | const Eigen::Vector3f & | start, |  
          |  |  | const std::vector< Eigen::Vector2f > & | points |  
          |  | ) |  |  |  | inlinevirtual | 
 
 
◆ drawPath() [2/2]
  
  | 
        
          | 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 | 
 
 
◆ getBasePathAndFileName()
  
  | 
        
          | std::string hector_geotiff::GeotiffWriter::getBasePathAndFileName | ( |  | ) | const |  | virtual | 
 
 
◆ setMapFileName()
      
        
          | void hector_geotiff::GeotiffWriter::setMapFileName | ( | const std::string & | mapFileName | ) |  | 
      
 
 
◆ setMapFilePath()
      
        
          | void hector_geotiff::GeotiffWriter::setMapFilePath | ( | const std::string & | mapFilePath | ) |  | 
      
 
 
◆ setupImageSize()
      
        
          | void hector_geotiff::GeotiffWriter::setupImageSize | ( |  | ) |  | 
      
 
 
◆ setupTransforms()
      
        
          | bool hector_geotiff::GeotiffWriter::setupTransforms | ( | const nav_msgs::OccupancyGrid & | map | ) |  | 
      
 
 
◆ setUseUtcTimeSuffix()
      
        
          | void hector_geotiff::GeotiffWriter::setUseUtcTimeSuffix | ( | bool | useSuffix | ) |  | 
      
 
 
◆ transformPainterToImgCoords()
  
  | 
        
          | void hector_geotiff::GeotiffWriter::transformPainterToImgCoords | ( | QPainter & | painter | ) |  |  | protected | 
 
 
◆ writeGeotiffImage()
      
        
          | void hector_geotiff::GeotiffWriter::writeGeotiffImage | ( |  | ) |  | 
      
 
 
◆ app
  
  | 
        
          | QApplication* hector_geotiff::GeotiffWriter::app |  | protected | 
 
 
◆ cached_map_meta_data_
  
  | 
        
          | nav_msgs::MapMetaData hector_geotiff::GeotiffWriter::cached_map_meta_data_ |  | protected | 
 
 
◆ checkerboard_cache
  
  | 
        
          | QImage hector_geotiff::GeotiffWriter::checkerboard_cache |  | protected | 
 
 
◆ fake_argc_
  
  | 
        
          | int hector_geotiff::GeotiffWriter::fake_argc_ |  | protected | 
 
 
◆ fake_argv_
  
  | 
        
          | char** hector_geotiff::GeotiffWriter::fake_argv_ |  | protected | 
 
 
◆ geoTiffSizePixels
  
  | 
        
          | Eigen::Vector2i hector_geotiff::GeotiffWriter::geoTiffSizePixels |  | protected | 
 
 
◆ image
  
  | 
        
          | QImage hector_geotiff::GeotiffWriter::image |  | protected | 
 
 
◆ leftTopMarginMeters
  
  | 
        
          | Eigen::Vector2f hector_geotiff::GeotiffWriter::leftTopMarginMeters |  | protected | 
 
 
◆ map_draw_font_
  
  | 
        
          | QFont hector_geotiff::GeotiffWriter::map_draw_font_ |  | protected | 
 
 
◆ map_file_name_
  
  | 
        
          | std::string hector_geotiff::GeotiffWriter::map_file_name_ |  | protected | 
 
 
◆ map_file_path_
  
  | 
        
          | std::string hector_geotiff::GeotiffWriter::map_file_path_ |  | protected | 
 
 
◆ map_geo_transformer_
◆ mapEndInGeotiff
  
  | 
        
          | Eigen::Vector2f hector_geotiff::GeotiffWriter::mapEndInGeotiff |  | protected | 
 
 
◆ mapOrigInGeotiff
  
  | 
        
          | Eigen::Vector2f hector_geotiff::GeotiffWriter::mapOrigInGeotiff |  | protected | 
 
 
◆ maxCoordsMap
  
  | 
        
          | Eigen::Vector2i hector_geotiff::GeotiffWriter::maxCoordsMap |  | protected | 
 
 
◆ minCoordsMap
  
  | 
        
          | Eigen::Vector2i hector_geotiff::GeotiffWriter::minCoordsMap |  | protected | 
 
 
◆ origin
  
  | 
        
          | Eigen::Vector2f hector_geotiff::GeotiffWriter::origin |  | protected | 
 
 
◆ pixelsPerGeoTiffMeter
  
  | 
        
          | float hector_geotiff::GeotiffWriter::pixelsPerGeoTiffMeter |  | protected | 
 
 
◆ pixelsPerMapMeter
  
  | 
        
          | float hector_geotiff::GeotiffWriter::pixelsPerMapMeter |  | protected | 
 
 
◆ resolution
  
  | 
        
          | float hector_geotiff::GeotiffWriter::resolution |  | protected | 
 
 
◆ resolutionFactor
  
  | 
        
          | int hector_geotiff::GeotiffWriter::resolutionFactor |  | protected | 
 
 
◆ resolutionFactorf
  
  | 
        
          | float hector_geotiff::GeotiffWriter::resolutionFactorf |  | protected | 
 
 
◆ rightBottomMarginMeters
  
  | 
        
          | Eigen::Vector2f hector_geotiff::GeotiffWriter::rightBottomMarginMeters |  | protected | 
 
 
◆ rightBottomMarginPixels
  
  | 
        
          | Eigen::Vector2i hector_geotiff::GeotiffWriter::rightBottomMarginPixels |  | protected | 
 
 
◆ rightBottomMarginPixelsf
  
  | 
        
          | Eigen::Vector2f hector_geotiff::GeotiffWriter::rightBottomMarginPixelsf |  | protected | 
 
 
◆ sizeMap
  
  | 
        
          | Eigen::Vector2i hector_geotiff::GeotiffWriter::sizeMap |  | protected | 
 
 
◆ sizeMapf
  
  | 
        
          | Eigen::Vector2f hector_geotiff::GeotiffWriter::sizeMapf |  | protected | 
 
 
◆ totalMeters
  
  | 
        
          | Eigen::Vector2f hector_geotiff::GeotiffWriter::totalMeters |  | protected | 
 
 
◆ use_utc_time_suffix_
  
  | 
        
          | bool hector_geotiff::GeotiffWriter::use_utc_time_suffix_ |  | protected | 
 
 
◆ useCheckerboardCache
  
  | 
        
          | bool hector_geotiff::GeotiffWriter::useCheckerboardCache |  | protected | 
 
 
◆ world_geo_transformer_
◆ world_map_transformer_
The documentation for this class was generated from the following files: