introlab / rtabmap

RTAB-Map library and standalone application
https://introlab.github.io/rtabmap
Other
2.6k stars 761 forks source link

What represents pose in signature and where are global poses are stored? #1274

Closed gvasserm closed 1 month ago

gvasserm commented 1 month ago

Hi. I'm trying to understand the logic behind pose graph optimization in rtabmap and how the poses are stored. What is the pose that is stored in signature? Is it an odometry pose or optimized graph pose? Where are the global/optimized poses stored in db?

matlabbe commented 1 month ago

The pose in Signature is the odometry pose. The optimized poses are computed online based on odometry poses and links. The optimized poses are also saved on exit in database's Admin table under opt_poses, and reloaded when re-opening the a map (in slam mode it is useful to give a first guess for optimization, for localization they should never changed).

gvasserm commented 1 month ago

Thank you for fast reponse) And where can I found the code that updates the pose for each signature from odometry to the optimized poses? I've seen some example in exportPoses(), however poses are generated only for specific signatures or nodes.

genawass commented 1 month ago

One more question: do you have some knowledge resource to better understand the code, since the code is not documented well, ie, there are no docstrings and comments in code

matlabbe commented 1 month ago

Are you referring to that exportPoses? https://github.com/introlab/rtabmap/blob/9505a21a7eaa2087c1d143090229436afe61b6bf/corelib/src/Rtabmap.cpp#L1019

Internally, rtabmap would call optimizeCurrentMap to optimize poses when necessary.

A more convenient way to see/analyze optimized poses is to open Graph View in rtabmap-databaseViewer. You can move the iterations slider to see different steps of the graph optimizer (with 0 the actual odometry poses). The File menu option "Export poses..." will export poses that you can see in the Graph View.

The optimized poses is created only from nodes that are linked in the graph. All nodes not linked to graph are ignored. If the database has multiple unlinked mapping sessions, you can change the root ID to a node in a session you want to export poses.

About API documentation, it could be indeed improved! Most documentation efforts back in the days were put on the actual rtabmap standalone app itself and rtabmap_ros wiki (in particular the tutorials, examples, and demos), which most users were interested about. For a general idea of how the code works, I would refer to that paper.