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