map_merge.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, Zhi Yan.
6  * Copyright (c) 2015-2016, Jiri Horner.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the Jiri Horner nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  *********************************************************************/
37 
38 #ifndef MAP_MERGE_H_
39 #define MAP_MERGE_H_
40 
41 #include <atomic>
42 #include <forward_list>
43 #include <mutex>
44 #include <unordered_map>
45 
47 #include <geometry_msgs/Pose.h>
48 #include <map_msgs/OccupancyGridUpdate.h>
49 #include <nav_msgs/OccupancyGrid.h>
50 #include <ros/ros.h>
51 #include <boost/thread.hpp>
52 
53 namespace map_merge
54 {
55 struct MapSubscription {
56  // protects consistency of writable_map and readonly_map
57  // also protects reads and writes of shared_ptrs
58  std::mutex mutex;
59 
60  geometry_msgs::Transform initial_pose;
61  nav_msgs::OccupancyGrid::Ptr writable_map;
62  nav_msgs::OccupancyGrid::ConstPtr readonly_map;
63 
66 };
67 
68 class MapMerge
69 {
70 private:
72 
73  /* parameters */
74  double merging_rate_;
75  double discovery_rate_;
76  double estimation_rate_;
77  double confidence_threshold_;
78  std::string robot_map_topic_;
79  std::string robot_map_updates_topic_;
80  std::string robot_namespace_;
81  std::string world_frame_;
83 
84  // publishing
86  // maps robots namespaces to maps. does not own
87  std::unordered_map<std::string, MapSubscription*> robots_;
88  // owns maps -- iterator safe
89  std::forward_list<MapSubscription> subscriptions_;
91  boost::shared_mutex subscriptions_mutex_;
93  std::mutex pipeline_mutex_;
94 
95  std::string robotNameFromTopic(const std::string& topic);
96  bool isRobotMapTopic(const ros::master::TopicInfo& topic);
97  bool getInitPose(const std::string& name, geometry_msgs::Transform& pose);
98 
99  void fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr& msg,
100  MapSubscription& map);
101  void partialMapUpdate(const map_msgs::OccupancyGridUpdate::ConstPtr& msg,
102  MapSubscription& map);
103 
104 public:
105  MapMerge();
106 
107  void spin();
111 
113  void mapMerging();
118  void poseEstimation();
119 };
120 
121 } // namespace map_merge
122 
123 #endif /* MAP_MERGE_H_ */
map_merge::MapMerge::world_frame_
std::string world_frame_
Definition: map_merge.h:116
map_merge::MapSubscription::writable_map
nav_msgs::OccupancyGrid::Ptr writable_map
Definition: map_merge.h:131
map_merge::MapSubscription
Definition: map_merge.h:90
map_merge::MapMerge::isRobotMapTopic
bool isRobotMapTopic(const ros::master::TopicInfo &topic)
Definition: map_merge.cpp:336
combine_grids::MergingPipeline
Pipeline for merging overlapping occupancy grids.
Definition: merging_pipeline.h:89
map_merge::MapMerge::robot_namespace_
std::string robot_namespace_
Definition: map_merge.h:115
ros::Publisher
map_merge::MapMerge::executemapMerging
void executemapMerging()
Definition: map_merge.cpp:386
map_merge::MapMerge::subscriptions_size_
size_t subscriptions_size_
Definition: map_merge.h:125
map_merge::MapMerge::merging_rate_
double merging_rate_
Definition: map_merge.h:109
ros.h
map_merge::MapSubscription::mutex
std::mutex mutex
Definition: map_merge.h:128
map_merge::MapMerge::pipeline_
combine_grids::MergingPipeline pipeline_
Definition: map_merge.h:127
map_merge
Definition: map_merge.h:53
map_merge::MapMerge::MapMerge
MapMerge()
Definition: map_merge.cpp:82
map_merge::MapSubscription::readonly_map
nav_msgs::OccupancyGrid::ConstPtr readonly_map
Definition: map_merge.h:132
map_merge::MapMerge::topicSubscribing
void topicSubscribing()
Definition: map_merge.cpp:108
map_merge::MapMerge::robots_
std::unordered_map< std::string, MapSubscription * > robots_
Definition: map_merge.h:122
map_merge::MapMerge::robot_map_updates_topic_
std::string robot_map_updates_topic_
Definition: map_merge.h:114
map_merge::MapMerge::poseEstimation
void poseEstimation()
Estimates initial positions of grids.
Definition: map_merge.cpp:222
map_merge::MapMerge
Definition: map_merge.h:103
map_merge::MapMerge::estimation_rate_
double estimation_rate_
Definition: map_merge.h:111
map_merge::MapSubscription::map_sub
ros::Subscriber map_sub
Definition: map_merge.h:134
map_merge::MapMerge::robotNameFromTopic
std::string robotNameFromTopic(const std::string &topic)
Definition: map_merge.cpp:330
map_merge::MapMerge::pipeline_mutex_
std::mutex pipeline_mutex_
Definition: map_merge.h:128
map_merge::MapMerge::subscriptions_mutex_
boost::shared_mutex subscriptions_mutex_
Definition: map_merge.h:126
map_merge::MapMerge::executetopicSubscribing
void executetopicSubscribing()
Definition: map_merge.cpp:395
map_merge::MapMerge::robot_map_topic_
std::string robot_map_topic_
Definition: map_merge.h:113
map_merge::MapMerge::spin
void spin()
Definition: map_merge.cpp:419
merging_pipeline.h
map_merge::MapMerge::getInitPose
bool getInitPose(const std::string &name, geometry_msgs::Transform &pose)
Definition: map_merge.cpp:360
map_merge::MapMerge::discovery_rate_
double discovery_rate_
Definition: map_merge.h:110
map_merge::MapMerge::partialMapUpdate
void partialMapUpdate(const map_msgs::OccupancyGridUpdate::ConstPtr &msg, MapSubscription &map)
Definition: map_merge.cpp:257
map_merge::MapMerge::subscriptions_
std::forward_list< MapSubscription > subscriptions_
Definition: map_merge.h:124
map_merge::MapMerge::merged_map_publisher_
ros::Publisher merged_map_publisher_
Definition: map_merge.h:120
map_merge::MapMerge::confidence_threshold_
double confidence_threshold_
Definition: map_merge.h:112
map_merge::MapMerge::fullMapUpdate
void fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr &msg, MapSubscription &map)
Definition: map_merge.cpp:242
ros::master::TopicInfo
map_merge::MapSubscription::initial_pose
geometry_msgs::Transform initial_pose
Definition: map_merge.h:130
map_merge::MapMerge::have_initial_poses_
bool have_initial_poses_
Definition: map_merge.h:117
map_merge::MapMerge::executeposeEstimation
void executeposeEstimation()
Definition: map_merge.cpp:404
map_merge::MapMerge::mapMerging
void mapMerging()
Definition: map_merge.cpp:181
ros::NodeHandle
ros::Subscriber
map_merge::MapMerge::node_
ros::NodeHandle node_
Definition: map_merge.h:106
map_merge::MapSubscription::map_updates_sub
ros::Subscriber map_updates_sub
Definition: map_merge.h:135


map_merge
Author(s): Jiri Horner
autogenerated on Wed Mar 2 2022 00:32:15