rtabmap_ros icon indicating copy to clipboard operation
rtabmap_ros copied to clipboard

Switching to mapping mode clears the existing map

Open mandrievich opened this issue 5 months ago • 7 comments

Hello,

I encountered an issue when switching RTAB-Map from localization mode to mapping mode using the following setup:

frame_id: "base_link"
ground_truth_base_frame_id: "base_footprint"
odom_frame_id: "odom"
map_frame_id: "map"
subscribe_rgb: true
subscribe_depth: true
subscribe_odom_info: false
approx_sync: false
subscribe_rgbd: false
queue_size: 10
wait_for_transform_duration: 0.2
Mem/IncrementalMemory: "false"
Mem/InitWMWithAllNodes: "true"
RGBD/OptimizeFromGraphEnd: "false"
RGBD/LinearUpdate: "0.0"
RGBD/AngularUpdate: "0.0"
RGBD/ProximityBySpace: "false"
RGBD/ProximityPathMaxNeighbors: "0"
Reg/Force3DoF: "true"
Kp/DetectorStrategy: "6"
Vis/EstimationType: "0"
Vis/MinInliers: "15"
Optimizer/Strategy: "1"
Grid/3D: "false"
Grid/FlatObstacleDetected: "false"
Grid/MinClusterSize: "0"
Rtabmap/TimeThr: "0"
Rtabmap/DetectionRate: "3.5"
GridGlobal/Eroded: "false"
Grid/RayTracing: "false"

When I call the following service to switch to mapping mode:

ros2 service call /rtabmap/set_mode_mapping std_srvs/srv/Empty "{}"

I expect that the previously built map will remain intact and that new data will be added to it — as described in this forum discussion: http://official-rtab-map-forum.206.s1.nabble.com/Updating-map-when-doing-localization-in-3D-lidar-version-td8769.html

However, the existing map completely disappears, and I only see a small segment from the latest camera frame.

Could you please advise? I'm using ROS 2 Jazzy.

Thank you in advance!

mandrievich avatar Jun 30 '25 17:06 mandrievich

I played with the same demo you linked, but with camera only (turtlebot3_sim_rgbd_demo.launch.py), and I can reproduce the same behavior than the lidar example. The only thing is that to not lose the map when switching from localization to map, the robot has to be already on a node that is easy to localize on, so that the old map won't disappear. In other words, the robot has to localize right away when starting the new map to link it with the old one and keep the two sessions in the occupancy grid.

If the robot cannot localize right away, the old map will disappear, showing the new map only. The old map would re-appear if the robot re-localizes on a node of a previous session.

cheers, Mathieu

matlabbe avatar Jul 01 '25 03:07 matlabbe

Hello @matlabbe Thank you for the quick response. Am I correct in understanding that in order to prevent the old map from disappearing, the robot must already be properly localized? In that case, how can we determine that the robot has been localized correctly? Is it correct to assume that if the map has already appeared, it means the robot has been successfully localized? Thank you.

mandrievich avatar Jul 01 '25 06:07 mandrievich

You can set Rtabmap/StartNewMapOnLoopClosure: "true" so that a new map will be created only after the robot has re-localized on the previous map(s). The occupancy grid used during localization will still be there.

To know if the robot re-localized, in rtabmap/Info topic, one of these three value will be non-zero:

int32 loop_closure_id
int32 proximity_detection_id
int32 landmark_id

matlabbe avatar Jul 02 '25 04:07 matlabbe

Hello @matlabbe

Thank you for your reply and the clarification!

The idea is not to create a new map, but rather to update the existing one — for example, when the landscape changes significantly during localization due to seasonal or weather changes. The goal is to accumulate these changes to improve localization accuracy over time. Is it possible to configure such a scenario?

mandrievich avatar Jul 02 '25 21:07 mandrievich

There are different approaches to do that:

  • Be always in mapping mode, but would require a special planner to adjust paths when the world frame is changing over time, see this paper.
  • Make the updates offline (i.e., the robot records map data during a localization session, then appends the new map data in offline way), similar to this paper

In both cases, a graph reduction approach can be used to reduce the size of the map over time, though there are some caveats. See the discussion section of the papers.

matlabbe avatar Jul 05 '25 05:07 matlabbe

Hello @matlabbe,

Thank you for your replay!

Am I correct in understanding that there is no such functionality, for example, when a robot is already using a map built with RTAB-Map and wants to switch to a mode to dynamically update the existing map with new frames under changing conditions, so that the 2D map is not lost, but the existing map is continuously and dynamically updated?

mandrievich avatar Jul 06 '25 16:07 mandrievich

With Rtabmap/StartNewMapOnLoopClosure: "true", it could do what you describe, though it won't start adding new data till the robot can re-localize on the current map. The "update" is adding new nodes, the old nodes of the previous map will still be kept, so you can end up with multiple nodes at exactly the same location but with different visual features. This obviously increases the map size in term of nodes, though it can help to handle better re-localization in dynamic environments (like illumination changing environments).

matlabbe avatar Jul 07 '25 01:07 matlabbe