rtabmap_ros icon indicating copy to clipboard operation
rtabmap_ros copied to clipboard

Questions on Multi-Floor Mapping Using RTAB-Map

Open csvicbot-7 opened this issue 5 months ago • 4 comments

Dear @matlabbe,

I am evaluating the use of RTAB-Map for multi-floor mapping. The robot will navigate across multiple floors connected by staircases, and I am considering the use of multi-session mode to manage the mapping process. I would be very grateful if you could help clarify a few technical questions related to this use case:

  1. Is it possible to create a separate session for each floor and use the GridGlobal/AltitudeDelta parameter to generate a 2D map for each floor?
  2. Would RTAB-Map be capable of detecting loop closures between two different floors from separate sessions, assuming there is a common area such as a staircase?
  3. If the robot revisits a previously mapped floor, would RTAB-Map be able to correctly localize the robot on the appropriate floor and load the corresponding 2D map?
  4. From a practical standpoint, is it more advisable to separate each floor into its own session, or to map all floors within a single session?

Thank you very much in advance for your time and support.

csvicbot-7 avatar Jul 13 '25 15:07 csvicbot-7

  1. If the maps between floors are not connected to know that one map is over than the other, GridGlobal/AltitudeDelta won't help. If the maps are not connected, then you would not need GridGlobal/AltitudeDelta.
  2. Yes, but there should be some overlap between the maps. If they are connected, then GridGlobal/AltitudeDelta coudl help to generate a 2D occupancy grid based on the current altitude in the graph.
  3. Yes. However, be careful on multi-floor buildings where all floors look the same. After the first localization, as long as the robot localizes often enough (under RGBD/MaxOdomCacheSize), it should not teleport to another floor if for some reason there is a high loop closure hypothesis triggering there.
  4. If the final result is combining all sessions in the same database, then it doesn't matter if you do it in one session or multiple sessions. However, as mentioned in the previous point, having multiple floors that all look similar in the same database could make the robot teleport between floors. Having all sessions in the same database could make also the robot use more RAM and more CPU. Having a single database per floor can reduce RAM/CPU usage and you can make sure that the robot won't teleport between floors. However you would need an external mechanism to know which floor to load, instead of just automatically re-localize in the all-floor combined version.

Related posts:

  • http://official-rtab-map-forum.206.s1.nabble.com/Rtab-map-in-different-floors-td6947.html
  • http://official-rtab-map-forum.206.s1.nabble.com/Mapping-Multiple-Facilities-td9847.html

cheers, Mathieu

matlabbe avatar Jul 14 '25 02:07 matlabbe

Hi @matlabbe

I hope you are doing well.

I have decided to map multiple floors within a single RTAB-Map database. In order to prevent the robot from "teleporting" between floors, I adjusted the RGBD/OptimizeMaxError parameter. Based on your explanation in this issue #996, "The idea behind RGBD/OptimizeMaxError is that after loop closure detection, if the graph is deformed more than X time the covariance error in the links, the loop closure will be rejected."

I conducted two tests using a public dataset from Hilti https://tp-public-facing.s3.eu-north-1.amazonaws.com/Challenges/2023/site2_robot_1.bag which corresponds to a three-level parking structure. In both tests, I only used the 3D LiDAR point cloud and IMU data. I am attaching the launch file in case it is helpful.

Test 1 (attached database: Hilti_dataset_test1.db )

RGBD/OptimizeMaxError = 3.0 (default)

GridGlobal/AltitudeDelta = 0.0 (default)

In this case, 22 loop closure links were created between floors 0 and -1. As a result, the robot is teleported from floor -1 to floor 0.

Test 2 (attached database: Hilti_dataset_test2.db)

RGBD/OptimizeMaxError = 0.2

GridGlobal/AltitudeDelta = 1.5

With RGBD/OptimizeMaxError = 0.2, I expected all loop closures between different floors to be rejected, as the transformations between such nodes should exceed this threshold. However, this was not fully the case: while 12 loop closures were rejected compared to Test 1, 10 loop closures between floors 0 and -1 were still accepted, as shown in the attached database.

This leads me to the following questions:

Why are 10 loop closures between floors 0 and -1 still accepted even when OptimizeMaxError is set to 0.2?

How are loop closures handled in the case of 3D LiDAR scans?

If stereo or depth camera images were used, could that help improve the rejection of loop closures between visually similar but spatially separate floors?

Assuming the robot has finished mapping a building with three floors, is there a way to query how many 2D maps were created and visualize each of them through a ROS topic?

Thank you very much for your time and any guidance you can provide.

Best regards Victor

csvicbot-7 avatar Jul 25 '25 15:07 csvicbot-7

It seems there is an issue with the Lidar to IMU transform. Optimizing with IMU on the back-end makes the trajectory worst. With GTSAM optimizer, it is slightly better, but we still need to increase Optimizer/GravitySigma value to >=1 to avoid too much deformation that makes the trajectories between floors close enough (below RGBD/LocalRadius, set to 2 meters here) to trigger a one-to-many proximity detection (RGBD/ProximityPathMaxNeighbors>0, set to 1 here). After a proximity loop is detected, the graph is not deformed inside the max covariance set to links. The odometry covariance may be over estimated, so RGBD/OptimizeMaxError should be a lot lower to actually reject it. Here is the optimizer ratio of the first database:

$ rtabmap-report Loop/Optimization_max_ang_error_ratio/ Loop/Optimization_max_error_ratio/   Hilti_dataset_test1.db
Image

Based on that, to reject the first proximity loop closure, RGBD/OptimizeMaxError should be below 0.169. Note that this issue can happen even if the odometry covariance is not overestimated, the longer the path before loop closure, the less deformation for each link may be measured and reduce ratio error to fall below the threshold

For the IMU issue, the best result I got is by using Optimizer/GravitySigma=10 with GTSAM optimizer (Optimizer/Strategy=2).

Original (Optimizer/GravitySigma=0.5 and Optimizer/Strategy=1): Image

Without IMU (Optimizer/GravitySigma=0): Image

Best (Optimizer/GravitySigma=10, Optimizer/Strategy=2): Image

Needing to set Optimizer/GravitySigma as high means the IMU/Lidar transform is not super accurate or there is some timing sync issue between the imu and lidar.

cheers, Mathieu

matlabbe avatar Aug 03 '25 19:08 matlabbe

Forgot to answer the question about the occupancy grid per floor. The occupancy grid will be automatically generated with nodes falling above and below the current position and GridGlobal/AltitudeDelta parameter.

Here is the occupancy grid during mapping with GridGlobal/AltitudeDelta=1 (I also set Grid/MaxRange=5 and Grid/MaxObstacleHeight=1 so that the ceiling when using the ramp doesn't create obstacles):

https://github.com/user-attachments/assets/2e23e332-cf24-4f5f-9f67-0a7bef3e4249

matlabbe avatar Aug 03 '25 20:08 matlabbe