introlab / rtabmap

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

Regenerate processing time graph for Rtabmap process #1336

Open naitiknakrani-eic opened 1 week ago

naitiknakrani-eic commented 1 week ago

Hi @francoisferland @matlabbe,

Can you help me to regenerate processing time logs for creating graph as shown in figure below? image

Any tools will be helpful ? If tools are not available, can you tell methodology used to derive these graph ?

Thanks

matlabbe commented 1 week ago

After you created a database, you can extract all timing statistics and export them to MATLAB or Octave to show a graph like that. To do so, you can see the available statistics in the database with:

rtabmap-report --stats rtabmap.db

To show the statistics of the figure above (respectively to legend, the name may slightly differ):

rtabmap-report Timing/Memory_update/ms Timing/Proximity_by_space/ms Timing/Posterior_computation/ms Timing/Map_optimization/ms RtabmapROS/TimeUpdatingMaps/ms Timing/Reactivation/ms rtabmap.db

In the figure that will open, you can already see something similar than the figure above. To export the data, right-click on the legend area and click "Copy all curve data to clipboard". image

Paste data in a text file, then import in any data analyzing software you want.

x   Timing/Memory_update/ms Timing/Proximity_by_space/ms    Timing/Posterior_computation/ms Timing/Map_optimization/ms  RtabmapROS/TimeUpdatingMaps/ms  Timing/Reactivation/ms  
0.000000    6.505010    0.001907    0.012875    0.025034    NaN 0.000000
1.004863    11.481000   0.000954    0.005960    0.011921    NaN 0.005960
2.071385    8.010860    0.000000    0.006199    0.012875    NaN 0.001907
3.072435    7.767920    0.000000    0.005960    4.143950    NaN 1.037120
4.072935    10.537100   0.000954    0.008106    0.799894    NaN 0.039101
5.073380    10.127100   0.001192    0.005007    0.937939    NaN 0.032902
6.073429    10.460100   0.000954    0.007868    1.488920    NaN 0.041962
7.139824    10.862100   0.000954    0.005960    1.379010    NaN 0.034094
8.139961    7.934090    0.000954    0.005960    1.073120    NaN 0.035048
9.140281    8.811000    0.000954    0.006914    1.636030    NaN 0.039101
10.140464   7.201910    0.000954    0.007868    1.781940    NaN 0.049830
11.140506   8.593800    0.000954    0.010014    2.104040    NaN 0.061989
12.206952   8.467200    0.000954    0.020981    1.698020    NaN 0.044823
13.273479   10.787000   0.000954    0.025034    2.268080    NaN 0.051975
...

Note that in this case that map didn't have "Map Assembling Time" (or RtabmapROS/TimeUpdatingMaps/ms), I took a random database, it may not have been taken on a robot with map assembling enabled.

naitiknakrani-eic commented 1 week ago

@matlabbe Thanks. This helps a lot. For our database, we are getting graph like this, image

We have Map assembling time, but its very less hence invisible in the graph. Below one is separate graph of Map assembling. image

From this graph, it seems Global map assembling is not time consuming process. Is it on expected line ? You mentioned in other thread as well as in paper, that Map assembling is computationally heavy process. Are we missing something ?

Also, we did detailed time profile of STM, and other modules but can't able to find which function does Global map assembling. Is it part of Rtabmap.cpp or Corewrapper.cpp ? Can you help us pointing that function ?

matlabbe commented 1 week ago

You mentioned in other thread as well as in paper, that Map assembling is computationally heavy process

... (and more precisely) when there is a loop closure and graph deformation is over GridGlobal/UpdateError (default=0.01m).

The global map assembling is called from the MapsManager called from here, but the actual implementation is in those files: https://github.com/introlab/rtabmap/tree/master/corelib/src/global_map (depending on the topic we are subscribing). The global maps are not generated if no one is subscribed on one of them.

The biggest update spikes will happen when the map has to be fully updated because of a loop closure or memory management retrieved past data back in the current WM (or more explicitly when this is true). Depending on the GlobalMap flavor, the full update may take more or less time (e..g, 2d maps are relatively fast to regenerate). In this paper Table 10, the last two columns show a comparison depending on the map used and if a loop closure happened or not. As you can see, when there is no loop closure, appending new local grids to global map is relatively fast (maybe what you are seeing). image