Loop Closure Parameters

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

Loop Closure Parameters

minato_99
This post was updated on .
CONTENTS DELETED
The author has deleted this message.
Reply | Threaded
Open this post in threaded view
|

Re: Loop Closure Parameters

matlabbe
Administrator
Not sure to understand what you are referring by increasing time for loop closure. Yes, rtabmap will automatically close loops  when they are detected. The detection rate is 1 Hz by default (Rtabmap/DetectionRate parameter), is it the frequency that you want to decrease?

You can also increase the STM size (Mem/STMSize parameter) to avoid loop closures on nodes that were just seen.

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

Re: Loop Closure Parameters

minato_99
This post was updated on .
CONTENTS DELETED
The author has deleted this message.
Reply | Threaded
Open this post in threaded view
|

Re: Loop Closure Parameters

minato_99
This post was updated on .
In reply to this post by matlabbe
Hello matlabbe,


I am trying to map 20 m by 20 m area with a rover. The problem I was facing is that when I tried to map all the area at once. There was a loop closures at different locations than where it supposed to. It warped the map very badly. The reason could be lack of enough differentiating textures.  So, I navigate a certain region and come back to the place where I started to enforce the loop closure. It did work for me. However, there are few corners showing up in my map. I have attached the image  and database along with the code. Can you please help me figure out the problem?

code:
<?xml version="1.0" encoding="UTF-8"?>

<launch>

  <arg name="rtabmapviz"              default="false" />
  <arg name="rviz"                    default="true" />
 
  <arg name="localization"            default="false"/>

<arg name="pi/2" value="1.5707963267948966" />
<arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2) " />
<arg name="optical_rotate2" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)  " />                                                               
<node pkg="tf2_ros" type="static_transform_publisher" name="camera_chassis"
     args="$(arg optical_rotate) chassis camera" /> 
     
<group ns="/stereo" >
    <node pkg="stereo_image_proc" type="stereo_image_proc" name="stereo_image_proc"/>

    <node pkg="rtabmap_odom" type="stereo_odometry" name="stereo_odometry" output="screen">
   <remap from="left/image_rect"   to="left/image_rect_color"/>
     <remap from="right/image_rect"  to="right/image_rect"/>
     <remap from="left/camera_info"  to="left/camera_info"/>
     <remap from="right/camera_info" to="right/camera_info"/>
     
    </node>     
</group> 

<group ns="rtabmap">   
  <node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="delete_db_on_start"> 
 
        <remap from="left/image_rect"       to="/stereo/left/image_raw"/>
        <remap from="right/image_rect"      to="/stereo/right/image_raw"/>
        <remap from="left/camera_info"      to="/stereo/left/camera_info"/>
        <remap from="right/camera_info"     to="/stereo/right/camera_info"/>
       <remap from="odom" to="/stereo/odom"/>

  </node>
 </group>
 
  
 
   <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_demos)/launch/config/demo_stereo_outdoor.rviz"/> 
   
</launch>

Image:


