localization with big db file

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

localization with big db file

dnozik
Hi ,
I am working on machine with 16GB RAM.
After mapping my rtabmap.db is ~50+GB file.
Trying to run in localization mode I getting crash on db file load.
Is there way not to load full db  file into memory ? or only remote ?
Thanks.
Reply | Threaded
Open this post in threaded view
|

Re: localization with big db file

matlabbe
Administrator
If you launch with "--udebug" argument, can you show the log untill it crashes?

Can you do also "rtabmap-info rtabmap.db" and show the results here ?
Reply | Threaded
Open this post in threaded view
|

Re: localization with big db file

dnozik
This post was updated on .
rtabmap-info /home/administrator/.ros/rtabmap.db 

Parameters (Yellow=modified, Red=old parameter not used anymore, NA=not in database):
ALIKE/Gpu=                         false
BRIEF/Bytes=                       32
BRISK/Octaves=                     3
BRISK/PatternScale=                1
BRISK/Thresh=                      30
Bayes/FullPredictionUpdate=        false
Bayes/PredictionLC=                0.1 0.36 0.30 0.16 0.062 0.0151 0.00255 0.000324 2.5e-05 1.3e-06 4.8e-08 1.2e-09 1.9e-11 2.2e-13 1.7e-15 8.5e-18 2.9e-20 6.9e-23
Bayes/VirtualPlacePriorThr=        0.9
Db/TargetVersion=                  1.0.3  (default=)
DbSqlite3/CacheSize=               10000
DbSqlite3/InMemory=                false
DbSqlite3/JournalMode=             3
DbSqlite3/Synchronous=             0
DbSqlite3/TempStore=               2
FAST/CV=                           0
FAST/Gpu=                          false
FAST/GpuKeypointsRatio=            0.05
FAST/GridCols=                     0
FAST/GridRows=                     0
FAST/MaxThreshold=                 200
FAST/MinThreshold=                 7
FAST/NonmaxSuppression=            true
FAST/Threshold=                    20
FE/Gpu=                            true
FE/Inputs=                         input_1
FE/Outputs=                        output_1 output_2 output_3
FREAK/NOctaves=                    4
FREAK/OrientationNormalized=       true
FREAK/PatternScale=                22
FREAK/ScaleNormalized=             true
GFTT/BlockSize=                    3
GFTT/K=                            0.04
GFTT/MinDistance=                  7
GFTT/QualityLevel=                 0.001
GFTT/UseHarrisDetector=            false
GMS/ThresholdFactor=               6.0
GMS/WithRotation=                  false
GMS/WithScale=                     false
GTSAM/Optimizer=                   1
Grid/3D=                           true
Grid/CellSize=                     0.05
Grid/ClusterRadius=                0.1
Grid/DepthDecimation=              4
Grid/DepthRoiRatios=               0.0 0.0 0.0 0.0
Grid/FlatObstacleDetected=         true
Grid/FootprintHeight=              0.0
Grid/FootprintLength=              0.0
Grid/FootprintWidth=               0.0
Grid/GroundIsObstacle=             false
Grid/MapFrameProjection=           false
Grid/MaxGroundAngle=               45
Grid/MaxGroundHeight=              0.02
Grid/MaxObstacleHeight=            0.4
Grid/MinClusterSize=               10
Grid/MinGroundHeight=              0.0
Grid/NoiseFilteringMinNeighbors=   5
Grid/NoiseFilteringRadius=         0.0
Grid/NormalK=                      20
Grid/NormalsSegmentation=          true
Grid/PreVoxelFiltering=            true
Grid/RangeMax=                     4.0
Grid/RangeMin=                     0.0
Grid/RayTracing=                   false  (default=true)
Grid/Scan2dUnknownSpaceFilled=     false
Grid/ScanDecimation=               1
Grid/Sensor=                       1
GridGlobal/AltitudeDelta=          0
GridGlobal/Eroded=                 false
GridGlobal/FloodFillDepth=         0
GridGlobal/FootprintRadius=        0.0
GridGlobal/FullUpdate=             true
GridGlobal/MaxNodes=               0
GridGlobal/MinSize=                0.0
GridGlobal/OccupancyThr=           0.5
GridGlobal/ProbClampingMax=        0.971
GridGlobal/ProbClampingMin=        0.1192
GridGlobal/ProbHit=                0.7
GridGlobal/ProbMiss=               0.4
GridGlobal/UpdateError=            0.01
Icp/CCFilterOutFarthestPoints=     false
Icp/CCMaxFinalRMS=                 0.2
Icp/CCSamplingLimit=               50000
Icp/CorrespondenceRatio=           0.1
Icp/DownsamplingStep=              1
Icp/Epsilon=                       0
Icp/Force4DoF=                     false
Icp/Iterations=                    30
Icp/MaxCorrespondenceDistance=     0.1
Icp/MaxRotation=                   0.78
Icp/MaxTranslation=                0.2
Icp/OutlierRatio=                  0.85
Icp/PMMatcherEpsilon=              0.0
Icp/PMMatcherIntensity=            false
Icp/PMMatcherKnn=                  1
Icp/PointToPlane=                  true
Icp/PointToPlaneGroundNormalsUp=   0.0
Icp/PointToPlaneK=                 5
Icp/PointToPlaneLowComplexityStrategy=1
Icp/PointToPlaneMinComplexity=     0.02
Icp/PointToPlaneRadius=            0.0
Icp/RangeMax=                      0
Icp/RangeMin=                      0
Icp/ReciprocalCorrespondences=     true
Icp/Strategy=                      1
Icp/VoxelSize=                     0.05
ImuFilter/ComplementaryBiasAlpha=  0.01
ImuFilter/ComplementaryDoAdpativeGain=true
ImuFilter/ComplementaryDoBiasEstimation=true
ImuFilter/ComplementaryGainAcc=    0.01
ImuFilter/MadgwickGain=            0.1
ImuFilter/MadgwickZeta=            0.0
KAZE/Diffusivity=                  1
KAZE/Extended=                     false
KAZE/NOctaveLayers=                4
KAZE/NOctaves=                     4
KAZE/Threshold=                    0.001
KAZE/Upright=                      false
Kp/BadSignRatio=                   0.5
Kp/ByteToFloat=                    false
Kp/DetectorStrategy=               8
Kp/FeatureCameras=                 0.3  (default=0,1,2,3)
Kp/FlannRebalancingFactor=         2.0
Kp/FlipCameras=                    true
Kp/GridCols=                       1
Kp/GridRows=                       1
Kp/IncrementalDictionary=          true
Kp/IncrementalFlann=               true
Kp/MaxDepth=                       0
Kp/MaxFeatures=                    2000  (default=1000)
Kp/MinDepth=                       0
Kp/NNStrategy=                     1
Kp/NewWordsComparedTogether=       true
Kp/NndrRatio=                      0.7
Kp/Parallelized=                   true
Kp/RoiRatios=                      0.0 0.0 0.0 0.0
Kp/SubPixEps=                      0.02
Kp/SubPixIterations=               0
Kp/SubPixWinSize=                  3
Kp/TfIdfLikelihoodUsed=            true
Marker/CornerRefinementMethod=     0
Marker/Dictionary=                 20
Marker/Length=                     0.169  (default=0)
Marker/MaxDepthError=              0.1
Marker/MaxRange=                   1.5  (default=0.0)
Marker/MinRange=                   0.1  (default=0.0)
Marker/PriorsVarianceAngular=      0.001
Marker/PriorsVarianceLinear=       0.001
Marker/VarianceAngular=            0.1  (default=0.01)
Marker/VarianceLinear=             0.5  (default=0.001)
Mem/BadSignaturesIgnored=          false
Mem/BinDataKept=                   true
Mem/CompressionParallelized=       true
Mem/CovOffDiagIgnored=             true
Mem/DepthAsMask=                   true
Mem/GenerateIds=                   true
Mem/ImageCompressionFormat=        .jpg
Mem/ImageKept=                     false
Mem/ImagePostDecimation=           1
Mem/ImagePreDecimation=            1
Mem/IncrementalMemory=             true
Mem/InitWMWithAllNodes=            false
Mem/IntermediateNodeDataKept=      false
Mem/LaserScanDownsampleStepSize=   1
Mem/LaserScanNormalK=              0
Mem/LaserScanNormalRadius=         0.0
Mem/LaserScanVoxelSize=            0.0
Mem/LocalizationDataSaved=         false
Mem/MapLabelsAdded=                true
Mem/NotLinkedNodesKept=            true
Mem/RawDescriptorsKept=            true
Mem/RecentWmRatio=                 0.2
Mem/ReduceGraph=                   false
Mem/RehearsalIdUpdatedToNewOne=    false
Mem/RehearsalSimilarity=           0.6
Mem/RehearsalWeightIgnoredWhileMoving=false
Mem/STMSize=                       10
Mem/SaveDepth16Format=             false
Mem/StereoFromMotion=              false
Mem/TransferSortingByWeightId=     false
Mem/UseOdomFeatures=               false  (default=true)
Mem/UseOdomGravity=                false
ORB/EdgeThreshold=                 19
ORB/FirstLevel=                    0
ORB/Gpu=                           false
ORB/NLevels=                       3
ORB/PatchSize=                     31
ORB/ScaleFactor=                   2
ORB/ScoreType=                     0
ORB/WTA_K=                         2
Odom/AlignWithGround=              false
Odom/FillInfoData=                 true
Odom/FilteringStrategy=            0
Odom/GuessMotion=                  true
Odom/GuessSmoothingDelay=          0
Odom/Holonomic=                    true
Odom/ImageBufferSize=              1
Odom/ImageDecimation=              1
Odom/KalmanMeasurementNoise=       0.01
Odom/KalmanProcessNoise=           0.001
Odom/KeyFrameThr=                  0.3
Odom/ParticleLambdaR=              100
Odom/ParticleLambdaT=              100
Odom/ParticleNoiseR=               0.002
Odom/ParticleNoiseT=               0.002
Odom/ParticleSize=                 400
Odom/ResetCountdown=               0
Odom/ScanKeyFrameThr=              0.9
Odom/Strategy=                     0
Odom/VisKeyFrameThr=               150
OdomF2M/BundleAdjustment=          1
OdomF2M/BundleAdjustmentMaxFrames= 10
OdomF2M/MaxNewFeatures=            0
OdomF2M/MaxSize=                   2000
OdomF2M/ReplaceFarMapPoints=       false
OdomF2M/ReplaceMPsMinDepth=        2.0
OdomF2M/ReplaceMPsThreshold=       0.9
OdomF2M/ScanMaxSize=               2000
OdomF2M/ScanRange=                 0
OdomF2M/ScanSubtractAngle=         45
OdomF2M/ScanSubtractRadius=        0.05
OdomF2M/ValidDepthRatio=           0.75
OdomFovis/BucketHeight=            80
OdomFovis/BucketWidth=             80
OdomFovis/CliqueInlierThreshold=   0.1
OdomFovis/FastThreshold=           20
OdomFovis/FastThresholdAdaptiveGain=0.005
OdomFovis/FeatureSearchWindow=     25
OdomFovis/FeatureWindowSize=       9
OdomFovis/InlierMaxReprojectionError=1.5
OdomFovis/MaxKeypointsPerBucket=   25
OdomFovis/MaxMeanReprojectionError=10.0
OdomFovis/MaxPyramidLevel=         3
OdomFovis/MinFeaturesForEstimate=  20
OdomFovis/MinPyramidLevel=         0
OdomFovis/StereoMaxDisparity=      128
OdomFovis/StereoMaxDistEpipolarLine=1.5
OdomFovis/StereoMaxRefinementDisplacement=1.0
OdomFovis/StereoRequireMutualMatch=true
OdomFovis/TargetPixelsPerFeature=  250
OdomFovis/UpdateTargetFeaturesWithRefined=false
OdomFovis/UseAdaptiveThreshold=    true
OdomFovis/UseBucketing=            true
OdomFovis/UseHomographyInitialization=true
OdomFovis/UseImageNormalization=   false
OdomFovis/UseSubpixelRefinement=   true
OdomLOAM/AngVar=                   0.01
OdomLOAM/LinVar=                   0.01
OdomLOAM/LocalMapping=             true
OdomLOAM/Resolution=               0.2
OdomLOAM/ScanPeriod=               0.1
OdomLOAM/Sensor=                   2
OdomMSCKF/FastThreshold=           10
OdomMSCKF/GridCol=                 5
OdomMSCKF/GridMaxFeatureNum=       4
OdomMSCKF/GridMinFeatureNum=       3
OdomMSCKF/GridRow=                 4
OdomMSCKF/InitCovAccBias=          0.01
OdomMSCKF/InitCovExRot=            0.00030462
OdomMSCKF/InitCovExTrans=          0.000025
OdomMSCKF/InitCovGyroBias=         0.01
OdomMSCKF/InitCovVel=              0.25
OdomMSCKF/MaxCamStateSize=         20
OdomMSCKF/MaxIteration=            30
OdomMSCKF/NoiseAcc=                0.05
OdomMSCKF/NoiseAccBias=            0.01
OdomMSCKF/NoiseFeature=            0.035
OdomMSCKF/NoiseGyro=               0.005
OdomMSCKF/NoiseGyroBias=           0.001
OdomMSCKF/OptTranslationThreshold= 0
OdomMSCKF/PatchSize=               15
OdomMSCKF/PositionStdThreshold=    8.0
OdomMSCKF/PyramidLevels=           3
OdomMSCKF/RansacThreshold=         3
OdomMSCKF/RotationThreshold=       0.2618
OdomMSCKF/StereoThreshold=         5
OdomMSCKF/TrackPrecision=          0.01
OdomMSCKF/TrackingRateThreshold=   0.5
OdomMSCKF/TranslationThreshold=    0.4
OdomMono/InitMinFlow=              100
OdomMono/InitMinTranslation=       0.1
OdomMono/MaxVariance=              0.01
OdomMono/MinTranslation=           0.02
OdomORBSLAM/Bf=                    0.076
OdomORBSLAM/Fps=                   0.0
OdomORBSLAM/MapSize=               3000
OdomORBSLAM/MaxFeatures=           1000
OdomORBSLAM/ThDepth=               40.0
OdomOpen3D/MaxDepth=               3.0
OdomOpen3D/Method=                 0
OdomViso2/BucketHeight=            50
OdomViso2/BucketMaxFeatures=       2
OdomViso2/BucketWidth=             50
OdomViso2/InlierThreshold=         2.0
OdomViso2/MatchBinsize=            50
OdomViso2/MatchDispTolerance=      2
OdomViso2/MatchHalfResolution=     true
OdomViso2/MatchMultiStage=         true
OdomViso2/MatchNmsN=               3
OdomViso2/MatchNmsTau=             50
OdomViso2/MatchOutlierDispTolerance=5
OdomViso2/MatchOutlierFlowTolerance=5
OdomViso2/MatchRadius=             200
OdomViso2/MatchRefinement=         1
OdomViso2/RansacIters=             200
OdomViso2/Reweighting=             true
Optimizer/Epsilon=                 0.0
Optimizer/GravitySigma=            0.3
Optimizer/Iterations=              20
Optimizer/LandmarksIgnored=        false
Optimizer/PriorsIgnored=           false
Optimizer/Robust=                  false
Optimizer/Strategy=                1
Optimizer/VarianceIgnored=         false
PyDetector/Cuda=                   true
PyDetector/RGB=                    true
PyMatcher/Cuda=                    true
PyMatcher/Iterations=              20
PyMatcher/Model=                   indoor
PyMatcher/Threshold=               0.2
RGBD/AngularSpeedUpdate=           1.5
RGBD/AngularUpdate=                0.2
RGBD/CreateOccupancyGrid=          true  (default=false)
RGBD/Enabled=                      true
RGBD/GoalReachedRadius=            0.5
RGBD/GoalsSavedInUserData=         false
RGBD/InvertedReg=                  false
RGBD/LinearSpeedUpdate=            1.0
RGBD/LinearUpdate=                 0.2
RGBD/LocalBundleOnLoopClosure=     false
RGBD/LocalImmunizationRatio=       0.25
RGBD/LocalRadius=                  10
RGBD/LocalizationSmoothing=        true
RGBD/LoopClosureIdentityGuess=     false
RGBD/LoopClosureReextractFeatures= false
RGBD/LoopCovLimited=               false
RGBD/MarkerDetection=              false
RGBD/MaxLocalRetrieved=            2
RGBD/MaxLoopClosureDistance=       0.0
RGBD/MaxOdomCacheSize=             10
RGBD/NeighborLinkRefining=         false
RGBD/NewMapOdomChangeDistance=     0
RGBD/OptimizeFromGraphEnd=         false
RGBD/OptimizeMaxError=             3  (default=2.0)
RGBD/PlanAngularVelocity=          0
RGBD/PlanLinearVelocity=           0
RGBD/PlanStuckIterations=          0
RGBD/ProximityAngle=               180  (default=45)
RGBD/ProximityBySpace=             true
RGBD/ProximityByTime=              false
RGBD/ProximityGlobalScanMap=       false
RGBD/ProximityMaxGraphDepth=       50
RGBD/ProximityMaxPaths=            3
RGBD/ProximityMergedScanCovFactor= 100.0
RGBD/ProximityOdomGuess=           false
RGBD/ProximityPathFilteringRadius= 1
RGBD/ProximityPathMaxNeighbors=    0
RGBD/ProximityPathRawPosesUsed=    true
RGBD/ScanMatchingIdsSavedInLinks=  true
RGBD/StartAtOrigin=                true  (default=false)
RGBD/StartUnknown=                 true
Reg/Force3DoF=                     true  (default=false)
Reg/RepeatOnce=                    true
Reg/Strategy=                      0
Rtabmap/ComputeRMSE=               true
Rtabmap/CreateIntermediateNodes=   false
Rtabmap/DetectionRate=             10  (default=1)
Rtabmap/ImageBufferSize=           1
Rtabmap/ImagesAlreadyRectified=    true
Rtabmap/LoopGPS=                   true
Rtabmap/LoopRatio=                 0
Rtabmap/LoopThr=                   0.11
Rtabmap/MaxRepublished=            2
Rtabmap/MaxRetrieved=              2
Rtabmap/MemoryThr=                 0
Rtabmap/PublishLastSignature=      true
Rtabmap/PublishLikelihood=         true
Rtabmap/PublishPdf=                true
Rtabmap/PublishRAMUsage=           false
Rtabmap/PublishStats=              true
Rtabmap/RectifyOnlyFeatures=       false
Rtabmap/SaveWMState=               false
Rtabmap/StartNewMapOnGoodSignature=false
Rtabmap/StartNewMapOnLoopClosure=  false
Rtabmap/StatisticLogged=           false
Rtabmap/StatisticLoggedHeaders=    true
Rtabmap/StatisticLogsBufferedInRAM=true
Rtabmap/TimeThr=                   0
SIFT/ContrastThreshold=            0.04
SIFT/EdgeThreshold=                10
SIFT/NFeatures=                    0
SIFT/NOctaveLayers=                3
SIFT/RootSIFT=                     false
SIFT/Sigma=                        1.6
SURF/Extended=                     false
SURF/GpuKeypointsRatio=            0.01
SURF/GpuVersion=                   false
SURF/HessianThreshold=             500
SURF/OctaveLayers=                 2
SURF/Octaves=                      4
SURF/Upright=                      false
Stereo/DenseStrategy=              0
Stereo/Eps=                        0.01
Stereo/Iterations=                 30
Stereo/MaxDisparity=               128.0
Stereo/MaxLevel=                   5
Stereo/MinDisparity=               0.5
Stereo/OpticalFlow=                true
Stereo/SSD=                        true
Stereo/WinHeight=                  3
Stereo/WinWidth=                   15
StereoBM/BlockSize=                15
StereoBM/Disp12MaxDiff=            -1
StereoBM/MinDisparity=             0
StereoBM/NumDisparities=           128
StereoBM/PreFilterCap=             31
StereoBM/PreFilterSize=            9
StereoBM/SpeckleRange=             4
StereoBM/SpeckleWindowSize=        100
StereoBM/TextureThreshold=         10
StereoBM/UniquenessRatio=          15
StereoSGBM/BlockSize=              15
StereoSGBM/Disp12MaxDiff=          1
StereoSGBM/MinDisparity=           0
StereoSGBM/Mode=                   2
StereoSGBM/NumDisparities=         128
StereoSGBM/P1=                     2
StereoSGBM/P2=                     5
StereoSGBM/PreFilterCap=           31
StereoSGBM/SpeckleRange=           4
StereoSGBM/SpeckleWindowSize=      100
StereoSGBM/UniquenessRatio=        20
SuperPoint/Cuda=                   true
SuperPoint/NMS=                    true
SuperPoint/NMSRadius=              4
SuperPoint/Threshold=              0.010
VhEp/Enabled=                      false
VhEp/MatchCountMin=                8
VhEp/RansacParam1=                 3
VhEp/RansacParam2=                 0.99
Vis/BundleAdjustment=              0
Vis/CorFlowEps=                    0.01
Vis/CorFlowIterations=             30
Vis/CorFlowMaxLevel=               3
Vis/CorFlowWinSize=                16
Vis/CorGuessMatchToProjection=     false
Vis/CorGuessWinSize=               0
Vis/CorNNDR=                       0.8
Vis/CorNNType=                     1
Vis/CorType=                       0
Vis/DepthAsMask=                   true
Vis/EpipolarGeometryVar=           0.1
Vis/EstimationType=                1
Vis/FeatureType=                   16  (default=8)
Vis/ForwardEstOnly=                true
Vis/GridCols=                      1
Vis/GridRows=                      1
Vis/InlierDistance=                0.1
Vis/Iterations=                    500
Vis/MaxDepth=                      0
Vis/MaxFeatures=                   -1  (default=1000)
Vis/MeanInliersDistance=           0.0
Vis/MinDepth=                      0
Vis/MinInliers=                    40  (default=30)
Vis/MinInliersDistribution=        0.0
Vis/PnPFlags=                      0
Vis/PnPMaxVariance=                0
Vis/PnPRefineIterations=           0
Vis/PnPReprojError=                2
Vis/PnPSamplingPolicy=             1
Vis/RefineIterations=              5
Vis/RoiRatios=                     0.0 0.0 0.0 0.0
Vis/SubPixEps=                     0.02
Vis/SubPixIterations=              0
Vis/SubPixWinSize=                 3
g2o/Baseline=                      0.075
g2o/Optimizer=                     0
g2o/PixelVariance=                 1.0
g2o/RobustKernelDelta=             8
g2o/Solver=                        0
FE/ModelPath=                      NA  (default="")
Icp/DebugExportFormat=             NA  (default="")
Icp/PMConfig=                      NA  (default="")
Kp/DictionaryPath=                 NA  (default="")
Marker/Priors=                     NA  (default="")
Marker/PriorsFile=                 NA  (default="")
OdomOKVIS/ConfigPath=              NA  (default="")
OdomORBSLAM/VocPath=               NA  (default="")
OdomVINS/ConfigPath=               NA  (default="")
PyDetector/Path=                   NA  (default="")
PyMatcher/Path=                    NA  (default="")
Rtabmap/WorkingDirectory=          NA  (default="")
SuperPoint/ModelPath=              NA  (default="")

