Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #include <cstdio>
00030 #include "ros/ros.h"
00031 #include "ros/console.h"
00032 #include "nav_msgs/GetMap.h"
00033 #include "geometry_msgs/Quaternion.h"
00034
00035 #include <Eigen/Geometry>
00036
00037 #include <QtGui/QApplication>
00038
00039 #include <hector_map_tools/HectorMapTools.h>
00040
00041 #include <geotiff_writer/geotiff_writer.h>
00042
00043 using namespace std;
00044
00045 namespace hector_geotiff{
00046
00050 class MapGenerator
00051 {
00052 public:
00053 MapGenerator(const std::string& mapname) : mapname_(mapname)
00054 {
00055 ros::NodeHandle n;
00056 ROS_INFO("Waiting for the map");
00057 map_sub_ = n.subscribe("map", 1, &MapGenerator::mapCallback, this);
00058 }
00059
00060 void mapCallback(const nav_msgs::OccupancyGridConstPtr& map)
00061 {
00062 ros::Time start_time (ros::Time::now());
00063
00064 geotiff_writer.setMapFileName(mapname_);
00065 geotiff_writer.setupTransforms(*map);
00066 geotiff_writer.drawBackgroundCheckerboard();
00067 geotiff_writer.drawMap(*map);
00068 geotiff_writer.drawCoords();
00069
00070 geotiff_writer.writeGeotiffImage();
00071
00072 ros::Duration elapsed_time (ros::Time::now() - start_time);
00073 ROS_INFO("GeoTiff created in %f seconds", elapsed_time.toSec());
00074 }
00075
00076 GeotiffWriter geotiff_writer;
00077
00078 std::string mapname_;
00079 ros::Subscriber map_sub_;
00080 };
00081
00082 }
00083
00084 #define USAGE "Usage: \n" \
00085 " geotiff_saver -h\n"\
00086 " geotiff_saver [-f <mapname>] [ROS remapping args]"
00087
00088 int main(int argc, char** argv)
00089 {
00090 ros::init(argc, argv, "map_saver");
00091 std::string mapname = "map";
00092
00093 for(int i=1; i<argc; i++)
00094 {
00095 if(!strcmp(argv[i], "-h"))
00096 {
00097 puts(USAGE);
00098 return 0;
00099 }
00100 else if(!strcmp(argv[i], "-f"))
00101 {
00102 if(++i < argc)
00103 mapname = argv[i];
00104 else
00105 {
00106 puts(USAGE);
00107 return 1;
00108 }
00109 }
00110 else
00111 {
00112 puts(USAGE);
00113 return 1;
00114 }
00115 }
00116
00117
00118
00119 hector_geotiff::MapGenerator mg(mapname);
00120
00121 ros::spin();
00122
00123 return 0;
00124 }
00125