RTAB-Map Localization Principle

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

RTAB-Map Localization Principle

GGYU
Dear Mathieu,

I’m trying to understand the underlying localization workflow in RTAB-Map, especially as implemented in the turtlebot3_rgbd_scan.launch.py example from the rtabmap_demos package. As I see it, depending on the parameter settings:

2D LiDAR scans are used to build and update the map continuously.

Camera images are processed to extract visual keypoints, and their depths are estimated from the RGB-D sensor.

The 2D LiDAR data is fed into an ICP-based local matching module (when local matching is enabled).

The visual keypoints from the camera are used primarily for loop‐closing detection and correction.

Is this sequence correct? Could you please explain in detail how RTAB-Map performs localization—how the LiDAR, visual features, depth information, ICP, and loop closure modules interact to estimate the robot’s pose?

Thank you for your insights.

Sincerely,
GGYU
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map Localization Principle

matlabbe
Administrator
Hi,

I'ld suggest to read Section 3 of this paper.


You have most parts right, though not exactly that sequence. As shown in the figure above, the occupancy grid is updated as the last step.

Basically:
1- (STM) Extract visual features, quantization of them to visual dictionary (visual words)
2- With the visual words, do BOW and try to find a global loop closure, if the hypothesis is high enough, estimate first with visual correspondences, then if icp is enabled and lidar is provided, do an icp refinement on the resulting loop closure.
3- Do proximity detection (local loop closure) based on current odometry pose. We do one proximity detection using visual features and the "closest" node in the graph, if a transform can be computed, add a proximity link. The proximity link can be refined by icp if lidar is provided. As a second step in proximity detection, if a lidar is used, we can do a pure local scan matching against close nodes in the graph, adding other proximity links if accepted.
4- Optimize the graph with the new constraints
5- Update the occupancy grid based on the updated graph.