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_treshold_, 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 */
67  node_.advertise<nav_msgs::OccupancyGrid>(merged_map_topic, 50, true);
68 }
69 
70 /*
71  * Subcribe to pose and map topics
72  */
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();
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 =
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  */
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  merged_map_publisher_.publish(merged_map);
183 }
184 
186 {
187  ROS_DEBUG("Grid pose estimation started.");
188  std::vector<nav_msgs::OccupancyGridConstPtr> grids;
189  grids.reserve(subscriptions_size_);
190  {
191  boost::shared_lock<boost::shared_mutex> lock(subscriptions_mutex_);
192  for (auto& subscription : subscriptions_) {
193  std::lock_guard<std::mutex> s_lock(subscription.mutex);
194  grids.push_back(subscription.readonly_map);
195  }
196  }
197 
198  std::lock_guard<std::mutex> lock(pipeline_mutex_);
199  pipeline_.feed(grids.begin(), grids.end());
201 }
202 
203 void MapMerge::fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr& msg,
204  MapSubscription& subscription)
205 {
206  ROS_DEBUG("received full map update");
207  std::lock_guard<std::mutex> lock(subscription.mutex);
208  if (subscription.readonly_map &&
209  subscription.readonly_map->header.stamp > msg->header.stamp) {
210  // we have been overrunned by faster update. our work was useless.
211  return;
212  }
213 
214  subscription.readonly_map = msg;
215  subscription.writable_map = nullptr;
216 }
217 
219  const map_msgs::OccupancyGridUpdate::ConstPtr& msg,
220  MapSubscription& subscription)
221 {
222  ROS_DEBUG("received partial map update");
223 
224  if (msg->x < 0 || msg->y < 0) {
225  ROS_ERROR("negative coordinates, invalid update. x: %d, y: %d", msg->x,
226  msg->y);
227  return;
228  }
229 
230  size_t x0 = static_cast<size_t>(msg->x);
231  size_t y0 = static_cast<size_t>(msg->y);
232  size_t xn = msg->width + x0;
233  size_t yn = msg->height + y0;
234 
235  nav_msgs::OccupancyGridPtr map;
236  nav_msgs::OccupancyGridConstPtr readonly_map; // local copy
237  {
238  // load maps
239  std::lock_guard<std::mutex> lock(subscription.mutex);
240  map = subscription.writable_map;
241  readonly_map = subscription.readonly_map;
242  }
243 
244  if (!readonly_map) {
245  ROS_WARN("received partial map update, but don't have any full map to "
246  "update. skipping.");
247  return;
248  }
249 
250  // we don't have partial map to take update, we must copy readonly map and
251  // update new writable map
252  if (!map) {
253  map.reset(new nav_msgs::OccupancyGrid(*readonly_map));
254  }
255 
256  size_t grid_xn = map->info.width;
257  size_t grid_yn = map->info.height;
258 
259  if (xn > grid_xn || x0 > grid_xn || yn > grid_yn || y0 > grid_yn) {
260  ROS_WARN("received update doesn't fully fit into existing map, "
261  "only part will be copied. received: [%lu, %lu], [%lu, %lu] "
262  "map is: [0, %lu], [0, %lu]",
263  x0, xn, y0, yn, grid_xn, grid_yn);
264  }
265 
266  // update map with data
267  size_t i = 0;
268  for (size_t y = y0; y < yn && y < grid_yn; ++y) {
269  for (size_t x = x0; x < xn && x < grid_xn; ++x) {
270  size_t idx = y * grid_xn + x; // index to grid for this specified cell
271  map->data[idx] = msg->data[i];
272  ++i;
273  }
274  }
275  // update time stamp
276  map->header.stamp = msg->header.stamp;
277 
278  {
279  // store back updated map
280  std::lock_guard<std::mutex> lock(subscription.mutex);
281  if (subscription.readonly_map &&
282  subscription.readonly_map->header.stamp > map->header.stamp) {
283  // we have been overrunned by faster update. our work was useless.
284  return;
285  }
286  subscription.writable_map = map;
287  subscription.readonly_map = map;
288  }
289 }
290 
291 std::string MapMerge::robotNameFromTopic(const std::string& topic)
292 {
293  return ros::names::parentNamespace(topic);
294 }
295 
296 /* identifies topic via suffix */
298 {
299  /* test whether topic is robot_map_topic_ */
300  std::string topic_namespace = ros::names::parentNamespace(topic.name);
301  bool is_map_topic =
302  ros::names::append(topic_namespace, robot_map_topic_) == topic.name;
303 
304  /* test whether topic contains *anywhere* robot namespace */
305  auto pos = topic.name.find(robot_namespace_);
306  bool contains_robot_namespace = pos != std::string::npos;
307 
308  /* we support only occupancy grids as maps */
309  bool is_occupancy_grid = topic.datatype == "nav_msgs/OccupancyGrid";
310 
311  /* we don't want to subcribe on published merged map */
312  bool is_our_topic = merged_map_publisher_.getTopic() == topic.name;
313 
314  return is_occupancy_grid && !is_our_topic && contains_robot_namespace &&
315  is_map_topic;
316 }
317 
318 /*
319  * Get robot's initial position
320  */
321 bool MapMerge::getInitPose(const std::string& name,
322  geometry_msgs::Transform& pose)
323 {
324  std::string merging_namespace = ros::names::append(name, "map_merge");
325  double yaw = 0.0;
326 
327  bool success =
328  ros::param::get(ros::names::append(merging_namespace, "init_pose_x"),
329  pose.translation.x) &&
330  ros::param::get(ros::names::append(merging_namespace, "init_pose_y"),
331  pose.translation.y) &&
332  ros::param::get(ros::names::append(merging_namespace, "init_pose_z"),
333  pose.translation.z) &&
334  ros::param::get(ros::names::append(merging_namespace, "init_pose_yaw"),
335  yaw);
336 
337  tf2::Quaternion q;
338  q.setEuler(0., 0., yaw);
339  pose.rotation = toMsg(q);
340 
341  return success;
342 }
343 
344 /*
345  * execute()
346  */
348 {
350  while (node_.ok()) {
351  mapMerging();
352  r.sleep();
353  }
354 }
355 
357 {
359  while (node_.ok()) {
361  r.sleep();
362  }
363 }
364 
366 {
368  return;
369 
371  while (node_.ok()) {
372  poseEstimation();
373  r.sleep();
374  }
375 }
376 
377 /*
378  * spin()
379  */
381 {
382  ros::spinOnce();
383  std::thread merging_thr([this]() { executemapMerging(); });
384  std::thread subscribing_thr([this]() { executetopicSubscribing(); });
385  std::thread estimation_thr([this]() { executeposeEstimation(); });
386  ros::spin();
387  estimation_thr.join();
388  merging_thr.join();
389  subscribing_thr.join();
390 }
391 
392 } // namespace map_merge
393 
394 int main(int argc, char** argv)
395 {
396  ros::init(argc, argv, "map_merge");
397  // this package is still in development -- start wil debugging enabled
401  }
402  map_merge::MapMerge map_merging;
403  map_merging.spin();
404  return 0;
405 }
ros::NodeHandle node_
Definition: map_merge.h:71
bool getInitPose(const std::string &name, geometry_msgs::Transform &pose)
Definition: map_merge.cpp:321
combine_grids::MergingPipeline pipeline_
Definition: map_merge.h:92
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
void publish(const boost::shared_ptr< M > &message) const
std::string robotNameFromTopic(const std::string &topic)
Definition: map_merge.cpp:291
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
nav_msgs::OccupancyGrid::Ptr composeGrids()
ROSCPP_DECL std::string parentNamespace(const std::string &name)
size_t subscriptions_size_
Definition: map_merge.h:90
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
double merging_rate_
Definition: map_merge.h:74
double discovery_rate_
Definition: map_merge.h:75
std::unordered_map< std::string, MapSubscription * > robots_
Definition: map_merge.h:87
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
std::string robot_map_updates_topic_
Definition: map_merge.h:79
std::vector< TopicInfo > V_TopicInfo
#define ROS_WARN(...)
ros::Subscriber map_updates_sub
Definition: map_merge.h:65
ROSCPP_DECL void spin(Spinner &spinner)
bool estimateTransforms(FeatureType feature=FeatureType::AKAZE, double confidence=1.0)
std::forward_list< MapSubscription > subscriptions_
Definition: map_merge.h:89
std::string robot_namespace_
Definition: map_merge.h:80
nav_msgs::OccupancyGrid::ConstPtr readonly_map
Definition: map_merge.h:62
ROSCPP_DECL bool get(const std::string &key, std::string &s)
void executeposeEstimation()
Definition: map_merge.cpp:365
#define ROS_INFO(...)
void partialMapUpdate(const map_msgs::OccupancyGridUpdate::ConstPtr &msg, MapSubscription &map)
Definition: map_merge.cpp:218
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool setTransforms(InputIt transforms_begin, InputIt transforms_end)
double estimation_rate_
Definition: map_merge.h:76
bool isRobotMapTopic(const ros::master::TopicInfo &topic)
Definition: map_merge.cpp:297
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
geometry_msgs::Transform initial_pose
Definition: map_merge.h:60
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
std::string robot_map_topic_
Definition: map_merge.h:78
ros::Subscriber map_sub
Definition: map_merge.h:64
std::string world_frame_
Definition: map_merge.h:81
double confidence_treshold_
Definition: map_merge.h:77
nav_msgs::OccupancyGrid::Ptr writable_map
Definition: map_merge.h:61
bool sleep()
void feed(InputIt grids_begin, InputIt grids_end)
B toMsg(const A &a)
int main(int argc, char **argv)
Definition: map_merge.cpp:394
bool have_initial_poses_
Definition: map_merge.h:82
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
ros::Publisher merged_map_publisher_
Definition: map_merge.h:85
boost::shared_mutex subscriptions_mutex_
Definition: map_merge.h:91
void poseEstimation()
Estimates initial positions of grids.
Definition: map_merge.cpp:185
static Time now()
std::string getTopic() const
bool ok() const
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
void fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr &msg, MapSubscription &map)
Definition: map_merge.cpp:203
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
std::mutex pipeline_mutex_
Definition: map_merge.h:93
#define ROSCONSOLE_DEFAULT_NAME
void executetopicSubscribing()
Definition: map_merge.cpp:356
#define ROS_DEBUG(...)


map_merge
Author(s): Jiri Horner
autogenerated on Mon Jun 10 2019 13:56:52