33 #include "ros/console.h"
34 #include "nav_msgs/GetMap.h"
35 #include "tf/LinearMath/Matrix3x3.h"
36 #include "geometry_msgs/Quaternion.h"
47 MapGenerator(
const std::string& mapname) : mapname_(mapname), saved_map_(false)
50 ROS_INFO(
"Waiting for the map");
56 ROS_INFO(
"Received a %d X %d map @ %.3f m/pix",
59 map->info.resolution);
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");
67 ROS_ERROR(
"Couldn't save map file to %s", mapdatafile.c_str());
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) {
78 }
else if (map->data[i] == +100) {
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");
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);
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);
124 #define USAGE "Usage: \n" \
126 " map_saver [-f <mapname>] [ROS remapping args]"
128 int main(
int argc,
char** argv)
130 ros::init(argc, argv,
"map_saver");
131 std::string mapname =
"map";
133 for(
int i=1; i<argc; i++)
135 if(!strcmp(argv[i],
"-h"))
140 else if(!strcmp(argv[i],
"-f"))
int main(int argc, char **argv)
MapGenerator(const std::string &mapname)
void mapCallback(const nav_msgs::OccupancyGridConstPtr &map)