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
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <mongo_ros/message_collection.h>
00041 #include <ros/ros.h>
00042 #include <nav_msgs/OccupancyGrid.h>
00043 #include <nav_msgs/GetMap.h>
00044 #include <map_store/SaveMap.h>
00045
00046 #include <string>
00047 #include <sstream>
00048
00049 #include <uuid/uuid.h>
00050
00051 namespace mr=mongo_ros;
00052
00053 std::string session_id;
00054 mr::MessageCollection<nav_msgs::OccupancyGrid> *map_collection;
00055 ros::ServiceClient add_metadata_service_client;
00056 ros::ServiceClient dynamic_map_service_client;
00057
00058 std::string uuidGenerate() {
00059 uuid_t uuid;
00060 uuid_generate(uuid);
00061 char uuid_string[37];
00062 uuid_unparse_lower(uuid, uuid_string);
00063 return std::string(uuid_string);
00064 }
00065
00066 void onMapReceived(const nav_msgs::OccupancyGrid::ConstPtr& map_msg)
00067 {
00068 ROS_DEBUG("received map");
00069 std::string uuid_string = uuidGenerate();
00070 mr::Metadata metadata
00071 = mr::Metadata("uuid", uuid_string,
00072 "session_id", session_id);
00073
00074 map_collection->insert(*map_msg, metadata);
00075
00076 ROS_DEBUG("saved map");
00077 }
00078
00079 bool saveMap(map_store::SaveMap::Request &req,
00080 map_store::SaveMap::Response &res)
00081 {
00082 nav_msgs::GetMap srv;
00083 if (!dynamic_map_service_client.call(srv)) {
00084 ROS_ERROR("Dynamic map getter service call failed");
00085 return false;
00086 }
00087
00088 std::string uuid_string = uuidGenerate();
00089 mr::Metadata metadata
00090 = mr::Metadata("uuid", uuid_string,
00091 "session_id", session_id,
00092 "name", req.map_name);
00093
00094 ROS_DEBUG("Save map %d by %d @ %f as %s", srv.response.map.info.width,
00095 srv.response.map.info.height, srv.response.map.info.resolution, req.map_name.c_str());
00096 map_collection->insert(srv.response.map, metadata);
00097
00098 ROS_DEBUG("nameLastestMaps() service call done");
00099 return true;
00100 }
00101
00102 int main (int argc, char** argv)
00103 {
00104 ros::init(argc, argv, "map_saver");
00105 ros::NodeHandle nh;
00106
00107
00108 char buff[256];
00109 snprintf(buff, 256, "%f", ros::Time::now().toSec());
00110 session_id = std::string(buff);
00111
00112 map_collection = new mr::MessageCollection<nav_msgs::OccupancyGrid>("map_store", "maps");
00113
00114 ros::Subscriber map_subscriber = nh.subscribe("map", 1, onMapReceived);
00115
00116 ros::ServiceServer name_latest_map_service = nh.advertiseService("save_map", saveMap);
00117 dynamic_map_service_client = nh.serviceClient<nav_msgs::GetMap>("dynamic_map");
00118
00119 ROS_DEBUG("spinning.");
00120
00121 ros::spin();
00122 return 0;
00123 }