geotiff_writer.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef _GEOTIFFWRITER_H__
30 #define _GEOTIFFWRITER_H__
31 
32 #include "map_writer_interface.h"
33 
34 #include <Eigen/Geometry>
35 
36 #include <nav_msgs/OccupancyGrid.h>
37 #include <nav_msgs/MapMetaData.h>
38 
39 #include <QtGui/QImage>
40 #include <QtGui/QApplication>
41 #include <QtGui/QFont>
42 #include <QtGui/QPen>
43 
45 
46 
47 namespace hector_geotiff{
48 
49 
51 {
52  public:
53  GeotiffWriter(bool useCheckerboardCacheIn = false);
54  virtual ~GeotiffWriter();
55 
56  //setUsePrecalcGrid(bool usePrecalc, const Eigen::Vector2f& size);
57 
58  void setMapFileName(const std::string& mapFileName);
59  void setMapFilePath(const std::string& mapFilePath);
60  void setUseUtcTimeSuffix(bool useSuffix);
61 
62  void setupImageSize();
63  bool setupTransforms(const nav_msgs::OccupancyGrid& map);
65  void drawMap(const nav_msgs::OccupancyGrid& map, bool draw_explored_space_grid = true);
66  void drawObjectOfInterest(const Eigen::Vector2f& coords, const std::string& txt, const Color& color);
67  inline virtual void drawPath(const Eigen::Vector3f& start, const std::vector<Eigen::Vector2f>& points){
68  drawPath(start, points, 120,0,240);
69  }
70  void drawPath(const Eigen::Vector3f& start, const std::vector<Eigen::Vector2f>& points, int color_r, int color_g, int color_b);
71  void drawCoords();
72  std::string getBasePathAndFileName() const;
73  void writeGeotiffImage();
74 
75 
76 protected:
77 
78  void transformPainterToImgCoords(QPainter& painter);
79  void drawCross(QPainter& painter, const Eigen::Vector2f& coords);
80  void drawArrow(QPainter& painter);
81  void drawCoordSystem(QPainter& painter);
82 
83  float resolution;
84  Eigen::Vector2f origin;
85 
88 
91 
94 
95  Eigen::Vector2i minCoordsMap;
96  Eigen::Vector2i maxCoordsMap;
97 
98  Eigen::Vector2i sizeMap;
99  Eigen::Vector2f sizeMapf;
100 
101  Eigen::Vector2f rightBottomMarginMeters;
102  Eigen::Vector2f rightBottomMarginPixelsf;
103  Eigen::Vector2i rightBottomMarginPixels;
104 
105  Eigen::Vector2f leftTopMarginMeters;
106 
107  Eigen::Vector2f totalMeters;
108 
109  Eigen::Vector2i geoTiffSizePixels;
110 
111  Eigen::Vector2f mapOrigInGeotiff;
112  Eigen::Vector2f mapEndInGeotiff;
113 
114  std::string map_file_name_;
115  std::string map_file_path_;
116 
117  QImage image;
119  QApplication* app;
121 
125 
126  nav_msgs::MapMetaData cached_map_meta_data_;
127 
129  char** fake_argv_;
130 };
131 
132 }
133 
134 #endif
Eigen::Vector2f rightBottomMarginPixelsf
HectorMapTools::CoordinateTransformer< float > world_map_transformer_
ROSCPP_DECL void start()
void drawMap(const nav_msgs::OccupancyGrid &map, bool draw_explored_space_grid=true)
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)
void drawObjectOfInterest(const Eigen::Vector2f &coords, const std::string &txt, const Color &color)
bool setupTransforms(const nav_msgs::OccupancyGrid &map)
Eigen::Vector2f rightBottomMarginMeters
void drawCoordSystem(QPainter &painter)
void setMapFilePath(const std::string &mapFilePath)
std::string getBasePathAndFileName() const
nav_msgs::MapMetaData cached_map_meta_data_
void setMapFileName(const std::string &mapFileName)
void drawArrow(QPainter &painter)
void transformPainterToImgCoords(QPainter &painter)
HectorMapTools::CoordinateTransformer< float > world_geo_transformer_
HectorMapTools::CoordinateTransformer< float > map_geo_transformer_


hector_geotiff
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:38