RAPP Platform  v0.6.0
RAPP Platform is a collection of ROS nodes and back-end processes that aim to deliver ready-to-use generic services to robots
 All Classes Namespaces Files Functions Variables Macros
map_saver.cpp
Go to the documentation of this file.
1 /*
2  * map_saver
3  * Copyright (c) 2008, Willow Garage, Inc.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the <ORGANIZATION> nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
31 #include <cstdio>
32 #include "ros/ros.h"
33 #include "ros/console.h"
34 #include "nav_msgs/GetMap.h"
35 #include "tf/LinearMath/Matrix3x3.h"
36 #include "geometry_msgs/Quaternion.h"
37 
38 using namespace std;
39 
44 {
45 
46  public:
47  MapGenerator(const std::string& mapname) : mapname_(mapname), saved_map_(false)
48  {
49  ros::NodeHandle n;
50  ROS_INFO("Waiting for the map");
51  map_sub_ = n.subscribe("map", 1, &MapGenerator::mapCallback, this);
52  }
53 
54  void mapCallback(const nav_msgs::OccupancyGridConstPtr& map)
55  {
56  ROS_INFO("Received a %d X %d map @ %.3f m/pix",
57  map->info.width,
58  map->info.height,
59  map->info.resolution);
60 
61 
62  std::string mapdatafile = mapname_ + ".pgm";
63  ROS_INFO("Writing map occupancy data to %s", mapdatafile.c_str());
64  FILE* out = fopen(mapdatafile.c_str(), "w");
65  if (!out)
66  {
67  ROS_ERROR("Couldn't save map file to %s", mapdatafile.c_str());
68  return;
69  }
70 
71  fprintf(out, "P5\n# CREATOR: Map_generator.cpp %.3f m/pix\n%d %d\n255\n",
72  map->info.resolution, map->info.width, map->info.height);
73  for(unsigned int y = 0; y < map->info.height; y++) {
74  for(unsigned int x = 0; x < map->info.width; x++) {
75  unsigned int i = x + (map->info.height - y - 1) * map->info.width;
76  if (map->data[i] == 0) { //occ [0,0.1)
77  fputc(254, out);
78  } else if (map->data[i] == +100) { //occ (0.65,1]
79  fputc(000, out);
80  } else { //occ [0.1,0.65]
81  fputc(205, out);
82  }
83  }
84  }
85 
86  fclose(out);
87 
88 
89  std::string mapmetadatafile = mapname_ + ".yaml";
90  ROS_INFO("Writing map occupancy data to %s", mapmetadatafile.c_str());
91  FILE* yaml = fopen(mapmetadatafile.c_str(), "w");
92 
93 
94  /*
95 resolution: 0.100000
96 origin: [0.000000, 0.000000, 0.000000]
97 #
98 negate: 0
99 occupied_thresh: 0.65
100 free_thresh: 0.196
101 
102  */
103 
104  geometry_msgs::Quaternion orientation = map->info.origin.orientation;
105  tf::Matrix3x3 mat(tf::Quaternion(orientation.x, orientation.y, orientation.z, orientation.w));
106  double yaw, pitch, roll;
107  mat.getEulerYPR(yaw, pitch, roll);
108 
109  fprintf(yaml, "image: %s\nresolution: %f\norigin: [%f, %f, %f]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n\n",
110  mapdatafile.c_str(), map->info.resolution, map->info.origin.position.x, map->info.origin.position.y, yaw);
111 
112  fclose(yaml);
113 
114  ROS_INFO("Done\n");
115  saved_map_ = true;
116  }
117 
118  std::string mapname_;
119  ros::Subscriber map_sub_;
121 
122 };
123 
124 #define USAGE "Usage: \n" \
125  " map_saver -h\n"\
126  " map_saver [-f <mapname>] [ROS remapping args]"
127 
128 int main(int argc, char** argv)
129 {
130  ros::init(argc, argv, "map_saver");
131  std::string mapname = "map";
132 
133  for(int i=1; i<argc; i++)
134  {
135  if(!strcmp(argv[i], "-h"))
136  {
137  puts(USAGE);
138  return 0;
139  }
140  else if(!strcmp(argv[i], "-f"))
141  {
142  if(++i < argc)
143  mapname = argv[i];
144  else
145  {
146  puts(USAGE);
147  return 1;
148  }
149  }
150  else
151  {
152  puts(USAGE);
153  return 1;
154  }
155  }
156 
157  MapGenerator mg(mapname);
158 
159  while(!mg.saved_map_ && ros::ok())
160  ros::spinOnce();
161 
162  return 0;
163 }
164 
165 
int main(int argc, char **argv)
Definition: map_saver.cpp:128
Map generation node.
Definition: map_saver.cpp:43
std::string mapname_
Definition: map_saver.cpp:118
#define USAGE
Definition: map_saver.cpp:124
ros::Subscriber map_sub_
Definition: map_saver.cpp:119
MapGenerator(const std::string &mapname)
Definition: map_saver.cpp:47
void mapCallback(const nav_msgs::OccupancyGridConstPtr &map)
Definition: map_saver.cpp:54