Info:

Path:               /home/administrator/.ros/rtabmap.db
Version:            1.0.3
Sessions:           1
Total odometry length:1432.233887 m
Total time:         4582.739898s
LTM:                30997 nodes and 8803876 words (dim=32 type=8U)
WM:                 5930 nodes and 8684994 words
Global graph:       30997 poses and 13174 links
Optimized graph:    5930 poses (x=13174->-65, y=7->-57, z=6->0)
Maps in graph:      1/1 [0(5930)]
Ground truth:       0 poses
GPS:                0 poses
Links:
  Neighbor:         11858
  GlobalClosure:    960
  LocalSpaceClosure:356
  LocalTimeClosure: 0
  UserClosure:      0
  VirtualClosure:   0
  NeighborMerged:   0
  PosePrior:        0
  Landmark:         0
  Gravity:          0

Database size:      60593 MB
Nodes size:         4 MB	(0.01%)
Links size:         4 MB	(0.01%)
RGB Images size:    14495 MB	(23.92%)
Depth Images size:  36031 MB	(59.46%)
Calibrations size:  41 MB	(0.07%)
Grids size:         2834 MB	(4.68%)
Scans size:         0 Bytes	(0.00%)
User data size:     0 Bytes	(0.00%)
Dictionary size:    534 MB	(0.88%)
Features size:      7441 MB	(12.28%)
Statistics size:    38 MB	(0.06%)
Other (indexing, unused):-832196637 Bytes	(-1.37%)