Database:
rtabmap-info /home/rakesh/.ros/rtabmap_best_so_far.db
Parameters (Yellow=modified, Red=old parameter not used anymore, NA=not in database):
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
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
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.0
Grid/MaxObstacleHeight=            0.0
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=                     5.0
Grid/RangeMin=                     0.0
Grid/RayTracing=                   false
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/FlannRebalancingFactor=         2.0
Kp/GridCols=                       1
Kp/GridRows=                       1
Kp/IncrementalDictionary=          true
Kp/IncrementalFlann=               true
Kp/MaxDepth=                       2  (default=0)
Kp/MaxFeatures=                    500
Kp/MinDepth=                       0
Kp/NNStrategy=                     1
Kp/NewWordsComparedTogether=       true
Kp/NndrRatio=                      0.8
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=                 0
Marker/Length=                     0
Marker/MaxDepthError=              0.01
Marker/MaxRange=                   0.0
Marker/MinRange=                   0.0
Marker/PriorsVarianceAngular=      0.001
Marker/PriorsVarianceLinear=       0.001
Marker/VarianceAngular=            0.01
Marker/VarianceLinear=             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.30  (default=0.6)
Mem/RehearsalWeightIgnoredWhileMoving=false
Mem/STMSize=                       10
Mem/SaveDepth16Format=             false
Mem/StereoFromMotion=              false
Mem/TransferSortingByWeightId=     false
Mem/UseOdomFeatures=               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/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=           true
Optimizer/Robust=                  false
Optimizer/Strategy=                1
Optimizer/VarianceIgnored=         false
PyDetector/Cuda=                   true
PyMatcher/Cuda=                    true
PyMatcher/Iterations=              20
PyMatcher/Model=                   indoor
PyMatcher/Threshold=               0.2
RGBD/AngularSpeedUpdate=           0.0
RGBD/AngularUpdate=                0.1
RGBD/CreateOccupancyGrid=          true  (default=false)
RGBD/Enabled=                      true
RGBD/GoalReachedRadius=            0.5
RGBD/GoalsSavedInUserData=         false
RGBD/InvertedReg=                  false
RGBD/LinearSpeedUpdate=            0.0
RGBD/LinearUpdate=                 0.1
RGBD/LocalBundleOnLoopClosure=     false
RGBD/LocalImmunizationRatio=       0.25
RGBD/LocalRadius=                  10
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.0
RGBD/PlanAngularVelocity=          0
RGBD/PlanLinearVelocity=           0
RGBD/PlanStuckIterations=          0
RGBD/ProximityAngle=               45
RGBD/ProximityBySpace=             false  (default=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=                false
Reg/Force3DoF=                     true  (default=false)
Reg/RepeatOnce=                    true
Reg/Strategy=                      0
Rtabmap/ComputeRMSE=               true
Rtabmap/CreateIntermediateNodes=   false
Rtabmap/DetectionRate=             2  (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=                   3000  (default=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=              1
Vis/CorFlowEps=                    0.01
Vis/CorFlowIterations=             30
Vis/CorFlowMaxLevel=               3
Vis/CorFlowWinSize=                16
Vis/CorGuessMatchToProjection=     false
Vis/CorGuessWinSize=               40
Vis/CorNNDR=                       0.8
Vis/CorNNType=                     1
Vis/CorType=                       0
Vis/DepthAsMask=                   true
Vis/EpipolarGeometryVar=           0.1
Vis/EstimationType=                1
Vis/FeatureType=                   8
Vis/ForwardEstOnly=                true
Vis/GridCols=                      1
Vis/GridRows=                      1
Vis/InlierDistance=                0.1
Vis/Iterations=                    300
Vis/MaxDepth=                      0
Vis/MaxFeatures=                   1000
Vis/MeanInliersDistance=           0.0
Vis/MinDepth=                      0
Vis/MinInliers=                    15  (default=20)
Vis/MinInliersDistribution=        0.0
Vis/PnPFlags=                      0
Vis/PnPMaxVariance=                0.0
Vis/PnPRefineIterations=           0
Vis/PnPReprojError=                2
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
Db/TargetVersion=                  NA  (default="")
Icp/DebugExportFormat=             NA  (default="")
Icp/PMConfig=                      NA  (default="")
Kp/DictionaryPath=                 NA  (default="")
Marker/Priors=                     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/rakesh/.ros/rtabmap_best_so_far.db
Version:            0.21.1
Sessions:           1
Total odometry length:395.392365 m
Total time:         1882.601000s
LTM:                3467 nodes and 855738 words (dim=32 type=8U)
WM:                 2353 nodes and 819438 words
Global graph:       3467 poses and 4998 links
Optimized graph:    2353 poses (x=4998->-9, y=8->-8, z=8->0)
Maps in graph:      1/1 [0(2353)]
Ground truth:       0 poses
GPS:                0 poses
Links:
  Neighbor:         4704
  GlobalClosure:    294
  LocalSpaceClosure:0
  LocalTimeClosure: 0
  UserClosure:      0
  VirtualClosure:   0
  NeighborMerged:   0
  PosePrior:        0
  Landmark:         0
  Gravity:          0

Database size:      1704 MB
Nodes size:         531 KB	(0.03%)
Links size:         1 MB	(0.10%)
RGB Images size:    667 MB	(39.17%)
Depth Images size:  616 MB	(36.16%)
Calibrations size:  2 MB	(0.16%)
Grids size:         55 MB	(3.24%)
Scans size:         0 Bytes	(0.00%)
User data size:     0 Bytes	(0.00%)
Dictionary size:    50 MB	(2.96%)
Features size:      282 MB	(16.58%)
Statistics size:    4 MB	(0.26%)
Other (indexing, unused):22 MB	(1.34%)

Thanks,
minato_99
Reply | Threaded
Open this post in threaded view
|

Re: Loop Closure Parameters

matlabbe
Administrator
Can you share the database?
Reply | Threaded
Open this post in threaded view
|

Re: Loop Closure Parameters

minato_99
Hello matlabbe,

https://drive.google.com/file/d/1Fxj2ZxOuhBNxOftIlRkBjLvVwePLDDHy/view?usp=sharing

I have attached the link. Please access the database. I could not upload it because the size of the zip file is large.

Thanks,
minato_99
Reply | Threaded
Open this post in threaded view
|

Re: Loop Closure Parameters

matlabbe
Administrator
In general I would use Kp/MaxDepth=0 (in your map it is 2 meters), to get better loop closure hypotheses and transformation estimation. Loop closures over larger distance can also be detected.

I see that when the computer seems to use more CPU, like during vocabulary rebalancing:


It caused some glitches like this between two consecutive nodes added to map:


I don't know why it affected the odometry, unless the simulator itself lagged and gave poor data.

The map looks relatively good otherwise. Here a comparison without and with loop closure optimization:


cheers,
Mathieu