Speeding up Rtabmap Without Memory Management

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

Speeding up Rtabmap Without Memory Management

seanxu112
This post was updated on .
Hello Mathieu,

Due to some problem (unable to get some loop closure), we are not able to use memory management to speed up mapping . And this is the analysis from rtabmab

As seen from the picture only the blue line is scaling with time, which I assume to be Map_Optimization, since the pose graph scales with time. Descriptor Extraction should be constant if I am not mistaken.

If Map_Optimization is indeed the problem, I am wondering when a new node is added to the graph, is rtabmap optimizing the entire graph? That would make sense for this linear scaling. However, from tracing from here: https://github.com/introlab/rtabmap/blob/ff956a725e05d14285c6978658eee06b40684190/corelib/src/Rtabmap.cpp#L3001, it seems like you are only optimizing the neighboring nodes of the current node. Why would this method cause map optimization scale with time? Is there somewhere else that is causing this problem?

Sincerely,
Sean
Reply | Threaded
Open this post in threaded view
|

Re: Speeding up Rtabmap Without Memory Management

matlabbe
Administrator
Hi,

it re-optimizes the whole graph (attached to latest node) every time a proximity detection or a loop closure is added.

Can you show the database info:
rtabmap-info my_map.db
Reply | Threaded
Open this post in threaded view
|

Re: Speeding up Rtabmap Without Memory Management

seanxu112
Hi,

I think I might have removed the db, but I do have one that is using pretty much the same parameters.

Here is the outcome of rtabmap-info --diff
Parameters (Yellow=modified, Red=old parameter not used anymore):
Db/TargetVersion=                  0.20.0  (default=)
Grid/MinClusterSize=               20  (default=10)
Grid/RangeMax=                     3.5  (default=5.0)
GridGlobal/Eroded=                 true  (default=false)
GridGlobal/ProbHit=                0.65  (default=0.7)
Icp/MaxCorrespondenceDistance=     0.5  (default=0.1)
Icp/MaxRotation=                   0.7  (default=0.78)
Icp/MaxTranslation=                1.0  (default=0.2)
Icp/PMConfig=                      /home/nvidia/catkin_ws/src/algo/software/frcbot_camera_calibration/launch/pm_1.yaml  (default=)
Icp/PointToPlane=                  false  (default=true)
Icp/VoxelSize=                     0.05  (default=0.0)
Kp/DetectorStrategy=               2  (default=6)
Mem/UseOdomFeatures=               false  (default=true)
ORB/EdgeThreshold=                 31  (default=19)
ORB/NLevels=                       8  (default=3)
ORB/ScaleFactor=                   1.2  (default=2)
Optimizer/Epsilon=                 0.0001  (default=0.00001)
Optimizer/Iterations=              60  (default=20)
Optimizer/Strategy=                1  (default=2)
RGBD/CreateOccupancyGrid=          true  (default=false)
RGBD/LocalBundleOnLoopClosure=     true  (default=false)
RGBD/LocalRadius=                  2.0  (default=10)
RGBD/NeighborLinkRefining=         true  (default=false)
RGBD/OptimizeMaxError=             30.0  (default=3.0)
RGBD/ProximityMaxGraphDepth=       200  (default=50)
RGBD/ProximityMaxPaths=            1  (default=3)
RGBD/ProximityOdomGuess=           true  (default=false)
RGBD/ProximityPathFilteringRadius= 0.5  (default=1)
RGBD/ProximityPathMaxNeighbors=    90  (default=0)
Reg/Force3DoF=                     true  (default=false)
Reg/Strategy=                      1  (default=0)
Rtabmap/DetectionRate=             3  (default=1)
Vis/CorNNDR=                       0.6  (default=0.8)
g2o/Optimizer=                     1  (default=0)

Info:

Path:               floor6_GN.db
Version:            0.20.7
Sessions:           4
Total odometry length:730.525818 m
Total time:         3964.549389s
LTM:                3732 nodes and 489613 words (dim=32 type=8U)
WM:                 2945 nodes and 484364 words
Global graph:       3732 poses and 11486 links
Optimized graph:    2945 poses
Maps in graph:      4/4 [0(377), 1(343), 2(47), 3(2178)]
Ground truth:       0 poses
GPS:                0 poses
Links:
  Neighbor:         5882
  GlobalClosure:    180
  LocalSpaceClosure:5424
  LocalTimeClosure: 0
  UserClosure:      0
  VirtualClosure:   0
  NeighborMerged:   0
  PosePrior:        0
  Landmark:         0
  Gravity:          0

Database size:      1287 MB
Nodes size:         600 KB (0.05%)
Links size:         4 MB (0.32%)
RGB Images size:    207 MB (16.08%)
Depth Images size:  715 MB (55.56%)
Calibrations size:  1 MB (0.11%)
Grids size:         131 MB (10.17%)
Scans size:         10 MB (0.79%)
User data size:     0 Bytes (0.00%)
Dictionary size:    28 MB (2.24%)
Features size:      199 MB (15.51%)
Statistics size:    5 MB (0.39%)
Other (indexing, unused):-15507089 Bytes (-1.20%)


The overall rtabmap-info is in the file below.
rtabmap_info.txt
Reply | Threaded
Open this post in threaded view
|

Re: Speeding up Rtabmap Without Memory Management

seanxu112
In reply to this post by matlabbe
Hello Mathieu,

Have you experimented with ceres solver with options: Solver::Options::num_threads? (http://ceres-solver.org/nnls_solving.html#_CPPv4N5ceres6Solver7Options11num_threadsE)

Sincerely,

Sean
Reply | Threaded
Open this post in threaded view
|

Re: Speeding up Rtabmap Without Memory Management

matlabbe
Administrator
Hi Sean,

I didn't play a lot with the Ceres optimizer, the num_threads option is interesting. This option could be added here.

From your database info, there are 11K links in the graph:
 Neighbor:         5882
 GlobalClosure:    180
 LocalSpaceClosure:5424 

A lot of them are "local space closures", which is why I pointed to proximity detections. Not sure what looks like your Graph (GraphView in rtabmap-databaseViewer), but some of these parameters could be tuned to avoid adding a new link every new node added (or add at most 1 link per new node):
rtabmap --params | grep RGBD/Proximity
e..g, setting RGBD/ProximityMaxPaths=1, or decreasing RGBD/LocalRadius (default 10 meters).

Afterwards, depending on the application, using rtabmap's memory management can help to limit the size of the graph over time. In this paper, the global graph had over 113K links. See also Figure 18 in this paper.

If you want to keep always all nodes in the Working Memory, approaches doing only local optimizations on the graph would have to be implemented. For example, for small loop closures, only nodes being part of that loop could be optimized, without touching the rest of the graph. However, for large loops (e.g., between first and last node in the map), the whole map would still need to be re-optimized.