introlab / rtabmap

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

rtabmap.db is empty #1178

Open kenhuang1964 opened 9 months ago

kenhuang1964 commented 9 months ago

I am trying to extract the poses of the device from rtabmap.db, but when I looked into it, it seemed to be empty. How can I fix this issue?

matlabbe commented 9 months ago

what is the size of the file? If rtabmap.db is empty, it means mapping didn't work.

For convenience, the optimized poses will be in Admin table under opt_ids and opt_poses fields. https://github.com/introlab/rtabmap/blob/f56875db4ada45ce9e8564c6a3911ebd809b83bd/corelib/src/resources/DatabaseSchema.sql.in#L123-L124

The pose in Node table is the odometry pose, not the one optimized after loop closures. To optimize the odometry poses, you can look at the Export tool: https://github.com/introlab/rtabmap/blob/f56875db4ada45ce9e8564c6a3911ebd809b83bd/tools/Export/main.cpp#L973-L984

kenhuang1964 commented 9 months ago

Hey @matlabbe, I really appreciate your help! I checked the file size and it is 73 kb, but when I opened it up in sqlite3, it was empty. Just to reiterate, the optimized poses only get saved after RTAB-Map closes, not when loop closure is detected right? Can I just use the Export tool to optimize the odometry poses whenever I want? is there a reason that the poses only get optimized after the RTAB-Map closes? Thanks in advance! :+1:

matlabbe commented 9 months ago

Yes, optimized poses are saved only when closing rtabmap. We didn't find the need to re-write them in database at every rtabmap updates. The export tool does re-optimize the graph anyway, so if they are saved or not, they could be regenerated.

73Kb seems pretty small. Are you in ROS? if so you should see a warning in terminal telling you that rtabmap didn't receive data.