Time needed to start RTABMAP

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

Time needed to start RTABMAP

jseng
I am running RTABMAP in localization mode (on a Jetson TX2) with a map of about 2000 nodes.  After running my ROS launch file, it takes over 2 minutes before the map is first published.  Does this seem typical?  I removed all the RGB and depth images from the database to see if the bottleneck was reading the database, but the delay is about the same.

During the 2 minutes I can see the memory used by RTABMAP slowly grow, so it seems like it is reading from the database.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

matlabbe
Administrator
Hi,

it needs to load the visual word vocabulary, get all visual features from all nodes and load all local occupancy grids. Note that in localization mode, if an optimized grid map is already saved in the database, we could comment those lines to avoid reloading local occupancy grids.

You can also try adding "--udebug" to rtabmap node arguments so that more messages are shown in the terminal to see which part takes longer time to load.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
I ran it with the --udebug flag and the timings I could read were:  loadsignatures() = 17 sec and loadwordsquery() = 75 sec (785K words).  There was a delay of about a minute after that.  I am assuming the access delays come from the SQLite accesses.

I am trying to think if there is a way to cache for faster startups since the data map does not change when running localization.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
I modified the loadWordsQuery() function to cache the words to a binary data file.  When starting the localization a second time, it read the words from the data file (if it exists) and not the database.  The loadWordsQuery() function takes around 2 secs now instead of 75 sec.  I still need to test it for full functionality, but it may be promising.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

matlabbe
Administrator
Good idea! Indeed there are maybe some places that we could just merge all data in a single bytes array, compress it and save it to database (similarly to "opt_" fields in the database). How/where do you save the descriptors?

I was looking at the code, and if you don't use memory management (Rtabmap/TimeThr=0), we can remove parameter Mem/InitWMWithAllNodes in localization mode. That way, instead of using loadWordsQuery(), load(VWDictionary*) will be used instead (which may be faster as only one query is done in the database), from here.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
I just write out the 32-byte descriptors out to a separate binary file (32 bytes at a time).  I am assuming that the ID's are iterated through in the same order every time, so I don't save that information in the file.
Saving it into the database could work too.

I was looking at loadSignaturesQuery() and how to speed that up.  There seems to be a lot going on with the different versions of Rtabmap and the changes to the database fields.  It looks like it is:  loading nodes, loading words for each node, and then calibrations.  That function seems like there is a lot more going on.

What happens after that in the init process?  I seem some FLANN messages and maybe another minute goes by before it actually starts running.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
Just another followup.  I tried the same database on another PC and it is loading much faster than the TX2.  There is still some delay, but it is faster.  It maybe a disk I/O bandwidth issue as well.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

matlabbe
Administrator
After the init, the 2d/3d maps may have to be reconstructed, fetching grid data from the database for every nodes in the map. In my post above, the link I sent is where there could be some delay. You could try to add ROS_WARN at the beginning and the end of the function. For rtabmap node, the init() is done here and the set2DMap() function of the link is called here just after the init(). The FLANN stuff is to initialize the vocabulary in the FLANN kdtree (done after loading the visual words).

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
Okay, I will look into that.  Even when I moved the database on to a RAM disk, it was still loading slowly.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

dschnabel
I have a similar number of nodes (2500) and I'm loading the map on a Raspberry Pi 4.

It takes 2 min 17 sec to load the whole map (1 CPU core constantly using 100%). After running with "--udebug" and analyzing the timestamps I ended up with this breakdown:
loadSignaturesQuery Creating: 0.5s
loadSignaturesQuery Add:      25.5s
loadWordsQuery:               23.4s + 4s after
Rebuilding FLANN:             79s
loadNodeDataQuery:            2.3s
So by far most time is spent rebuilding FLANN (79s), followed by loadSignaturesQuery Add (25s) and loadWordsQuery (23s).

Most often I'm loading the exact same map when starting rtabmap which means the data doesn't change. In this case a cache would be very helpful, so that rebuilding FLANN and loading queries doesn't need to happen on every startup.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
I still have the same problem in the long startup time.  I was able to build a cache for the loadWordsQuery, but I didn't have time to figure out the FLANN structures.  My database doesn't change either, so it is kind of bothersome to wait for it to rebuild the FLANN every time I start it up.

It looked like there was some serialization code in the FLANN library, but I could not get it to work.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
It looks like the version of flann is 1.8.4.  Maybe if the version can be updated, we can get the load/save index to work.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

dschnabel
You probably mean these methods?
Save index to file: https://github.com/introlab/rtabmap/blob/master/corelib/src/rtflann/flann.hpp#L177
Load index from file: https://github.com/introlab/rtabmap/blob/master/corelib/src/rtflann/flann.hpp#L381

Was there a bug in FLANN 1.8.4 that you couldn't get it to work or what's the reason you want to update?
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

dschnabel
I made a first attempt to save the FLANN index to a file and load it afterwards. But so far I've been unsuccessful. If interested here's my hack: https://github.com/dschnabel/rtabmap/pull/1/files?w=1

The error I'm getting is:
[DEBUG] (2020-10-24 20:11:06.767) VWDictionary.cpp:408::update() incremental=1
[DEBUG] (2020-10-24 20:11:06.767) VWDictionary.cpp:429::update() Incremental FLANN: Removing 0 words...
[DEBUG] (2020-10-24 20:11:06.767) VWDictionary.cpp:438::update() Incremental FLANN: Removing 0 words... done!
[DEBUG] (2020-10-24 20:11:06.767) VWDictionary.cpp:444::update() Incremental FLANN: Loading cached words...
[DEBUG] (2020-10-24 20:11:06.920) FlannIndex.cpp:319::loadFromFile() 
terminate called after throwing an instance of 'rtflann::FLANNException'
  what():  Invalid index file, last block not zero length

Not sure if it's worth pursuing further as the FLANN index structure seems rather complicated and there may be other objects that I need to cache as well, e.g. _mapIndexId or _mapIdIndex.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
Thanks for trying that out.  I was trying out those load/save function in the FLANN library as well, but I was getting some problems.  I'm thinking I don't understand all the data structures that need to be cache with the FLANN index in order to get it to work.

I think we'll need Mathieu to chime in on suggestions on caching the FLANN index.

Also, what do you think about using a c++ serialization library?
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
I just wanted to check if you are still interested in an RTABMAP that starts faster.  I have made a lot of progress on a feature that caches the visual word dictionary and the flann index.  It builds the flann index and then loads a cached version.  Let me know if you would like to test it out.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
In reply to this post by dschnabel
I think I replied to the wrong post.  Let me know if you are interested in testing a version that starts up faster.  I have been working on a caching feature for RTABMAP.
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

dschnabel
Sure, happy to try it out (although not sure when I will get to it).

How much faster are we talking? Have you done some benchmarking?
Reply | Threaded
Open this post in threaded view
|

Re: Time needed to start RTABMAP

jseng
Here is the repository:  https://github.com/jsseng/herbie_rtabmap/

It still needs some cleaning up, but am in the process of writing instructions.  Without the cache, on my PC (Intel Xeon E5-1620), the loadWordsQuery() and building the FLANN take about 10 seconds.  With the cache enabled, it now takes 0.7 secs.  I am hoping for a factor of 10, in general.

After you have built a map, you run RTABMAP with a buildCache flag.  This loads the map and then saves the visual word dictionary and rebuilds the flann (flattening the trees into a contiguous chunk of memory and then saving it to a binary file).

When you start up the next time, you pass a useCache flag and it loads the data from the files, without accessing the .db file.  The cache only works with localization mode.