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 
00030 #include <ros/ros.h>
00031 #include <octomap_msgs/conversions.h>
00032 #include <octomap/octomap.h>
00033 #include <fstream>
00034 
00035 #include <octomap_msgs/GetOctomap.h>
00036 using octomap_msgs::GetOctomap;
00037 
00038 #define USAGE "\nUSAGE: octomap_saver [-f] <mapfile.[bt|ot]>\n" \
00039                 "  -f: Query for the full occupancy octree, instead of just the compact binary one\n" \
00040                 "  mapfile.bt: filename of map to be saved (.bt: binary tree, .ot: general octree)\n"
00041 
00042 using namespace std;
00043 using namespace octomap;
00044 
00045 class MapSaver{
00046 public:
00047   MapSaver(const std::string& mapname, bool full){
00048     ros::NodeHandle n;
00049     std::string servname = "octomap_binary";
00050     if (full)
00051       servname = "octomap_full";
00052     ROS_INFO("Requesting the map from %s...", n.resolveName(servname).c_str());
00053     GetOctomap::Request req;
00054     GetOctomap::Response resp;
00055     while(n.ok() && !ros::service::call(servname, req, resp))
00056     {
00057       ROS_WARN("Request to %s failed; trying again...", n.resolveName(servname).c_str());
00058       usleep(1000000);
00059     }
00060 
00061     if (n.ok()){ 
00062 
00063       AbstractOcTree* tree = octomap_msgs::msgToMap(resp.map);
00064       AbstractOccupancyOcTree* octree = NULL;
00065       if (tree){
00066         octree = dynamic_cast<AbstractOccupancyOcTree*>(tree);
00067       } else {
00068         ROS_ERROR("Error creating octree from received message");
00069         if (resp.map.id == "ColorOcTree")
00070           ROS_WARN("You requested a binary map for a ColorOcTree - this is currently not supported. Please add -f to request a full map");
00071       }
00072 
00073       if (octree){
00074         ROS_INFO("Map received (%zu nodes, %f m res), saving to %s", octree->size(), octree->getResolution(), mapname.c_str());
00075         
00076         std::string suffix = mapname.substr(mapname.length()-3, 3);
00077         if (suffix== ".bt"){ 
00078           if (!octree->writeBinary(mapname)){
00079             ROS_ERROR("Error writing to file %s", mapname.c_str());
00080           }
00081         } else if (suffix == ".ot"){ 
00082           if (!octree->write(mapname)){
00083             ROS_ERROR("Error writing to file %s", mapname.c_str());
00084           }
00085         } else{
00086           ROS_ERROR("Unknown file extension, must be either .bt or .ot");
00087         }
00088 
00089 
00090       } else{
00091         ROS_ERROR("Error reading OcTree from stream");
00092       }
00093 
00094       delete octree;
00095 
00096     }
00097   }
00098 };
00099 
00100 int main(int argc, char** argv){
00101   ros::init(argc, argv, "octomap_saver");
00102   std::string mapFilename("");
00103   bool fullmap = false;
00104   if (argc == 3 && strcmp(argv[1], "-f")==0){
00105     fullmap = true;
00106     mapFilename = std::string(argv[2]);
00107   } else if (argc == 2)
00108     mapFilename = std::string(argv[1]);
00109   else{
00110     ROS_ERROR("%s", USAGE);
00111     exit(1);
00112   }
00113 
00114   try{
00115     MapSaver ms(mapFilename, fullmap);
00116   }catch(std::runtime_error& e){
00117     ROS_ERROR("octomap_saver exception: %s", e.what());
00118     exit(2);
00119   }
00120 
00121   exit(0);
00122 }
00123 
00124