GridMapAssemblerNode.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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/Graph.h>
00033 #include <rtabmap/core/Compression.h>
00034 #include <rtabmap/utilite/ULogger.h>
00035 #include <rtabmap/utilite/UStl.h>
00036 #include <rtabmap/utilite/UTimer.h>
00037 #include <nav_msgs/OccupancyGrid.h>
00038 #include <nav_msgs/GetMap.h>
00039 #include <std_srvs/Empty.h>
00040 #include <pcl_ros/transforms.h>
00041 #include <pcl_conversions/pcl_conversions.h>
00042 
00043 using namespace rtabmap;
00044 
00045 class GridMapAssembler
00046 {
00047 
00048 public:
00049         GridMapAssembler() :
00050                 gridCellSize_(0.05), // meters
00051                 mapSize_(0), // meters
00052                 eroded_(false),
00053                 filterRadius_(0.5),
00054                 filterAngle_(30.0) // degrees
00055         {
00056                 ros::NodeHandle pnh("~");
00057                 pnh.param("cell_size", gridCellSize_, gridCellSize_); // m
00058                 pnh.param("map_size", mapSize_, mapSize_); // m
00059                 pnh.param("filter_radius", filterRadius_, filterRadius_);
00060                 pnh.param("filter_angle", filterAngle_, filterAngle_);
00061                 pnh.param("eroded", eroded_, eroded_);
00062 
00063                 UASSERT(gridCellSize_ > 0.0);
00064                 UASSERT(mapSize_ >= 0.0);
00065 
00066                 ros::NodeHandle nh;
00067                 mapDataTopic_ = nh.subscribe("mapData", 1, &GridMapAssembler::mapDataReceivedCallback, this);
00068 
00069                 gridMap_ = nh.advertise<nav_msgs::OccupancyGrid>("grid_map", 1);
00070 
00071                 //private service
00072                 getMapService_ = pnh.advertiseService("get_map", &GridMapAssembler::getGridMapCallback, this);
00073                 resetService_ = pnh.advertiseService("reset", &GridMapAssembler::reset, this);
00074         }
00075 
00076         ~GridMapAssembler()
00077         {
00078         }
00079 
00080         void mapDataReceivedCallback(const rtabmap_ros::MapDataConstPtr & msg)
00081         {
00082                 UTimer timer;
00083                 for(unsigned int i=0; i<msg->nodes.size(); ++i)
00084                 {
00085                         if(!uContains(gridMaps_, msg->nodes[i].id) && msg->nodes[i].laserScan.size())
00086                         {
00087                                 cv::Mat laserScan = rtabmap::uncompressData(msg->nodes[i].laserScan);
00088                                 if(!laserScan.empty())
00089                                 {
00090                                         cv::Mat ground, obstacles;
00091                                         util3d::occupancy2DFromLaserScan(laserScan, ground, obstacles, gridCellSize_);
00092 
00093                                         if(!ground.empty() || !obstacles.empty())
00094                                         {
00095                                                 gridMaps_.insert(std::make_pair(msg->nodes[i].id, std::make_pair(ground, obstacles)));
00096                                         }
00097                                 }
00098                         }
00099                 }
00100 
00101                 std::map<int, Transform> poses;
00102                 for(unsigned int i=0; i<msg->graph.nodeIds.size() && i<msg->graph.poses.size(); ++i)
00103                 {
00104                         poses.insert(std::make_pair(msg->graph.nodeIds[i], rtabmap_ros::transformFromPoseMsg(msg->graph.poses[i])));
00105                 }
00106 
00107                 if(filterRadius_ > 0.0 && filterAngle_ > 0.0)
00108                 {
00109                         poses = rtabmap::graph::radiusPosesFiltering(poses, filterRadius_, filterAngle_*CV_PI/180.0);
00110                 }
00111 
00112                 if(gridMap_.getNumSubscribers())
00113                 {
00114                         // create the map
00115                         float xMin=0.0f, yMin=0.0f;
00116                         //cv::Mat pixels = util3d::create2DMap(poses, scans_, gridCellSize_, gridUnknownSpaceFilled_, xMin, yMin, mapSize_);
00117                         cv::Mat pixels = util3d::create2DMapFromOccupancyLocalMaps(
00118                                                         poses,
00119                                                         gridMaps_,
00120                                                         gridCellSize_,
00121                                                         xMin, yMin,
00122                                                         mapSize_,
00123                                                         eroded_);
00124 
00125                         if(!pixels.empty())
00126                         {
00127                                 //init
00128                                 map_.info.resolution = gridCellSize_;
00129                                 map_.info.origin.position.x = 0.0;
00130                                 map_.info.origin.position.y = 0.0;
00131                                 map_.info.origin.position.z = 0.0;
00132                                 map_.info.origin.orientation.x = 0.0;
00133                                 map_.info.origin.orientation.y = 0.0;
00134                                 map_.info.origin.orientation.z = 0.0;
00135                                 map_.info.origin.orientation.w = 1.0;
00136 
00137                                 map_.info.width = pixels.cols;
00138                                 map_.info.height = pixels.rows;
00139                                 map_.info.origin.position.x = xMin;
00140                                 map_.info.origin.position.y = yMin;
00141                                 map_.data.resize(map_.info.width * map_.info.height);
00142 
00143                                 memcpy(map_.data.data(), pixels.data, map_.info.width * map_.info.height);
00144 
00145                                 map_.header.frame_id = msg->header.frame_id;
00146                                 map_.header.stamp = ros::Time::now();
00147 
00148                                 gridMap_.publish(map_);
00149                                 ROS_INFO("Grid Map published [%d,%d] (%fs)", pixels.cols, pixels.rows, timer.ticks());
00150                         }
00151                 }
00152         }
00153 
00154         bool getGridMapCallback(nav_msgs::GetMap::Request  &req, nav_msgs::GetMap::Response &res)
00155         {
00156                 if(map_.data.size())
00157                 {
00158                         res.map = map_;
00159                         return true;
00160                 }
00161                 return false;
00162         }
00163 
00164         bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00165         {
00166                 ROS_INFO("grid_map_assembler: reset!");
00167                 gridMaps_.clear();
00168                 map_ = nav_msgs::OccupancyGrid();
00169                 return true;
00170         }
00171 
00172 private:
00173         double gridCellSize_;
00174         double mapSize_;
00175         bool eroded_;
00176         double filterRadius_;
00177         double filterAngle_;
00178 
00179         ros::Subscriber mapDataTopic_;
00180 
00181         ros::Publisher gridMap_;
00182 
00183         ros::ServiceServer getMapService_;
00184         ros::ServiceServer resetService_;
00185 
00186         std::map<int, std::pair<cv::Mat, cv::Mat> > gridMaps_; //<ground,obstacles>
00187 
00188         nav_msgs::OccupancyGrid map_;
00189 };
00190 
00191 
00192 int main(int argc, char** argv)
00193 {
00194         ros::init(argc, argv, "grid_map_assembler");
00195         GridMapAssembler assembler;
00196         ros::spin();
00197         return 0;
00198 }


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:24