rtabmap_ros icon indicating copy to clipboard operation
rtabmap_ros copied to clipboard

Improving loop closure detection in RTAB-Map for TUM dataset

Open yongyun-iastate opened this issue 3 months ago • 1 comments

When I evaluate the TUM dataset, especially the sequence freiburg3_sitting_halfsphere, the total number of RGB frames is 1,064, but the number of loop closures detected by RTAB-Map is only around 640. I tried increasing the detection rate to 2 or 0 (infinity) and also reducing the ROS 2 bag play rate to 0.1. Is there any way to get more loop closures, or is this normal? I feel that the lack of loop closures may be causing drift and increasing the trajectory error.

Thanks in advance.

yongyun-iastate avatar Sep 10 '25 20:09 yongyun-iastate

I tried the original rosbag on ros1:

$ wget http://vision.in.tum.de/rgbd/dataset/freiburg3/rgbd_dataset_freiburg3_sitting_halfsphere.bag
$ rosbag decompress rgbd_dataset_freiburg3_sitting_halfsphere.bag
$ wget https://gist.githubusercontent.com/matlabbe/897b775c38836ed8069a1397485ab024/raw/6287ce3def8231945326efead0c8a7730bf6a3d5/tum_rename_world_kinect_frame.py
$ python3 tum_rename_world_kinect_frame.py rgbd_dataset_freiburg3_sitting_halfsphere.bag

$ roslaunch rtabmap_examples rgbdslam_datasets.launch
$ rosbag play --clock rgbd_dataset_freiburg3_sitting_halfsphere.bag

it looks about right:

Image

Comparison with the ground truth (gray): Image

There are indeed not many loop closures, but the motion is pretty small, so I would not expect a lot of them. I would not recommend setting loop closure rate at infinity or higher than 2 Hz. The visual odometry should be normally more accurate than loop closures. However, if you play with dynamic datasets, VO may sometime introduce more drift if it starts tracking the dynamic obstacles instead of the static environment. This kind of drift is difficult to correct even with more loop closures.

matlabbe avatar Sep 21 '25 01:09 matlabbe