geotiff_writer.cpp
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 #include <ros/console.h>
31 
32 #include <QtGui/QPainter>
33 #include <QtGui/QImageWriter>
34 #include <QtGui/QApplication>
35 #include <QtCore/QFile>
36 //#include <QtCore/QDateTime>
37 #include <QtCore/QTime>
38 #include <QtCore/QTextStream>
39 
40 namespace hector_geotiff{
41 
42 
43 GeotiffWriter::GeotiffWriter(bool useCheckerboardCacheIn)
44  : useCheckerboardCache(useCheckerboardCacheIn)
45  , use_utc_time_suffix_(true)
46 {
47  cached_map_meta_data_.height = -1;
48  cached_map_meta_data_.width = -1;
49  cached_map_meta_data_.resolution = -1.0f;
50 
51  fake_argc_ = 0;
52 
53  //Create a QApplication cause otherwise drawing text will crash
54  app = new QApplication(fake_argc_, fake_argv_, false);
55 
56  map_file_name_ = "";
57  map_file_path_ = "";
58 }
59 
61 {
62  delete app;
63 }
64 
65 void GeotiffWriter::setMapFileName(const std::string& mapFileName)
66 {
67  map_file_name_ = mapFileName;
68 
70  //QDateTime now (QDateTime::currentDateTimeUtc());
71  //std::string current_time_string = now.toString(Qt::ISODate).toStdString();
72  QTime now (QTime::currentTime());
73  std::string current_time_string = now.toString(Qt::ISODate).toStdString();
74 
75  map_file_name_ += "_" + current_time_string;
76  }
77 }
78 
79 void GeotiffWriter::setMapFilePath(const std::string& mapFilePath)
80 {
81  map_file_path_ = mapFilePath;
82 }
83 
85 {
86  use_utc_time_suffix_ = useSuffix;
87 }
88 
89 
90 bool GeotiffWriter::setupTransforms(const nav_msgs::OccupancyGrid& map)
91 {
92  resolution = static_cast<float>(map.info.resolution);
93  origin = Eigen::Vector2f(map.info.origin.position.x, map.info.origin.position.y);
94 
95  resolutionFactor = 3;
96  resolutionFactorf = static_cast<float>(resolutionFactor);
97 
98  pixelsPerMapMeter = 1.0f / map.info.resolution;
100 
101  minCoordsMap = Eigen::Vector2i::Zero();
102  maxCoordsMap = Eigen::Vector2i(map.info.width, map.info.height);
103 
104  if(!HectorMapTools::getMapExtends(map, minCoordsMap, maxCoordsMap)){
105  ROS_INFO("Cannot determine map extends!");
106  return false;
107  }
108 
109  sizeMap = Eigen::Vector2i(maxCoordsMap - minCoordsMap);
110  sizeMapf = ((maxCoordsMap - minCoordsMap).cast<float>());
111 
112 
113  rightBottomMarginMeters = Eigen::Vector2f(1.0f, 1.0f);
115  rightBottomMarginPixels = ((rightBottomMarginPixelsf.array() +0.5f).cast<int>());
116 
117  leftTopMarginMeters= Eigen::Vector2f(3.0f, 3.0f);
118 
120  //std::cout << "\n" << totalMeters;
121 
122  totalMeters.x() = ceil(totalMeters.x());
123  totalMeters.y() = ceil(totalMeters.y());
124  //std::cout << "\n" << totalMeters;
125 
126  geoTiffSizePixels = ( (totalMeters.array() * pixelsPerGeoTiffMeter).cast<int>());
127 
128 
131  //std::cout << "\n mapOrig\n" << mapOrigInGeotiff;
132  //std::cout << "\n mapOrig\n" << mapEndInGeotiff;
133 
134  world_map_transformer_.setTransforms(map);
135 
136  map_geo_transformer_.setTransformsBetweenCoordSystems(mapOrigInGeotiff,mapEndInGeotiff, minCoordsMap.cast<float>(),maxCoordsMap.cast<float>());
137 
138  /*
139  Eigen::Vector2f temp_zero_map_g (map_geo_transformer_.getC2Coords(Eigen::Vector2f::Zero()));
140 
141  Eigen::Vector2f temp_zero_map_g_floor (floor(temp_zero_map_g.x()), floor(temp_zero_map_g.x()));
142 
143  Eigen::Vector2f diff (temp_zero_map_g - temp_zero_map_g_floor);
144 
145  map*/
146 
147 
148  Eigen::Vector2f p1_w (Eigen::Vector2f::Zero());
149  Eigen::Vector2f p2_w (Eigen::Vector2f(100.0f, 100.0f));
150 
151  Eigen::Vector2f p1_m (world_map_transformer_.getC2Coords(p1_w));
152  Eigen::Vector2f p2_m (world_map_transformer_.getC2Coords(p2_w));
153 
154  Eigen::Vector2f p1_g (map_geo_transformer_.getC2Coords(p1_m));
155  Eigen::Vector2f p2_g (map_geo_transformer_.getC2Coords(p2_m));
156 
157  world_geo_transformer_.setTransformsBetweenCoordSystems(p1_g, p2_g, p1_w, p2_w);
158 
159  map_draw_font_ = QFont();
160  map_draw_font_.setPixelSize(6*resolutionFactor);
161 
163 
164  if ((cached_map_meta_data_.height != map.info.height) ||
165  (cached_map_meta_data_.width != map.info.width) ||
166  (cached_map_meta_data_.resolution = map.info.resolution)){
167 
168  cached_map_meta_data_ = map.info;
169 
170  Eigen::Vector2f img_size (Eigen::Vector2f(map.info.width,map.info.height)* resolutionFactorf + (rightBottomMarginMeters + leftTopMarginMeters)*pixelsPerGeoTiffMeter );
171  checkerboard_cache = QImage(img_size.y(),img_size.x(), QImage::Format_RGB32);
172 
173  QPainter qPainter(&image);
174  transformPainterToImgCoords(qPainter);
175 
176  QBrush c1 = QBrush(QColor(226, 226, 227));
177  QBrush c2 = QBrush(QColor(237, 237, 238));
178  QRectF background_grid_tile(0.0f, 0.0f, pixelsPerGeoTiffMeter, pixelsPerGeoTiffMeter);
179 
180 
181  int xMaxGeo = geoTiffSizePixels[0];
182  int yMaxGeo = geoTiffSizePixels[1];
183 
184  for (int y = 0; y < yMaxGeo; ++y){
185  for (int x = 0; x < xMaxGeo; ++x){
186  //std::cout << "\n" << x << " " << y;
187 
188  if ((x + y) % 2 == 0) {
189  //qPainter.fillRect(background_grid_tile, c1);
190  qPainter.fillRect(static_cast<float>(x)*pixelsPerGeoTiffMeter,static_cast<float>(y)*pixelsPerGeoTiffMeter,pixelsPerGeoTiffMeter,pixelsPerGeoTiffMeter, c1);
191 
192  } else {
193  //qPainter.fillRect(background_grid_tile, c2);
194  qPainter.fillRect(static_cast<float>(x)*pixelsPerGeoTiffMeter,static_cast<float>(y)*pixelsPerGeoTiffMeter,pixelsPerGeoTiffMeter,pixelsPerGeoTiffMeter, c2);
195  }
196  //background_grid_tile.moveTo(QPointF(static_cast<float>(x)*pixelsPerGeoTiffMeter,static_cast<float>(y)*pixelsPerGeoTiffMeter));
197  }
198  }
199 
200  }
201 
202  }
203 
204  return true;
205 }
206 
208 {
209  bool painter_rotate = true;
210 
211  int xMaxGeo = geoTiffSizePixels[0];
212  int yMaxGeo = geoTiffSizePixels[1];
213 
214  if (!useCheckerboardCache){
215  if (painter_rotate){
216  image = QImage(yMaxGeo, xMaxGeo, QImage::Format_RGB32);
217  }else{
218  image = QImage(xMaxGeo, yMaxGeo, QImage::Format_RGB32);
219  }
220 
221  QPainter qPainter(&image);
222 
223  QBrush grey = QBrush(QColor(128, 128, 128));
224 
225  qPainter.fillRect(image.rect(), grey);
226 
227  }
228 }
229 
231 {
232  int xMaxGeo = geoTiffSizePixels[0];
233  int yMaxGeo = geoTiffSizePixels[1];
234 
235  bool painter_rotate = true;
236 
237  if (!useCheckerboardCache){
238 
239  QPainter qPainter(&image);
240 
241  if (painter_rotate){
242  transformPainterToImgCoords(qPainter);
243  }
244 
245  //*********************** Background checkerboard pattern **********************
246  QBrush c1 = QBrush(QColor(226, 226, 227));
247  QBrush c2 = QBrush(QColor(237, 237, 238));
248  QRectF background_grid_tile(0.0f, 0.0f, pixelsPerGeoTiffMeter, pixelsPerGeoTiffMeter);
249 
250 
251 
252  for (int y = 0; y < yMaxGeo; ++y){
253  for (int x = 0; x < xMaxGeo; ++x){
254  //std::cout << "\n" << x << " " << y;
255 
256  if ((x + y) % 2 == 0) {
257  //qPainter.fillRect(background_grid_tile, c1);
258  qPainter.fillRect(static_cast<float>(x)*pixelsPerGeoTiffMeter,static_cast<float>(y)*pixelsPerGeoTiffMeter,pixelsPerGeoTiffMeter,pixelsPerGeoTiffMeter, c1);
259 
260  } else {
261  //qPainter.fillRect(background_grid_tile, c2);
262  qPainter.fillRect(static_cast<float>(x)*pixelsPerGeoTiffMeter,static_cast<float>(y)*pixelsPerGeoTiffMeter,pixelsPerGeoTiffMeter,pixelsPerGeoTiffMeter, c2);
263  }
264  //background_grid_tile.moveTo(QPointF(static_cast<float>(x)*pixelsPerGeoTiffMeter,static_cast<float>(y)*pixelsPerGeoTiffMeter));
265  }
266  }
267  }else{
269  }
270 }
271 
272 void GeotiffWriter::drawMap(const nav_msgs::OccupancyGrid& map, bool draw_explored_space_grid)
273 {
274  QPainter qPainter(&image);
275 
276  transformPainterToImgCoords(qPainter);
277 
278  //this->drawCoordSystem(qPainter);
279 
280  QRectF map_cell_grid_tile(0.0f, 0.0f, resolutionFactor, resolutionFactor);
281 
282  QBrush occupied_brush(QColor(0, 40, 120));
283  QBrush free_brush(QColor(255, 255, 255));
284  QBrush explored_space_grid_brush(QColor(190,190,191));
285 
286  int width = map.info.width;
287 
288  float explored_space_grid_resolution_pixels = pixelsPerGeoTiffMeter * 0.5f;
289 
290  float yGeo = 0.0f;
291  float currYLimit = 0.0f;
292 
293  bool drawY = false;
294 
295  for (int y = minCoordsMap[1] ; y < maxCoordsMap[1]; ++y){
296 
297  float xGeo = 0.0f;
298 
299  if(yGeo >= currYLimit ){
300  drawY = true;
301  }
302 
303  float currXLimit = 0.0f;
304  bool drawX = false;
305 
306  for (int x = minCoordsMap[0] ; x < maxCoordsMap[0]; ++x){
307 
308  unsigned int i = y*width + x;
309 
310  int8_t data = map.data[i];
311 
312  if (xGeo >= currXLimit){
313  drawX = true;
314  }
315 
316  if (data == 0){
317 
318  Eigen::Vector2f coords(mapOrigInGeotiff + (Eigen::Vector2f(xGeo,yGeo)));
319  qPainter.fillRect(coords[0],coords[1],resolutionFactorf, resolutionFactorf, free_brush);
320 
321 
322  if (draw_explored_space_grid){
323  if (drawY){
324  qPainter.fillRect(coords[0],mapOrigInGeotiff.y() + currYLimit, resolutionFactorf, 1.0f, explored_space_grid_brush);
325  }
326 
327  if (drawX){
328  qPainter.fillRect(mapOrigInGeotiff.x() + currXLimit, coords[1], 1.0f, resolutionFactorf, explored_space_grid_brush);
329  }
330  }
331 
332  }else if(data == 100){
333  qPainter.fillRect(mapOrigInGeotiff.x()+xGeo, mapOrigInGeotiff.y()+yGeo,resolutionFactorf, resolutionFactorf, occupied_brush);
334  }
335 
336  if(drawX){
337  currXLimit += explored_space_grid_resolution_pixels;
338  drawX=false;
339  }
340 
341  xGeo+=resolutionFactorf;
342  }
343 
344  if(drawY){
345  drawY=false;
346  currYLimit += explored_space_grid_resolution_pixels;
347  }
348 
349  yGeo+= resolutionFactorf;
350  }
351 }
352 
353 void GeotiffWriter::drawObjectOfInterest(const Eigen::Vector2f& coords, const std::string& txt, const Color& color)
354 {
355  QPainter qPainter(&image);
356 
357  transformPainterToImgCoords(qPainter);
358 
359 
360  //qPainter.setPen(ellipse_pen_);
361 
362  Eigen::Vector2f map_coords (world_map_transformer_.getC2Coords(coords) );
363 
364  Eigen::Vector2f coords_g (world_geo_transformer_.getC2Coords(coords));
365 
366  qPainter.translate(coords_g[0],coords_g[1]);
367 
368  qPainter.rotate(90);
369 
370  qPainter.setRenderHint(QPainter::Antialiasing, true);
371 
372  float radius = pixelsPerGeoTiffMeter * 0.175f;
373 
374  QRectF ellipse_shape( - radius, - radius, radius*2.0f, radius*2.0f);
375  qPainter.save();
376 
377 
378  QBrush tmpBrush(QColor(color.r,color.g,color.b));
379  QPen tmpPen(Qt::NoPen);
380  qPainter.setBrush(tmpBrush);
381  qPainter.setPen(tmpPen);
382 
383  qPainter.drawEllipse(ellipse_shape);
384  qPainter.restore();
385 
386 
387  QString tmp (txt.c_str());
388  //tmp.setNum(number);
389 
390  if (tmp.length() < 2){
391  qPainter.setFont(map_draw_font_);
392  }else{
393  QFont tmp_font;
394  tmp_font.setPixelSize(3*resolutionFactor);
395  qPainter.setFont(tmp_font);
396  }
397 
398 
399 
400  qPainter.setPen(Qt::white);
401  qPainter.scale(-1.0,1.0);
402 
403  qPainter.drawText(ellipse_shape,Qt::AlignCenter , tmp);
404 }
405 
406 void GeotiffWriter::drawPath(const Eigen::Vector3f& start, const std::vector<Eigen::Vector2f>& points,int color_r, int color_g, int color_b)
407 {
408  QPainter qPainter(&image);
409 
410  transformPainterToImgCoords(qPainter);
411 
412  Eigen::Vector2f start_geo (world_geo_transformer_.getC2Coords(start.head<2>()));
413 
414 
415 
416  size_t size = points.size();
417 
418  QPolygonF polygon;
419  polygon.reserve(size);
420 
421  polygon.push_back(QPointF(start_geo.x(), start_geo.y()));
422 
423  for (size_t i = 0; i < size; ++i){
424  const Eigen::Vector2f vec (world_geo_transformer_.getC2Coords(points[i]));
425  polygon.push_back(QPointF(vec.x(), vec.y()));
426  }
427 
428  QPen pen(qPainter.pen());
429  pen.setColor(QColor(color_r, color_g, color_b));
430  pen.setWidth(3);
431 
432  qPainter.setPen(pen);
433 
434  //qPainter.setPen(QColor(120,0,240));
435 
436 
437  qPainter.drawPolyline(polygon);
438 
439  qPainter.save();
440  qPainter.translate(start_geo.x(), start_geo.y());
441  qPainter.rotate(start.z());
442  qPainter.setRenderHint(QPainter::Antialiasing, true);
443  drawArrow(qPainter);
444  //drawCoordSystem(qPainter);
445  qPainter.restore();
446 }
447 
449 {
450  return std::string (map_file_path_ +"/" + map_file_name_);
451 }
452 
454 {
455  //Only works with recent Qt versions
456  //QDateTime now (QDateTime::currentDateTimeUtc());
457  //std::string current_time_string = now.toString(Qt::ISODate).toStdString();
458 
459 
460  std::string complete_file_string ( map_file_path_ +"/" + map_file_name_ +".tif");
461  QImageWriter imageWriter(QString::fromStdString(complete_file_string));
462  imageWriter.setCompression(1);
463 
464  bool success = imageWriter.write(image);
465 
466  std::string tfw_file_name (map_file_path_ +"/" + map_file_name_ + ".tfw");
467  QFile tfwFile(QString::fromStdString(tfw_file_name));
468 
469  tfwFile.open(QIODevice::WriteOnly);
470 
471  QTextStream out(&tfwFile);
472 
473  float resolution_geo = resolution / resolutionFactorf;
474 
475  QString resolution_string;
476  resolution_string.setNum(resolution_geo,'f',10);
477 
478  //positive x resolution
479  out << resolution_string << "\n";
480 
481  QString zero_string;
482  zero_string.setNum(0.0f, 'f', 10);
483 
484  //rotation, translation
485  out << zero_string << "\n" << zero_string << "\n";
486 
487  //negative y resolution
488  out << "-" << resolution_string << "\n";
489 
490  QString top_left_string_x;
491  QString top_left_string_y;
492 
493  //Eigen::Vector2f zero_map_w = world_map_transformer_.getC1Coords(Eigen::Vector2f::Zero());
494  Eigen::Vector2f zero_geo_w (world_geo_transformer_.getC1Coords((geoTiffSizePixels.array()+1).cast<float>()));
495 
496 
497  top_left_string_x.setNum(-zero_geo_w.y(),'f',10);
498  top_left_string_y.setNum(zero_geo_w.x(),'f',10);
499 
500  out << top_left_string_x << "\n" << top_left_string_y << "\n";
501 
502  tfwFile.close();
503 
504  if(!success){
505  ROS_INFO("Writing image with file %s failed with error %s", complete_file_string.c_str(), imageWriter.errorString().toStdString().c_str());
506  }else{
507  ROS_INFO("Successfully wrote geotiff to %s", complete_file_string.c_str());
508  }
509 }
510 
512 {
513  painter.rotate(-90);
514  painter.translate(-geoTiffSizePixels.x(),geoTiffSizePixels.y());
515  painter.scale(1.0,-1.0);
516 }
517 
519 {
520  QPainter qPainter(&image);
521  qPainter.setFont(map_draw_font_);
522 
523  float arrowOffset = pixelsPerGeoTiffMeter * 0.15f;
524 
525  // MAP ORIENTATION
526  qPainter.setPen(QColor(0, 50, 140));
528  qPainter.drawLine(pixelsPerGeoTiffMeter * 2 / 5, pixelsPerGeoTiffMeter - 1, pixelsPerGeoTiffMeter * 3 / 5, pixelsPerGeoTiffMeter - 1);
529  qPainter.drawLine(pixelsPerGeoTiffMeter * 2 / 5, 2 * pixelsPerGeoTiffMeter, pixelsPerGeoTiffMeter * 3 / 5, 2 * pixelsPerGeoTiffMeter);
530 
531 
532 
533  qPainter.drawLine(pixelsPerGeoTiffMeter, 2 * pixelsPerGeoTiffMeter, 2 * pixelsPerGeoTiffMeter, 2 * pixelsPerGeoTiffMeter);
534  qPainter.drawLine(pixelsPerGeoTiffMeter, 2 * pixelsPerGeoTiffMeter, pixelsPerGeoTiffMeter + arrowOffset, 2 * pixelsPerGeoTiffMeter - arrowOffset);
535  qPainter.drawLine(pixelsPerGeoTiffMeter, 2 * pixelsPerGeoTiffMeter, pixelsPerGeoTiffMeter + arrowOffset, 2 * pixelsPerGeoTiffMeter + arrowOffset);
536 
537  qPainter.drawLine(2 * pixelsPerGeoTiffMeter, pixelsPerGeoTiffMeter, 2 * pixelsPerGeoTiffMeter, 2 * pixelsPerGeoTiffMeter);
538  qPainter.drawLine(2 * pixelsPerGeoTiffMeter, pixelsPerGeoTiffMeter, 2 * pixelsPerGeoTiffMeter + arrowOffset, pixelsPerGeoTiffMeter + arrowOffset);
539  qPainter.drawLine(2 * pixelsPerGeoTiffMeter, pixelsPerGeoTiffMeter, 2 * pixelsPerGeoTiffMeter - arrowOffset, pixelsPerGeoTiffMeter + arrowOffset);
540 
541  qPainter.drawText(0.6 * pixelsPerGeoTiffMeter, 1.6 * pixelsPerGeoTiffMeter, QString("1m"));
542 
543  qPainter.drawText(2.2 * pixelsPerGeoTiffMeter, 1.1 * pixelsPerGeoTiffMeter, QString("x"));
544  qPainter.drawText(1.2 * pixelsPerGeoTiffMeter, 1.8 * pixelsPerGeoTiffMeter, QString("y"));
545 
546  qPainter.drawText (0.5f*pixelsPerGeoTiffMeter,0.75f*pixelsPerGeoTiffMeter, QString((map_file_name_ + ".tif").c_str()));
547 }
548 
549 void GeotiffWriter::drawCross(QPainter& painter, const Eigen::Vector2f& coords)
550 {
551  painter.drawLine(QPointF(coords[0]-1.0f, coords[1]), QPointF(coords[0]+1.0f, coords[1]));
552  painter.drawLine(QPointF(coords[0] , coords[1]-1.0f), QPointF(coords[0], coords[1]+1.0f));
553 }
554 
555 void GeotiffWriter::drawArrow(QPainter& painter)
556 {
557  float tip_distance = pixelsPerGeoTiffMeter * 0.3f;
558 
559  QPolygonF polygon;
560 
561  polygon << QPointF(tip_distance, 0.0f) << QPointF(-tip_distance*0.5f, -tip_distance*0.5f) << QPointF(0.0f, 0.0f) << QPointF(-tip_distance*0.5f, tip_distance*0.5f);
562 
563  painter.save();
564 
565  QBrush tmpBrush(QColor(255,200,0));
566  QPen tmpPen(Qt::NoPen);
567  painter.setBrush(tmpBrush);
568  painter.setPen(tmpPen);
569 
570  painter.drawPolygon(polygon);
571 
572  painter.restore();
573 }
574 
575 void GeotiffWriter::drawCoordSystem(QPainter& painter)
576 {
577  painter.save();
578  QPointF zero_point (0.0f, 0.0f);
579  QPointF x_point (pixelsPerGeoTiffMeter, 0.0f);
580  QPointF y_point (0.0f, pixelsPerGeoTiffMeter);
581 
582  QPen tmp = painter.pen();
583  tmp.setWidth(5);
584  tmp.setColor(QColor(255.0,0.0,0.0));
585  //painter.setPen(QPen::setWidth(5));
586  painter.setPen(tmp);
587  painter.drawLine(zero_point,x_point);
588 
589  tmp.setColor(QColor(0,255,0));
590  painter.setPen(tmp);
591  painter.drawLine(zero_point,y_point);
592 
593  painter.restore();
594 }
595 
596 }
Eigen::Vector2f rightBottomMarginPixelsf
HectorMapTools::CoordinateTransformer< float > world_map_transformer_
void drawMap(const nav_msgs::OccupancyGrid &map, bool draw_explored_space_grid=true)
f
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)
#define ROS_INFO(...)
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)
static bool getMapExtends(const nav_msgs::OccupancyGrid &map, Eigen::Vector2i &topLeft, Eigen::Vector2i &bottomRight)
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