map_merge.cpp
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 #include <thread>
39 
40 #include <map_merge/map_merge.h>
41 #include <ros/assert.h>
42 #include <ros/console.h>
44 
45 namespace map_merge
46 {
47 MapMerge::MapMerge() : subscriptions_size_(0)
48 {
49  ros::NodeHandle private_nh("~");
50  std::string frame_id;
51  std::string merged_map_topic;
52 
53  private_nh.param("merging_rate", merging_rate_, 4.0);
54  private_nh.param("discovery_rate", discovery_rate_, 0.05);
55  private_nh.param("estimation_rate", estimation_rate_, 0.5);
56  private_nh.param("known_init_poses", have_initial_poses_, true);
57  private_nh.param("estimation_confidence", confidence_threshold_, 1.0);
58  private_nh.param<std::string>("robot_map_topic", robot_map_topic_, "map");
59  private_nh.param<std::string>("robot_map_updates_topic",
60  robot_map_updates_topic_, "map_updates");
61  private_nh.param<std::string>("robot_namespace", robot_namespace_, "");
62  private_nh.param<std::string>("merged_map_topic", merged_map_topic, "map");
63  private_nh.param<std::string>("world_frame", world_frame_, "world");
64 
65  /* publishing */
66  merged_map_publisher_ =
67  node_.advertise<nav_msgs::OccupancyGrid>(merged_map_topic, 50, true);
68 }
69 
70 /*
71  * Subcribe to pose and map topics
72  */
73 void MapMerge::topicSubscribing()
74 {
75  ROS_DEBUG("Robot discovery started.");
76 
77  ros::master::V_TopicInfo topic_infos;
78  geometry_msgs::Transform init_pose;
79  std::string robot_name;
80  std::string map_topic;
81  std::string map_updates_topic;
82 
83  ros::master::getTopics(topic_infos);
84  // default msg constructor does no properly initialize quaternion
85  init_pose.rotation.w = 1; // create identity quaternion
86 
87  for (const auto& topic : topic_infos) {
88  // we check only map topic
89  if (!isRobotMapTopic(topic)) {
90  continue;
91  }
92 
93  robot_name = robotNameFromTopic(topic.name);
94  if (robots_.count(robot_name)) {
95  // we already know this robot
96  continue;
97  }
98 
99  if (have_initial_poses_ && !getInitPose(robot_name, init_pose)) {
100  ROS_WARN("Couldn't get initial position for robot [%s]\n"
101  "did you defined parameters map_merge/init_pose_[xyz]? in robot "
102  "namespace? If you want to run merging without known initial "
103  "positions of robots please set `known_init_poses` parameter "
104  "to false. See relavant documentation for details.",
105  robot_name.c_str());
106  continue;
107  }
108 
109  ROS_INFO("adding robot [%s] to system", robot_name.c_str());
110  {
111  std::lock_guard<boost::shared_mutex> lock(subscriptions_mutex_);
112  subscriptions_.emplace_front();
113  ++subscriptions_size_;
114  }
115 
116  // no locking here. robots_ are used only in this procedure
117  MapSubscription& subscription = subscriptions_.front();
118  robots_.insert({robot_name, &subscription});
119  subscription.initial_pose = init_pose;
120 
121  /* subscribe callbacks */
122  map_topic = ros::names::append(robot_name, robot_map_topic_);
123  map_updates_topic =
124  ros::names::append(robot_name, robot_map_updates_topic_);
125  ROS_INFO("Subscribing to MAP topic: %s.", map_topic.c_str());
126  subscription.map_sub = node_.subscribe<nav_msgs::OccupancyGrid>(
127  map_topic, 50,
128  [this, &subscription](const nav_msgs::OccupancyGrid::ConstPtr& msg) {
129  fullMapUpdate(msg, subscription);
130  });
131  ROS_INFO("Subscribing to MAP updates topic: %s.",
132  map_updates_topic.c_str());
133  subscription.map_updates_sub =
134  node_.subscribe<map_msgs::OccupancyGridUpdate>(
135  map_updates_topic, 50,
136  [this, &subscription](
137  const map_msgs::OccupancyGridUpdate::ConstPtr& msg) {
138  partialMapUpdate(msg, subscription);
139  });
140  }
141 }
142 
143 /*
144  * mapMerging()
145  */
146 void MapMerge::mapMerging()
147 {
148  ROS_DEBUG("Map merging started.");
149 
150  if (have_initial_poses_) {
151  std::vector<nav_msgs::OccupancyGridConstPtr> grids;
152  std::vector<geometry_msgs::Transform> transforms;
153  grids.reserve(subscriptions_size_);
154  {
155  boost::shared_lock<boost::shared_mutex> lock(subscriptions_mutex_);
156  for (auto& subscription : subscriptions_) {
157  std::lock_guard<std::mutex> s_lock(subscription.mutex);
158  grids.push_back(subscription.readonly_map);
159  transforms.push_back(subscription.initial_pose);
160  }
161  }
162  // we don't need to lock here, because when have_initial_poses_ is true we
163  // will not run concurrently on the pipeline
164  pipeline_.feed(grids.begin(), grids.end());
165  pipeline_.setTransforms(transforms.begin(), transforms.end());
166  }
167 
168  nav_msgs::OccupancyGridPtr merged_map;
169  {
170  std::lock_guard<std::mutex> lock(pipeline_mutex_);
171  merged_map = pipeline_.composeGrids();
172  }
173  if (!merged_map) {
174  return;
175  }
176 
177  ROS_DEBUG("all maps merged, publishing");
178  ros::Time now = ros::Time::now();
179  merged_map->info.map_load_time = now;
180  merged_map->header.stamp = now;
181  merged_map->header.frame_id = world_frame_;
182 
183  ROS_ASSERT(merged_map->info.resolution > 0.f);
184  merged_map_publisher_.publish(merged_map);
185 }
186 
187 void MapMerge::poseEstimation()
188 {
189  ROS_DEBUG("Grid pose estimation started.");
190  std::vector<nav_msgs::OccupancyGridConstPtr> grids;
191  grids.reserve(subscriptions_size_);
192  {
193  boost::shared_lock<boost::shared_mutex> lock(subscriptions_mutex_);
194  for (auto& subscription : subscriptions_) {
195  std::lock_guard<std::mutex> s_lock(subscription.mutex);
196  grids.push_back(subscription.readonly_map);
197  }
198  }
199 
200  std::lock_guard<std::mutex> lock(pipeline_mutex_);
201  pipeline_.feed(grids.begin(), grids.end());
202  // TODO allow user to change feature type
203  pipeline_.estimateTransforms(combine_grids::FeatureType::AKAZE,
204  confidence_threshold_);
205 }
206 
207 void MapMerge::fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr& msg,
208  MapSubscription& subscription)
209 {
210  ROS_DEBUG("received full map update");
211  std::lock_guard<std::mutex> lock(subscription.mutex);
212  if (subscription.readonly_map &&
213  subscription.readonly_map->header.stamp > msg->header.stamp) {
214  // we have been overrunned by faster update. our work was useless.
215  return;
216  }
217 
218  subscription.readonly_map = msg;
219  subscription.writable_map = nullptr;
220 }
221 
222 void MapMerge::partialMapUpdate(
223  const map_msgs::OccupancyGridUpdate::ConstPtr& msg,
224  MapSubscription& subscription)
225 {
226  ROS_DEBUG("received partial map update");
227 
228  if (msg->x < 0 || msg->y < 0) {
229  ROS_ERROR("negative coordinates, invalid update. x: %d, y: %d", msg->x,
230  msg->y);
231  return;
232  }
233 
234  size_t x0 = static_cast<size_t>(msg->x);
235  size_t y0 = static_cast<size_t>(msg->y);
236  size_t xn = msg->width + x0;
237  size_t yn = msg->height + y0;
238 
239  nav_msgs::OccupancyGridPtr map;
240  nav_msgs::OccupancyGridConstPtr readonly_map; // local copy
241  {
242  // load maps
243  std::lock_guard<std::mutex> lock(subscription.mutex);
244  map = subscription.writable_map;
245  readonly_map = subscription.readonly_map;
246  }
247 
248  if (!readonly_map) {
249  ROS_WARN("received partial map update, but don't have any full map to "
250  "update. skipping.");
251  return;
252  }
253 
254  // we don't have partial map to take update, we must copy readonly map and
255  // update new writable map
256  if (!map) {
257  map.reset(new nav_msgs::OccupancyGrid(*readonly_map));
258  }
259 
260  size_t grid_xn = map->info.width;
261  size_t grid_yn = map->info.height;
262 
263  if (xn > grid_xn || x0 > grid_xn || yn > grid_yn || y0 > grid_yn) {
264  ROS_WARN("received update doesn't fully fit into existing map, "
265  "only part will be copied. received: [%lu, %lu], [%lu, %lu] "
266  "map is: [0, %lu], [0, %lu]",
267  x0, xn, y0, yn, grid_xn, grid_yn);
268  }
269 
270  // update map with data
271  size_t i = 0;
272  for (size_t y = y0; y < yn && y < grid_yn; ++y) {
273  for (size_t x = x0; x < xn && x < grid_xn; ++x) {
274  size_t idx = y * grid_xn + x; // index to grid for this specified cell
275  map->data[idx] = msg->data[i];
276  ++i;
277  }
278  }
279  // update time stamp
280  map->header.stamp = msg->header.stamp;
281 
282  {
283  // store back updated map
284  std::lock_guard<std::mutex> lock(subscription.mutex);
285  if (subscription.readonly_map &&
286  subscription.readonly_map->header.stamp > map->header.stamp) {
287  // we have been overrunned by faster update. our work was useless.
288  return;
289  }
290  subscription.writable_map = map;
291  subscription.readonly_map = map;
292  }
293 }
294 
295 std::string MapMerge::robotNameFromTopic(const std::string& topic)
296 {
297  return ros::names::parentNamespace(topic);
298 }
299 
300 /* identifies topic via suffix */
301 bool MapMerge::isRobotMapTopic(const ros::master::TopicInfo& topic)
302 {
303  /* test whether topic is robot_map_topic_ */
304  std::string topic_namespace = ros::names::parentNamespace(topic.name);
305  bool is_map_topic =
306  ros::names::append(topic_namespace, robot_map_topic_) == topic.name;
307 
308  /* test whether topic contains *anywhere* robot namespace */
309  auto pos = topic.name.find(robot_namespace_);
310  bool contains_robot_namespace = pos != std::string::npos;
311 
312  /* we support only occupancy grids as maps */
313  bool is_occupancy_grid = topic.datatype == "nav_msgs/OccupancyGrid";
314 
315  /* we don't want to subcribe on published merged map */
316  bool is_our_topic = merged_map_publisher_.getTopic() == topic.name;
317 
318  return is_occupancy_grid && !is_our_topic && contains_robot_namespace &&
319  is_map_topic;
320 }
321 
322 /*
323  * Get robot's initial position
324  */
325 bool MapMerge::getInitPose(const std::string& name,
326  geometry_msgs::Transform& pose)
327 {
328  std::string merging_namespace = ros::names::append(name, "map_merge");
329  double yaw = 0.0;
330 
331  bool success =
332  ros::param::get(ros::names::append(merging_namespace, "init_pose_x"),
333  pose.translation.x) &&
334  ros::param::get(ros::names::append(merging_namespace, "init_pose_y"),
335  pose.translation.y) &&
336  ros::param::get(ros::names::append(merging_namespace, "init_pose_z"),
337  pose.translation.z) &&
338  ros::param::get(ros::names::append(merging_namespace, "init_pose_yaw"),
339  yaw);
340 
341  tf2::Quaternion q;
342  q.setEuler(0., 0., yaw);
343  pose.rotation = toMsg(q);
344 
345  return success;
346 }
347 
348 /*
349  * execute()
350  */
351 void MapMerge::executemapMerging()
352 {
353  ros::Rate r(merging_rate_);
354  while (node_.ok()) {
355  mapMerging();
356  r.sleep();
357  }
358 }
359 
360 void MapMerge::executetopicSubscribing()
361 {
362  ros::Rate r(discovery_rate_);
363  while (node_.ok()) {
364  topicSubscribing();
365  r.sleep();
366  }
367 }
368 
369 void MapMerge::executeposeEstimation()
370 {
371  if (have_initial_poses_)
372  return;
373 
374  ros::Rate r(estimation_rate_);
375  while (node_.ok()) {
376  poseEstimation();
377  r.sleep();
378  }
379 }
380 
381 /*
382  * spin()
383  */
384 void MapMerge::spin()
385 {
387  std::thread merging_thr([this]() { executemapMerging(); });
388  std::thread subscribing_thr([this]() { executetopicSubscribing(); });
389  std::thread estimation_thr([this]() { executeposeEstimation(); });
390  ros::spin();
391  estimation_thr.join();
392  merging_thr.join();
393  subscribing_thr.join();
394 }
395 
396 } // namespace map_merge
397 
398 int main(int argc, char** argv)
399 {
400  ros::init(argc, argv, "map_merge");
401  // this package is still in development -- start wil debugging enabled
405  }
406  map_merge::MapMerge map_merging;
407  map_merging.spin();
408  return 0;
409 }
map_merge::MapSubscription::writable_map
nav_msgs::OccupancyGrid::Ptr writable_map
Definition: map_merge.h:131
map_merge::MapSubscription
Definition: map_merge.h:90
combine_grids::FeatureType::AKAZE
@ AKAZE
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
map_merge::MapSubscription::mutex
std::mutex mutex
Definition: map_merge.h:128
ros::spinOnce
ROSCPP_DECL void spinOnce()
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
main
int main(int argc, char **argv)
Definition: map_merge.cpp:398
ros::console::set_logger_level
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
ros::master::getTopics
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
ros::names::parentNamespace
ROSCPP_DECL std::string parentNamespace(const std::string &name)
map_merge.h
map_merge::MapMerge
Definition: map_merge.h:103
console.h
map_merge::MapSubscription::map_sub
ros::Subscriber map_sub
Definition: map_merge.h:134
ros::console::levels::Debug
Debug
ROS_DEBUG
#define ROS_DEBUG(...)
ros::master::V_TopicInfo
std::vector< TopicInfo > V_TopicInfo
ROS_WARN
#define ROS_WARN(...)
map_merge::MapMerge::spin
void spin()
Definition: map_merge.cpp:419
ros::Rate::sleep
bool sleep()
ros::names::append
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
ros::Time
tf2::Quaternion::setEuler
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
ros::master::TopicInfo::datatype
std::string datatype
ROS_ERROR
#define ROS_ERROR(...)
tf2::Quaternion
tf2_geometry_msgs.h
toMsg
B toMsg(const A &a)
ros::Rate
ros::spin
ROSCPP_DECL void spin()
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
assert.h
ROS_INFO
#define ROS_INFO(...)
ros::master::TopicInfo
ROS_ASSERT
#define ROS_ASSERT(cond)
map_merge::MapSubscription::initial_pose
geometry_msgs::Transform initial_pose
Definition: map_merge.h:130
ros::NodeHandle
ros::master::TopicInfo::name
std::string name
ros::Time::now
static Time now()
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