51 std::string merged_map_topic;
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");
66 merged_map_publisher_ =
67 node_.advertise<nav_msgs::OccupancyGrid>(merged_map_topic, 50,
true);
73 void MapMerge::topicSubscribing()
78 geometry_msgs::Transform init_pose;
79 std::string robot_name;
80 std::string map_topic;
81 std::string map_updates_topic;
85 init_pose.rotation.w = 1;
87 for (
const auto& topic : topic_infos) {
89 if (!isRobotMapTopic(topic)) {
93 robot_name = robotNameFromTopic(topic.name);
94 if (robots_.count(robot_name)) {
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.",
109 ROS_INFO(
"adding robot [%s] to system", robot_name.c_str());
111 std::lock_guard<boost::shared_mutex> lock(subscriptions_mutex_);
112 subscriptions_.emplace_front();
113 ++subscriptions_size_;
118 robots_.insert({robot_name, &subscription});
125 ROS_INFO(
"Subscribing to MAP topic: %s.", map_topic.c_str());
126 subscription.
map_sub = node_.subscribe<nav_msgs::OccupancyGrid>(
128 [
this, &subscription](
const nav_msgs::OccupancyGrid::ConstPtr& msg) {
129 fullMapUpdate(msg, subscription);
131 ROS_INFO(
"Subscribing to MAP updates topic: %s.",
132 map_updates_topic.c_str());
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);
146 void MapMerge::mapMerging()
150 if (have_initial_poses_) {
151 std::vector<nav_msgs::OccupancyGridConstPtr> grids;
152 std::vector<geometry_msgs::Transform> transforms;
153 grids.reserve(subscriptions_size_);
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);
164 pipeline_.feed(grids.begin(), grids.end());
165 pipeline_.setTransforms(transforms.begin(), transforms.end());
168 nav_msgs::OccupancyGridPtr merged_map;
170 std::lock_guard<std::mutex> lock(pipeline_mutex_);
171 merged_map = pipeline_.composeGrids();
177 ROS_DEBUG(
"all maps merged, publishing");
179 merged_map->info.map_load_time = now;
180 merged_map->header.stamp = now;
181 merged_map->header.frame_id = world_frame_;
183 ROS_ASSERT(merged_map->info.resolution > 0.f);
184 merged_map_publisher_.publish(merged_map);
187 void MapMerge::poseEstimation()
189 ROS_DEBUG(
"Grid pose estimation started.");
190 std::vector<nav_msgs::OccupancyGridConstPtr> grids;
191 grids.reserve(subscriptions_size_);
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);
200 std::lock_guard<std::mutex> lock(pipeline_mutex_);
201 pipeline_.feed(grids.begin(), grids.end());
204 confidence_threshold_);
207 void MapMerge::fullMapUpdate(
const nav_msgs::OccupancyGrid::ConstPtr& msg,
208 MapSubscription& subscription)
211 std::lock_guard<std::mutex> lock(subscription.mutex);
212 if (subscription.readonly_map &&
213 subscription.readonly_map->header.stamp > msg->header.stamp) {
218 subscription.readonly_map = msg;
219 subscription.writable_map =
nullptr;
222 void MapMerge::partialMapUpdate(
223 const map_msgs::OccupancyGridUpdate::ConstPtr& msg,
226 ROS_DEBUG(
"received partial map update");
228 if (msg->x < 0 || msg->y < 0) {
229 ROS_ERROR(
"negative coordinates, invalid update. x: %d, y: %d", msg->x,
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;
239 nav_msgs::OccupancyGridPtr map;
240 nav_msgs::OccupancyGridConstPtr readonly_map;
243 std::lock_guard<std::mutex> lock(subscription.
mutex);
249 ROS_WARN(
"received partial map update, but don't have any full map to "
250 "update. skipping.");
257 map.reset(
new nav_msgs::OccupancyGrid(*readonly_map));
260 size_t grid_xn = map->info.width;
261 size_t grid_yn = map->info.height;
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);
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;
275 map->data[idx] = msg->data[i];
280 map->header.stamp = msg->header.stamp;
284 std::lock_guard<std::mutex> lock(subscription.
mutex);
286 subscription.
readonly_map->header.stamp > map->header.stamp) {
295 std::string MapMerge::robotNameFromTopic(
const std::string& topic)
309 auto pos = topic.
name.find(robot_namespace_);
310 bool contains_robot_namespace = pos != std::string::npos;
313 bool is_occupancy_grid = topic.
datatype ==
"nav_msgs/OccupancyGrid";
316 bool is_our_topic = merged_map_publisher_.getTopic() == topic.
name;
318 return is_occupancy_grid && !is_our_topic && contains_robot_namespace &&
325 bool MapMerge::getInitPose(
const std::string& name,
326 geometry_msgs::Transform& pose)
333 pose.translation.x) &&
335 pose.translation.y) &&
337 pose.translation.z) &&
343 pose.rotation =
toMsg(q);
351 void MapMerge::executemapMerging()
360 void MapMerge::executetopicSubscribing()
369 void MapMerge::executeposeEstimation()
371 if (have_initial_poses_)
384 void MapMerge::spin()
387 std::thread merging_thr([
this]() { executemapMerging(); });
388 std::thread subscribing_thr([
this]() { executetopicSubscribing(); });
389 std::thread estimation_thr([
this]() { executeposeEstimation(); });
391 estimation_thr.join();
393 subscribing_thr.join();
398 int main(
int argc,
char** argv)