Re: Realtime Map Merger Improvements

Posted by matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Realtime-Map-Merger-Improvements-tp8200p8577.html

Hi Derek,

Good question! No there was no mechanism to recover not received data in MapCloud plugin automatically, unless by clicking "Download map" action. However "Download map" will download all the map again, which may not be efficient (in terms of bandwidth and time of transmission) if we missed only some nodes. Also in some cases, when the map is big, we just cannot call "Download map" because services in ROS have a maximum of data allowed before failing.

I implemented an approach (in this commit) to ask rtabmap to republish data of some nodes. To test it, I updated MapCloud plugin to use that new feature. MapCloud will publish on /rtabmap/republish_node_data topic with ids of nodes for which it didn't cache the data yet. How it works is that rtabmap is listening on /rtabmap/republish_node_data topic, then will republish data of nodes listed in this topic during the next rtabmap update, up to max_nodes_republished parameter (default 2). The parameter max_nodes_republished is used to limit the bandwidth for each rtabmap update. I tested with demo robot mapping rosbag:
# Create a map first.

$ roslaunch rtabmap_ros demo_robot_mapping.launch rviz:=true rtabmapviz:=false
$ rosbag play --clock demo_mapping.bag

# Then restart in localization mode without downloading the map in MapCloud plugin,
# you will see clouds of the map incrementally be downloaded.

$ roslaunch rtabmap_ros demo_robot_mapping.launch rviz:=true rtabmapviz:=false localization:=true
$ rosbag play --clock demo_mapping.bag

Issue: this approach doesn't work with rtabmapviz, as some refactoring would be needed.

cheers,
Mathieu