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