geotiff_writer.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Simulation, Systems Optimization and Robotics
00013 //       group, TU Darmstadt nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #ifndef _GEOTIFFWRITER_H__
00030 #define _GEOTIFFWRITER_H__
00031 
00032 #include "map_writer_interface.h"
00033 
00034 #include <Eigen/Geometry>
00035 
00036 #include <nav_msgs/OccupancyGrid.h>
00037 #include <nav_msgs/MapMetaData.h>
00038 
00039 #include <QtGui/QImage>
00040 #include <QtGui/QApplication>
00041 #include <QtGui/QFont>
00042 #include <QtGui/QPen>
00043 
00044 #include <hector_map_tools/HectorMapTools.h>
00045 
00046 
00047 namespace hector_geotiff{
00048 
00049 
00050 class GeotiffWriter : public MapWriterInterface
00051 {
00052   public:
00053   GeotiffWriter(bool useCheckerboardCacheIn = false);
00054   virtual ~GeotiffWriter();
00055 
00056   //setUsePrecalcGrid(bool usePrecalc, const Eigen::Vector2f& size);
00057 
00058   void setMapFileName(const std::string& mapFileName);
00059   void setMapFilePath(const std::string& mapFilePath);
00060   void setUseUtcTimeSuffix(bool useSuffix);
00061 
00062   void setupImageSize();
00063   bool setupTransforms(const nav_msgs::OccupancyGrid& map);
00064   void drawBackgroundCheckerboard();
00065   void drawMap(const nav_msgs::OccupancyGrid& map, bool draw_explored_space_grid = true);
00066   void drawObjectOfInterest(const Eigen::Vector2f& coords, const std::string& txt, const Color& color);
00067   inline virtual void drawPath(const Eigen::Vector3f& start, const std::vector<Eigen::Vector2f>& points){
00068       drawPath(start, points, 120,0,240);
00069   }
00070   void drawPath(const Eigen::Vector3f& start, const std::vector<Eigen::Vector2f>& points, int color_r, int color_g, int color_b);
00071   void drawCoords();
00072   std::string getBasePathAndFileName() const;
00073   void writeGeotiffImage();
00074 
00075 
00076 protected:
00077 
00078   void transformPainterToImgCoords(QPainter& painter);
00079   void drawCross(QPainter& painter, const Eigen::Vector2f& coords);
00080   void drawArrow(QPainter& painter);
00081   void drawCoordSystem(QPainter& painter);
00082 
00083   float resolution;
00084   Eigen::Vector2f origin;
00085 
00086   int resolutionFactor;
00087   float resolutionFactorf;
00088 
00089   bool useCheckerboardCache;
00090   bool use_utc_time_suffix_;
00091 
00092   float pixelsPerMapMeter;
00093   float pixelsPerGeoTiffMeter;
00094 
00095   Eigen::Vector2i minCoordsMap;
00096   Eigen::Vector2i maxCoordsMap;
00097 
00098   Eigen::Vector2i sizeMap;
00099   Eigen::Vector2f sizeMapf;
00100 
00101   Eigen::Vector2f rightBottomMarginMeters;
00102   Eigen::Vector2f rightBottomMarginPixelsf;
00103   Eigen::Vector2i rightBottomMarginPixels;
00104 
00105   Eigen::Vector2f leftTopMarginMeters;
00106 
00107   Eigen::Vector2f totalMeters;
00108 
00109   Eigen::Vector2i geoTiffSizePixels;
00110 
00111   Eigen::Vector2f mapOrigInGeotiff;
00112   Eigen::Vector2f mapEndInGeotiff;
00113 
00114   std::string map_file_name_;
00115   std::string map_file_path_;
00116 
00117   QImage image;
00118   QImage checkerboard_cache;
00119   QApplication* app;
00120   QFont map_draw_font_;
00121 
00122   HectorMapTools::CoordinateTransformer<float> world_map_transformer_;
00123   HectorMapTools::CoordinateTransformer<float> map_geo_transformer_;
00124   HectorMapTools::CoordinateTransformer<float> world_geo_transformer_;
00125 
00126   nav_msgs::MapMetaData cached_map_meta_data_;
00127 
00128   int fake_argc_;
00129   char** fake_argv_;
00130 };
00131 
00132 }
00133 
00134 #endif


hector_geotiff
Author(s): Stefan Kohlbrecher
autogenerated on Thu Jun 6 2019 20:12:34