udebug
DEBUG] (2023-12-17 10:09:42.369) CameraModel.cpp:556::deserialize() Header: 1 0 3 0 640 480 9 0 9 12 12
[DEBUG] (2023-12-17 10:09:42.369) CameraModel.cpp:556::deserialize() Header: 1 0 3 0 640 480 9 0 9 12 12
[DEBUG] (2023-12-17 10:09:42.369) DBDriverSqlite3.cpp:3472::loadSignaturesQuery() Time load 5930 calibrations=7.198363s
[DEBUG] (2023-12-17 10:09:42.384) DBDriverSqlite3.cpp:3539::loadSignaturesQuery() Time load 5930 global descriptors=0.015006s
[DEBUG] (2023-12-17 10:09:42.387) Memory.cpp:350::loadDataFromDb() Get labels
[DEBUG] (2023-12-17 10:09:42.387) DBDriverSqlite3.cpp:2871::getAllLabelsQuery() Time=0.000248
[DEBUG] (2023-12-17 10:09:42.387) Memory.cpp:353::loadDataFromDb() Check if all nodes are in Working Memory
[DEBUG] (2023-12-17 10:09:42.388) Memory.cpp:365::loadDataFromDb() allNodesInWM()=true
[DEBUG] (2023-12-17 10:09:42.388) Memory.cpp:367::loadDataFromDb() update odomMaxInf vector
[DEBUG] (2023-12-17 10:09:42.430) Memory.cpp:389::loadDataFromDb() update odomMaxInf vector, done!
[DEBUG] (2023-12-17 10:09:42.430) DBDriverSqlite3.cpp:2641::getLastIdQuery() get last id from table "Node"
[DEBUG] (2023-12-17 10:09:42.431) DBDriverSqlite3.cpp:2672::getLastIdQuery() Time=0.001004s
[DEBUG] (2023-12-17 10:09:42.431) DBDriverSqlite3.cpp:2641::getLastIdQuery() get last id from table "Statistics"
[DEBUG] (2023-12-17 10:09:42.431) DBDriverSqlite3.cpp:2672::getLastIdQuery() Time=0.000098s
[DEBUG] (2023-12-17 10:09:42.431) DBDriverSqlite3.cpp:2641::getLastIdQuery() get last map_id from table "Node"
[DEBUG] (2023-12-17 10:09:42.433) DBDriverSqlite3.cpp:2672::getLastIdQuery() Time=0.002494s
[DEBUG] (2023-12-17 10:09:42.433) Memory.cpp:412::loadDataFromDb() Loading dictionary...
[DEBUG] (2023-12-17 10:09:42.433) Memory.cpp:416::loadDataFromDb() load all referenced words in working memory
[DEBUG] (2023-12-17 10:09:45.191) Memory.cpp:433::loadDataFromDb() load words 8684994
[DEBUG] (2023-12-17 10:09:45.438) DBDriverSqlite3.cpp:3690::loadWordsQuery() size=8684994
[DEBUG] (2023-12-17 10:10:10.768) DBDriverSqlite3.cpp:3767::loadWordsQuery() Time=25.329514s (8684994 words, 277 MB)
[DEBUG] (2023-12-17 10:10:18.088) DBDriverSqlite3.cpp:2641::getLastIdQuery() get last id from table "Word"
[DEBUG] (2023-12-17 10:10:18.088) DBDriverSqlite3.cpp:2672::getLastIdQuery() Time=0.000079s
[DEBUG] (2023-12-17 10:10:18.304) Memory.cpp:465::loadDataFromDb() 8684994 words loaded!
[DEBUG] (2023-12-17 10:10:18.304) VWDictionary.cpp:505::update() incremental=1
[DEBUG] (2023-12-17 10:10:18.304) VWDictionary.cpp:526::update() Incremental FLANN: Removing 0 words...
[DEBUG] (2023-12-17 10:10:18.304) VWDictionary.cpp:535::update() Incremental FLANN: Removing 0 words... done!
[DEBUG] (2023-12-17 10:10:18.304) VWDictionary.cpp:539::update() Incremental FLANN: Inserting 8684994 words...
[DEBUG] (2023-12-17 10:10:18.497) VWDictionary.cpp:566::update() Building FLANN index...
[DEBUG] (2023-12-17 10:10:18.497) FlannIndex.cpp:238::buildKDTreeIndex() 
[DEBUG] (2023-12-17 10:10:18.497) FlannIndex.cpp:82::release() 
[DEBUG] (2023-12-17 10:10:18.497) FlannIndex.cpp:110::release() 
[DEBUG] (2023-12-17 10:10:18.498) FlannIndex.cpp:290::buildKDTreeIndex() 
[DEBUG] (2023-12-17 10:10:18.498) VWDictionary.cpp:584::update() Building FLANN index... done!
[DEBUG] (2023-12-17 10:10:18.499) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 1 -> 3
[DEBUG] (2023-12-17 10:10:18.502) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 3.2921ms
[DEBUG] (2023-12-17 10:10:18.503) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 3 -> 7
[DEBUG] (2023-12-17 10:10:18.504) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 0.5620ms
[DEBUG] (2023-12-17 10:10:18.509) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 7 -> 15
[DEBUG] (2023-12-17 10:10:18.509) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 0.5460ms
[DEBUG] (2023-12-17 10:10:18.520) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 15 -> 31
[DEBUG] (2023-12-17 10:10:18.521) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 0.6351ms
[DEBUG] (2023-12-17 10:10:18.542) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 31 -> 63
[DEBUG] (2023-12-17 10:10:18.543) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 0.7570ms
[DEBUG] (2023-12-17 10:10:18.586) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 63 -> 127
[DEBUG] (2023-12-17 10:10:18.588) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 1.2801ms
[DEBUG] (2023-12-17 10:10:18.621) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 127 -> 255
[DEBUG] (2023-12-17 10:10:18.622) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 0.8330ms
[DEBUG] (2023-12-17 10:10:18.623) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 255 -> 511
[DEBUG] (2023-12-17 10:10:18.624) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 1.6329ms
[DEBUG] (2023-12-17 10:10:18.626) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 511 -> 1023
[DEBUG] (2023-12-17 10:10:18.629) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 3.3090ms
[DEBUG] (2023-12-17 10:10:18.631) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 1023 -> 2047
[DEBUG] (2023-12-17 10:10:18.638) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 6.8440ms
[DEBUG] (2023-12-17 10:10:18.643) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 2047 -> 4095
[DEBUG] (2023-12-17 10:10:18.658) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 14.9601ms
[DEBUG] (2023-12-17 10:10:18.667) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 4095 -> 8191
[DEBUG] (2023-12-17 10:10:18.696) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 29.0890ms
[DEBUG] (2023-12-17 10:10:18.716) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 8191 -> 16383
[DEBUG] (2023-12-17 10:10:18.777) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 61.5981ms
[DEBUG] (2023-12-17 10:10:18.825) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 16383 -> 32767
[DEBUG] (2023-12-17 10:10:18.956) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 130.9710ms
[DEBUG] (2023-12-17 10:10:19.070) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 32767 -> 65535
[DEBUG] (2023-12-17 10:10:19.348) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 278.0912ms
[DEBUG] (2023-12-17 10:10:19.602) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 65535 -> 131071
[DEBUG] (2023-12-17 10:10:20.180) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 577.9569ms
[DEBUG] (2023-12-17 10:10:20.747) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 131071 -> 262143
[DEBUG] (2023-12-17 10:10:21.938) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 1190.9089ms
[DEBUG] (2023-12-17 10:10:23.293) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 262143 -> 524287
[DEBUG] (2023-12-17 10:10:25.791) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 2497.8521ms
[DEBUG] (2023-12-17 10:10:28.953) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 524287 -> 1048575
[DEBUG] (2023-12-17 10:10:34.211) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 5257.9980ms
[DEBUG] (2023-12-17 10:10:41.209) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 1048575 -> 2097151
[DEBUG] (2023-12-17 10:10:52.487) FlannIndex.cpp:450::addPoints() [FLANN] Rebuilding FLANN index took: 11277.7572ms
[DEBUG] (2023-12-17 10:11:07.768) FlannIndex.cpp:448::addPoints() Rebuilding FLANN index: 2097151 -> 4194303
[DEBUG] (2023-12-17 10
Reply | Threaded
Open this post in threaded view
|

Re: localization with big db file

matlabbe
Administrator

I don't feel it is a memory issue, unless in your system monitor you can clearly see that RAM is full when it crashes.

The flann index is taken a while to update though, with 8M words. From the log, it "seems" crashing while updating the flann index. I

Are you using ros? You may launch rtabmap node in gdb to get a more precise debug trace, see section A of this post: https://github.com/introlab/rtabmap_ros/issues/28, don't forget `bt` after it crashed.

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

Re: localization with big db file

dnozik
Hi Mathieu.
I am using top tool to check rtabmap memory usage.
I am using ros.

1.Before loading dictoinary rtabmap Mem~1.5GB
2.After call to :
                        UDEBUG("load words");

                        // load the last dictionary

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

   Mem~6-6.5GB is 40% total Ram  (sizeof(VisualWord) = 208B)

3.During call to _vwd->update(); Mem usage raising to 80% of Ram and rtabmap crashing.

Is that sound logical to crash in dictionary update with 8M words ?
Thanks.
Reply | Threaded
Open this post in threaded view
|

Re: localization with big db file

matlabbe
Administrator
Hi,

I compared with a large map that I made recently (note that I removed the raw image data, from 14GB to 1.6GB):
Version:            0.21.3
Sessions:           4
Total odometry length:7949.869629 m
Total time:         11374.330171s
LTM:                10351 nodes and 3486621 words (dim=32 type=8U)
WM:                 9037 nodes and 3477496 words
Global graph:       10351 poses and 27140 links
Optimized graph:    9037 poses (x=27140->-14, y=145->-75, z=53->0)
Maps in graph:      4/4 [0(2295), 1(1773), 2(2267), 3(2702)]
Ground truth:       0 poses
GPS:                0 poses
Links:
  Neighbor:         18066
  GlobalClosure:    3578
  LocalSpaceClosure:1552
  LocalTimeClosure: 0
  UserClosure:      3944
  VirtualClosure:   0
  NeighborMerged:   0
  PosePrior:        0
  Landmark:         0
  Gravity:          0

Database size:      1653 MB
Nodes size:         1 MB	(0.10%)
Links size:         9 MB	(0.57%)
RGB Images size:    0 Bytes	(0.00%)
Depth Images size:  0 Bytes	(0.00%)
Calibrations size:  16 MB	(0.99%)
Grids size:         442 MB	(26.73%)
Scans size:         0 Bytes	(0.00%)
User data size:     0 Bytes	(0.00%)
Dictionary size:    208 MB	(12.59%)
Features size:      1045 MB	(63.23%)
Statistics size:    12 MB	(0.78%)

For 7 times less distance, you got 3 times more nodes and a dictionary of 8M words. Not sure what the robot is doing at what speed, but do you really need Rtabmap/DetectionRate=10 and Kp/MaxFeatures=2000? For the actual issue, on this database above (using default parameters), for 3.5M, I see RAM usage increasing to 8.7 GB. For 8M, I guess it could go over 16 GB of RAM like you observed. As you are using binary features, you may set parameter Kp/ByteToFloat to true:
Param: Kp/ByteToFloat = "false"                            [For Kp/NNStrategy=1, binary descriptors are converted to float by converting each byte to float instead of converting each bit to float. When converting bytes instead of bits, less memory is used and search is faster at the cost of slightly less accurate matching.]
On my computer, doing so I get 5.8 GB instead of 8.7 GB. I would suggest however that you reprocess your database with Kp/MaxFeatures=500 (default) to cut approximatly by 4 the dictionary size (2M instead of 8M):
rtabmap-reprocess --Kp/MaxFeatures=500 rtabmap.db output.db

Another option would be to use a fixed-size dictionary of 1M words for example.

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

Re: localization with big db file

dnozik
Hi Mathieu,
How did you remove raw image data ? Post reprocess or during mapping ?
Thanks,
Dima.
Reply | Threaded
Open this post in threaded view
|

Re: localization with big db file

matlabbe
Administrator
See https://github.com/introlab/rtabmap_ros/issues/671#issuecomment-1272734472

For Mem/BinDataKept, instead of reprocessing, you could delete the data from the database with a sqlite3 query.

sqlite3 rtabmap.db "UPDATE Data SET image = null, depth=null"
sqlite3 rtabmap.db 'VACUUM;'

You may then have to shrink the database afterwards.
Reply | Threaded
Open this post in threaded view
|

Re: localization with big db file

dnozik
Hi , thank you for your reply.
What If I don't want to keep binary data in signature to reduce RAM usage? After feature extraction there no need in images?!
Thanks.
Dima.
Reply | Threaded
Open this post in threaded view
|

Re: localization with big db file

matlabbe
Administrator
Yeah, you can disable image saving by setting Mem/BinDataKept to false. However, it may make it more difficult to debug the database afterwards as you will only see features (also trying other visual features down the road won't be possible either with that database).