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 <rtabmap/core/util3d.h>
00032 #include <rtabmap/core/Compression.h>
00033 #include <rtabmap/core/Graph.h>
00034 #include <rtabmap/utilite/ULogger.h>
00035 #include <rtabmap/utilite/UStl.h>
00036 #include <rtabmap/utilite/UTimer.h>
00037 #include <pcl_ros/transforms.h>
00038 #include <pcl_conversions/pcl_conversions.h>
00039 #include <nav_msgs/OccupancyGrid.h>
00040 #include <std_srvs/Empty.h>
00041
00042 using namespace rtabmap;
00043
00044 class MapAssembler
00045 {
00046
00047 public:
00048 MapAssembler() :
00049 cloudDecimation_(4),
00050 cloudMaxDepth_(4.0),
00051 cloudVoxelSize_(0.02),
00052 scanVoxelSize_(0.01),
00053 nodeFilteringAngle_(30),
00054 nodeFilteringRadius_(0.5),
00055 noiseFilterRadius_(0.0),
00056 noiseFilterMinNeighbors_(5),
00057 computeOccupancyGrid_(false),
00058 gridCellSize_(0.05),
00059 groundMaxAngle_(M_PI_4),
00060 clusterMinSize_(20),
00061 maxHeight_(0),
00062 occupancyMapSize_(0.0)
00063 {
00064 ros::NodeHandle pnh("~");
00065 pnh.param("cloud_decimation", cloudDecimation_, cloudDecimation_);
00066 pnh.param("cloud_max_depth", cloudMaxDepth_, cloudMaxDepth_);
00067 pnh.param("cloud_voxel_size", cloudVoxelSize_, cloudVoxelSize_);
00068 pnh.param("scan_voxel_size", scanVoxelSize_, scanVoxelSize_);
00069
00070 pnh.param("filter_radius", nodeFilteringRadius_, nodeFilteringRadius_);
00071 pnh.param("filter_angle", nodeFilteringAngle_, nodeFilteringAngle_);
00072
00073 pnh.param("noise_filter_radius", noiseFilterRadius_, noiseFilterRadius_);
00074 pnh.param("noise_filter_min_neighbors", noiseFilterMinNeighbors_, noiseFilterMinNeighbors_);
00075
00076 pnh.param("occupancy_grid", computeOccupancyGrid_, computeOccupancyGrid_);
00077 pnh.param("occupancy_cell_size", gridCellSize_, gridCellSize_);
00078 pnh.param("occupancy_ground_max_angle", groundMaxAngle_, groundMaxAngle_);
00079 pnh.param("occupancy_cluster_min_size", clusterMinSize_, clusterMinSize_);
00080 pnh.param("occupancy_max_height", maxHeight_, maxHeight_);
00081 pnh.param("occupancy_map_size", occupancyMapSize_, occupancyMapSize_);
00082
00083 UASSERT(gridCellSize_ > 0);
00084 UASSERT(maxHeight_ >= 0);
00085 UASSERT(occupancyMapSize_ >=0.0);
00086
00087 ros::NodeHandle nh;
00088 mapDataTopic_ = nh.subscribe("mapData", 1, &MapAssembler::mapDataReceivedCallback, this);
00089
00090 assembledMapClouds_ = nh.advertise<sensor_msgs::PointCloud2>("assembled_clouds", 1);
00091 assembledMapScans_ = nh.advertise<sensor_msgs::PointCloud2>("assembled_scans", 1);
00092 if(computeOccupancyGrid_)
00093 {
00094 occupancyMapPub_ = nh.advertise<nav_msgs::OccupancyGrid>("grid_projection_map", 1);
00095 }
00096
00097
00098 resetService_ = pnh.advertiseService("reset", &MapAssembler::reset, this);
00099 }
00100
00101 ~MapAssembler()
00102 {
00103 }
00104
00105 void mapDataReceivedCallback(const rtabmap_ros::MapDataConstPtr & msg)
00106 {
00107 UTimer timer;
00108 for(unsigned int i=0; i<msg->nodes.size(); ++i)
00109 {
00110 int id = msg->nodes[i].id;
00111 if(!uContains(rgbClouds_, id))
00112 {
00113 rtabmap::Transform localTransform = rtabmap_ros::transformFromGeometryMsg(msg->nodes[i].localTransform);
00114 if(!localTransform.isNull())
00115 {
00116 cv::Mat image, depth;
00117 float fx = msg->nodes[i].fx;
00118 float fy = msg->nodes[i].fy;
00119 float cx = msg->nodes[i].cx;
00120 float cy = msg->nodes[i].cy;
00121
00122
00123 rtabmap::CompressionThread ctImage(rtabmap_ros::compressedMatFromBytes(msg->nodes[i].image, false), true);
00124 rtabmap::CompressionThread ctDepth(rtabmap_ros::compressedMatFromBytes(msg->nodes[i].depth, false), true);
00125 ctImage.start();
00126 ctDepth.start();
00127 ctImage.join();
00128 ctDepth.join();
00129 image = ctImage.getUncompressedData();
00130 depth = ctDepth.getUncompressedData();
00131
00132 if(!image.empty() && !depth.empty() && fx > 0.0f && fy > 0.0f && cx >= 0.0f && cy >= 0.0f)
00133 {
00134 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
00135 if(depth.type() == CV_8UC1)
00136 {
00137 cloud = util3d::cloudFromStereoImages(image, depth, cx, cy, fx, fy, cloudDecimation_);
00138 }
00139 else
00140 {
00141 cloud = util3d::cloudFromDepthRGB(image, depth, cx, cy, fx, fy, cloudDecimation_);
00142 }
00143
00144 if(cloud->size() && cloudMaxDepth_ > 0)
00145 {
00146 cloud = util3d::passThrough<pcl::PointXYZRGB>(cloud, "z", 0, cloudMaxDepth_);
00147 }
00148 if(cloud->size() && noiseFilterRadius_ > 0.0 && noiseFilterMinNeighbors_ > 0)
00149 {
00150 pcl::IndicesPtr indices = rtabmap::util3d::radiusFiltering<pcl::PointXYZRGB>(cloud, noiseFilterRadius_, noiseFilterMinNeighbors_);
00151 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZRGB>);
00152 pcl::copyPointCloud(*cloud, *indices, *tmp);
00153 cloud = tmp;
00154 }
00155 if(cloud->size() && cloudVoxelSize_ > 0)
00156 {
00157 cloud = util3d::voxelize<pcl::PointXYZRGB>(cloud, cloudVoxelSize_);
00158 }
00159
00160 if(cloud->size())
00161 {
00162 cloud = util3d::transformPointCloud<pcl::PointXYZRGB>(cloud, localTransform);
00163
00164
00165 rgbClouds_.insert(std::make_pair(id, cloud));
00166
00167 if(computeOccupancyGrid_)
00168 {
00169 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudClipped = cloud;
00170 if(cloudClipped->size() && maxHeight_ > 0)
00171 {
00172 cloudClipped = util3d::passThrough<pcl::PointXYZRGB>(cloudClipped, "z", std::numeric_limits<int>::min(), maxHeight_);
00173 }
00174 if(cloudClipped->size())
00175 {
00176 cloudClipped = util3d::voxelize<pcl::PointXYZRGB>(cloudClipped, gridCellSize_);
00177
00178 cv::Mat ground, obstacles;
00179 util3d::occupancy2DFromCloud3D<pcl::PointXYZRGB>(cloudClipped, ground, obstacles, gridCellSize_, groundMaxAngle_, clusterMinSize_);
00180 if(!ground.empty() || !obstacles.empty())
00181 {
00182 occupancyLocalMaps_.insert(std::make_pair(id, std::make_pair(ground, obstacles)));
00183 }
00184 }
00185
00186 }
00187 }
00188 }
00189 }
00190 }
00191
00192 if(!uContains(scans_, id) && msg->nodes[i].laserScan.size())
00193 {
00194 cv::Mat laserScan = rtabmap::uncompressData(msg->nodes[i].laserScan);
00195 if(!laserScan.empty())
00196 {
00197 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::laserScanToPointCloud(laserScan);
00198 if(cloud->size() && scanVoxelSize_ > 0)
00199 {
00200 cloud = util3d::voxelize<pcl::PointXYZ>(cloud, scanVoxelSize_);
00201 }
00202 if(cloud->size())
00203 {
00204 scans_.insert(std::make_pair(id, cloud));
00205 }
00206 }
00207 }
00208 }
00209
00210
00211 std::map<int, Transform> poses;
00212 for(unsigned int i=0; i<msg->graph.nodeIds.size() && i<msg->graph.poses.size(); ++i)
00213 {
00214 poses.insert(std::make_pair(msg->graph.nodeIds[i], rtabmap_ros::transformFromPoseMsg(msg->graph.poses[i])));
00215 }
00216 if(nodeFilteringAngle_ > 0.0 && nodeFilteringRadius_ > 0.0)
00217 {
00218 poses = rtabmap::graph::radiusPosesFiltering(poses, nodeFilteringRadius_, nodeFilteringAngle_*CV_PI/180.0);
00219 }
00220
00221 if(assembledMapClouds_.getNumSubscribers())
00222 {
00223
00224 pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledCloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00225
00226 for(std::map<int, Transform>::iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00227 {
00228 std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr >::iterator jter = rgbClouds_.find(iter->first);
00229 if(jter != rgbClouds_.end())
00230 {
00231 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed = util3d::transformPointCloud<pcl::PointXYZRGB>(jter->second, iter->second);
00232 *assembledCloud+=*transformed;
00233 }
00234 }
00235
00236 if(assembledCloud->size())
00237 {
00238 if(cloudVoxelSize_ > 0)
00239 {
00240 assembledCloud = util3d::voxelize<pcl::PointXYZRGB>(assembledCloud,cloudVoxelSize_);
00241 }
00242
00243 sensor_msgs::PointCloud2::Ptr cloudMsg(new sensor_msgs::PointCloud2);
00244 pcl::toROSMsg(*assembledCloud, *cloudMsg);
00245 cloudMsg->header.stamp = ros::Time::now();
00246 cloudMsg->header.frame_id = msg->header.frame_id;
00247 assembledMapClouds_.publish(cloudMsg);
00248 }
00249 }
00250
00251 if(assembledMapScans_.getNumSubscribers())
00252 {
00253
00254 pcl::PointCloud<pcl::PointXYZ>::Ptr assembledCloud(new pcl::PointCloud<pcl::PointXYZ>);
00255
00256 for(std::map<int, Transform>::iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00257 {
00258 std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr >::iterator jter = scans_.find(iter->first);
00259 if(jter != scans_.end())
00260 {
00261 pcl::PointCloud<pcl::PointXYZ>::Ptr transformed = util3d::transformPointCloud<pcl::PointXYZ>(jter->second, iter->second);
00262 *assembledCloud+=*transformed;
00263 }
00264 }
00265
00266 if(assembledCloud->size())
00267 {
00268 if(scanVoxelSize_ > 0)
00269 {
00270 assembledCloud = util3d::voxelize<pcl::PointXYZ>(assembledCloud, scanVoxelSize_);
00271 }
00272
00273 sensor_msgs::PointCloud2::Ptr cloudMsg(new sensor_msgs::PointCloud2);
00274 pcl::toROSMsg(*assembledCloud, *cloudMsg);
00275 cloudMsg->header.stamp = ros::Time::now();
00276 cloudMsg->header.frame_id = msg->header.frame_id;
00277 assembledMapScans_.publish(cloudMsg);
00278 }
00279 }
00280
00281 if(occupancyMapPub_.getNumSubscribers())
00282 {
00283
00284 float xMin=0.0f, yMin=0.0f;
00285 cv::Mat pixels = util3d::create2DMapFromOccupancyLocalMaps(
00286 poses,
00287 occupancyLocalMaps_,
00288 gridCellSize_, xMin, yMin,
00289 occupancyMapSize_);
00290
00291 if(!pixels.empty())
00292 {
00293
00294 nav_msgs::OccupancyGrid map;
00295 map.info.resolution = gridCellSize_;
00296 map.info.origin.position.x = 0.0;
00297 map.info.origin.position.y = 0.0;
00298 map.info.origin.position.z = 0.0;
00299 map.info.origin.orientation.x = 0.0;
00300 map.info.origin.orientation.y = 0.0;
00301 map.info.origin.orientation.z = 0.0;
00302 map.info.origin.orientation.w = 1.0;
00303
00304 map.info.width = pixels.cols;
00305 map.info.height = pixels.rows;
00306 map.info.origin.position.x = xMin;
00307 map.info.origin.position.y = yMin;
00308 map.data.resize(map.info.width * map.info.height);
00309
00310 memcpy(map.data.data(), pixels.data, map.info.width * map.info.height);
00311
00312 map.header.frame_id = msg->header.frame_id;
00313 map.header.stamp = ros::Time::now();
00314
00315 occupancyMapPub_.publish(map);
00316 }
00317 }
00318 ROS_INFO("Processing data %fs", timer.ticks());
00319 }
00320
00321 bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00322 {
00323 ROS_INFO("map_assembler: reset!");
00324 occupancyLocalMaps_.clear();
00325 rgbClouds_.clear();
00326 scans_.clear();
00327 return true;
00328 }
00329
00330 private:
00331 int cloudDecimation_;
00332 double cloudMaxDepth_;
00333 double cloudVoxelSize_;
00334 double scanVoxelSize_;
00335
00336 double nodeFilteringAngle_;
00337 double nodeFilteringRadius_;
00338
00339 double noiseFilterRadius_;
00340 double noiseFilterMinNeighbors_;
00341
00342 bool computeOccupancyGrid_;
00343 double gridCellSize_;
00344 double groundMaxAngle_;
00345 int clusterMinSize_;
00346 double maxHeight_;
00347 double occupancyMapSize_;
00348
00349 std::map<int, std::pair<cv::Mat, cv::Mat> > occupancyLocalMaps_;
00350
00351 ros::Subscriber mapDataTopic_;
00352
00353 ros::Publisher assembledMapClouds_;
00354 ros::Publisher assembledMapScans_;
00355 ros::Publisher occupancyMapPub_;
00356
00357 ros::ServiceServer resetService_;
00358
00359 std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > rgbClouds_;
00360 std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr > scans_;
00361 };
00362
00363
00364 int main(int argc, char** argv)
00365 {
00366 ros::init(argc, argv, "map_assembler");
00367 MapAssembler assembler;
00368 ros::spin();
00369 return 0;
00370 }