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