introlab / rtabmap

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

Need for speed - Speed up loading map time #1267

Open hellovuong opened 2 months ago

hellovuong commented 2 months ago

This PR saves the FLANN index, and its data points and serializes the associated data. Saving FLANN data points will take a long time to save data points, only do it once. The loading will be faster by x10 by using saved files.

matlabbe commented 2 months ago

Thanks for the PR. Would it make more sense to save the flann index inside the database instead of creating new file(s)? I won't have much time in next 2 weeks to review it or try a database version, but you may check to fix the CI errors in the mean time.

cheers, Mathieu

hellovuong commented 1 month ago

Hi, I fixed CI, when you have time can you try or write me suggestions on how to save in the database file? We then can work together on that. Cheers, Vuong

hellovuong commented 1 month ago

Hmm, I am not sure why the last step AppVeyor failed. All build on Ubuntu succeed

matlabbe commented 1 month ago

For the windows build, maybe it is because the Eigen version used is not CMAKE_CXX_STANDARD 17 compatible. We may have to update windows dependencies to support it.

For database usage, the dictionary could be loaded from a database field in Admin table (with a new field flann_index_state BLOB). That could be done when Memory is initialized: https://github.com/introlab/rtabmap/blob/9505a21a7eaa2087c1d143090229436afe61b6bf/corelib/src/Memory.cpp#L423

We may add a new parameter (e.g., Mem/DictionaryStateSaved) as a new flag to this function to tell DBDriver to look into Admin table for the serialized state of the flann index.

_dbDriver->load(_vwd, _vwd->isIncremental(), _dictionaryStateSaved);

If the field in database exists, inside load, there could be a call to a function like dictionary->restoreFlannState(blob) (which will deserialize the flann data and restore flann to right state) after adding the words.

When closing rtabmap, the flann index state could be saved before removing the visual words from the dictionary... before this line: https://github.com/introlab/rtabmap/blob/9505a21a7eaa2087c1d143090229436afe61b6bf/corelib/src/Memory.cpp#L1863 like:

// Setting 0 or null would set null to field in database, otherwise, it will update it
_dbDriver->saveFlannState(_dictionaryStateSaved?_vwd:0);
cleanUnusedWords(); 

This would overwrite the last flann_index_state blob (with serialized data of the flann index) in the database if exists.

Note that by default I would keep the new parameter Mem/DictionaryStateSaved set to false to continue the old behavior, till it is tested more.