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 #include <ros/ros.h>
00029 #include "rtabmap_ros/MapData.h"
00030 #include "rtabmap_ros/MsgConversion.h"
00031 #include "MapsManager.h"
00032 #include <rtabmap/core/util3d_transforms.h>
00033 #include <rtabmap/core/util3d.h>
00034 #include <rtabmap/core/util3d_filtering.h>
00035 #include <rtabmap/core/util3d_mapping.h>
00036 #include <rtabmap/core/Compression.h>
00037 #include <rtabmap/core/Graph.h>
00038 #include <rtabmap/utilite/ULogger.h>
00039 #include <rtabmap/utilite/UStl.h>
00040 #include <rtabmap/utilite/UTimer.h>
00041 #include <pcl_ros/transforms.h>
00042 #include <pcl_conversions/pcl_conversions.h>
00043 #include <nav_msgs/OccupancyGrid.h>
00044 #include <std_srvs/Empty.h>
00045
00046 using namespace rtabmap;
00047
00048 class MapAssembler
00049 {
00050
00051 public:
00052 MapAssembler() :
00053 mapsManager_(false)
00054 {
00055 ros::NodeHandle pnh("~");
00056
00057 ros::NodeHandle nh;
00058 mapDataTopic_ = nh.subscribe("mapData", 1, &MapAssembler::mapDataReceivedCallback, this);
00059
00060
00061 resetService_ = pnh.advertiseService("reset", &MapAssembler::reset, this);
00062 }
00063
00064 ~MapAssembler()
00065 {
00066 }
00067
00068 void mapDataReceivedCallback(const rtabmap_ros::MapDataConstPtr & msg)
00069 {
00070 UTimer timer;
00071
00072 std::map<int, Transform> poses;
00073 std::multimap<int, Link> constraints;
00074 Transform mapOdom;
00075 rtabmap_ros::mapGraphFromROS(msg->graph, poses, constraints, mapOdom);
00076 for(unsigned int i=0; i<msg->nodes.size(); ++i)
00077 {
00078 if(msg->nodes[i].image.size() ||
00079 msg->nodes[i].depth.size() ||
00080 msg->nodes[i].laserScan.size())
00081 {
00082 uInsert(nodes_, std::make_pair(msg->nodes[i].id, rtabmap_ros::nodeDataFromROS(msg->nodes[i])));
00083 }
00084 }
00085
00086
00087 if(poses.size() && nodes_.find(poses.rbegin()->first) != nodes_.end())
00088 {
00089 Signature tmpS = nodes_.at(poses.rbegin()->first);
00090 SensorData tmpData = tmpS.sensorData();
00091 tmpData.setId(-1);
00092 uInsert(nodes_, std::make_pair(-1, Signature(-1, -1, 0, tmpS.getStamp(), "", tmpS.getPose(), Transform(), tmpData)));
00093 poses.insert(std::make_pair(-1, poses.rbegin()->second));
00094 }
00095
00096
00097 poses = mapsManager_.updateMapCaches(
00098 poses,
00099 0,
00100 false,
00101 false,
00102 false,
00103 false,
00104 false,
00105 nodes_);
00106
00107 mapsManager_.publishMaps(poses, msg->header.stamp, msg->header.frame_id);
00108
00109 ROS_INFO("map_assembler: Publishing data = %fs", timer.ticks());
00110 }
00111
00112 bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00113 {
00114 ROS_INFO("map_assembler: reset!");
00115 mapsManager_.clear();
00116 return true;
00117 }
00118
00119 private:
00120 MapsManager mapsManager_;
00121 std::map<int, Signature> nodes_;
00122
00123 ros::Subscriber mapDataTopic_;
00124
00125 ros::ServiceServer resetService_;
00126 };
00127
00128
00129 int main(int argc, char** argv)
00130 {
00131 ros::init(argc, argv, "map_assembler");
00132 MapAssembler assembler;
00133 ros::spin();
00134 return 0;
00135 }