00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2014, Zhi Yan. 00006 * Copyright (c) 2015-2016, Jiri Horner. 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions 00011 * are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above 00016 * copyright notice, this list of conditions and the following 00017 * disclaimer in the documentation and/or other materials provided 00018 * with the distribution. 00019 * * Neither the name of the Jiri Horner nor the names of its 00020 * contributors may be used to endorse or promote products derived 00021 * from this software without specific prior written permission. 00022 * 00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00024 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00025 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00026 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00027 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00028 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00029 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00030 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00031 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00032 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00033 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 * POSSIBILITY OF SUCH DAMAGE. 00035 * 00036 *********************************************************************/ 00037 00038 #ifndef MAP_MERGE_H_ 00039 #define MAP_MERGE_H_ 00040 00041 #include <vector> 00042 #include <unordered_map> 00043 #include <mutex> 00044 #include <forward_list> 00045 00046 #include <boost/thread.hpp> 00047 00048 #include <ros/ros.h> 00049 #include <geometry_msgs/Pose.h> 00050 #include <nav_msgs/OccupancyGrid.h> 00051 #include <map_msgs/OccupancyGridUpdate.h> 00052 00053 namespace map_merge 00054 { 00055 struct PosedMap { 00056 std::mutex mutex; 00057 00058 geometry_msgs::Pose initial_pose; 00059 nav_msgs::OccupancyGrid map; 00060 00061 ros::Subscriber map_sub; 00062 ros::Subscriber map_updates_sub; 00063 }; 00064 00065 class MapMerging 00066 { 00067 private: 00068 ros::NodeHandle node_; 00069 00070 /* parameters */ 00071 double merging_rate_; 00072 double discovery_rate_; 00073 double estimation_rate_; 00074 double confidence_treshold_; 00075 std::string robot_map_topic_; 00076 std::string robot_map_updates_topic_; 00077 std::string robot_namespace_; 00078 bool have_initial_poses_; 00079 00080 /* publisher */ 00081 nav_msgs::OccupancyGrid merged_map_; 00082 ros::Publisher merged_map_publisher_; 00083 00084 // maps robots namespaces to maps. does not own 00085 std::unordered_map<std::string, PosedMap*> robots_; 00086 // owns maps -- iterator safe 00087 std::forward_list<PosedMap> maps_; 00088 size_t maps_size_; 00089 // does not own. view of only grids from PosedMaps for merging 00090 typedef std::vector<std::reference_wrapper<nav_msgs::OccupancyGrid>> 00091 grids_view_t; 00092 // always contains all grids 00093 grids_view_t all_grids_view_; 00094 // aplicable only when estimations is on, will contain only grids which poses 00095 // could be properly estimated 00096 grids_view_t estimated_grids_view_; 00097 // this must be locked exclusively when modifying grid_view_ or changing 00098 // metadata (esp. size!) of OccupancyGrids inside. This could otherwise break 00099 // horribly because merging algorithm needs to compute merged map size first. 00100 boost::shared_mutex merging_mutex_; 00101 00102 std::string robotNameFromTopic(const std::string& topic); 00103 bool isRobotMapTopic(const ros::master::TopicInfo& topic); 00104 bool getInitPose(const std::string& name, geometry_msgs::Pose& pose); 00105 00106 void fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr& msg, 00107 PosedMap& map); 00108 void partialMapUpdate(const map_msgs::OccupancyGridUpdate::ConstPtr& msg, 00109 PosedMap& map); 00110 00111 public: 00112 MapMerging(); 00113 00114 void spin(); 00115 void executetopicSubscribing(); 00116 void executemapMerging(); 00117 void executeposeEstimation(); 00118 00119 void topicSubscribing(); 00120 void mapMerging(); 00125 void poseEstimation(); 00126 }; 00127 00128 } // namespace map_merge 00129 00130 #endif /* MAP_MERGE_H_ */