00001
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039 #include <octomap_ros/GetOctomap.h>
00040 #include <octomap_ros/conversions.h>
00041 #include <octomap/octomap.h>
00042 #include <fstream>
00043
00044 #define USAGE "\nUSAGE: octomap_saver <map.bt>\n" \
00045 " map.bt: filename of map to be saved\n"
00046
00047 using namespace std;
00048
00052 class MapSaver{
00053 public:
00054 MapSaver(const std::string& mapname){
00055 ros::NodeHandle n;
00056 const static std::string servname = "octomap_binary";
00057 ROS_INFO("Requesting the map from %s...", n.resolveName(servname).c_str());
00058 octomap_ros::GetOctomap::Request req;
00059 octomap_ros::GetOctomap::Response resp;
00060 while(n.ok() && !ros::service::call(servname, req, resp))
00061 {
00062 ROS_WARN("Request to %s failed; trying again...", n.resolveName(servname).c_str());
00063 usleep(1000000);
00064 }
00065
00066 if (n.ok()){
00067 ROS_INFO("Map received, saving to %s", mapname.c_str());
00068 ofstream mapfile(mapname.c_str(), ios_base::binary);
00069
00070 if (!mapfile.is_open()){
00071 ROS_ERROR("Could not open file %s for writing", mapname.c_str());
00072 } else {
00073
00074
00075
00076
00077
00078
00079 mapfile.write((char*)&resp.map.data[0], resp.map.data.size());
00080 mapfile.close();
00081 }
00082 }
00083 }
00084 };
00085
00086 int main(int argc, char** argv){
00087 ros::init(argc, argv, "octomap_saver");
00088 std::string mapFilename("");
00089 if (argc == 2)
00090 mapFilename = std::string(argv[1]);
00091 else{
00092 ROS_ERROR("%s", USAGE);
00093 exit(-1);
00094 }
00095
00096 try{
00097 MapSaver ms(mapFilename);
00098 }catch(std::runtime_error& e){
00099 ROS_ERROR("map_saver exception: %s", e.what());
00100 return -1;
00101 }
00102
00103 return 0;
00104 }
00105
00106