Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Failing Localization with Obstructions Present while still #1444

Open
jsreveal opened this issue Jan 29, 2025 · 4 comments
Open

Failing Localization with Obstructions Present while still #1444

jsreveal opened this issue Jan 29, 2025 · 4 comments

Comments

@jsreveal
Copy link

jsreveal commented Jan 29, 2025

I am experiencing difficulties with RTAB-Map's localization and loop closure capabilities in scenarios where there are obstructions (specifically, people) between the camera and previously mapped areas, but there are still important scene features visible. In this scenario the camera subject is still. I don't experience these issues if the people are not obstructing the view.

Observations:

  • Failure Modes: RTAB-Map fails to either localize correctly or establish loop closures when obstructions are present in the described scenario. Instead it yields bad loop closures.
  • External SIFT Verification: I have independently tested SIFT feature detection and matching using the same configuration as RTAB-Map's internal implementation (see below). When comparing RGB images from the current scene (with people present) against previously captured map images, SIFT successfully identifies good keypoint matches, not many but feels sufficien. This suggests that the features themselves are detectable and match-able despite the obstructions.
  • Obstruction Removal: When the people are removed from the scene, RTAB-Map is able to localize correctly without issue.

Scenario with occlusion, with bad localization
There are some good keypoint matches, despite some bad ones.
Image on the right is an rgb exported from the map at a close position. Using distance threshold 0.7
Image

Scenario without occlusion with good localization
Good keypoint matches, but again not many.Image on the left is from an rgb exported from the map
Image

Expected Behavior:

I would expect RTAB-Map to be more robust to partial occlusions, especially when feature matching (as demonstrated by external SIFT) is still possible. Ideally, it should be able to utilize the available matches to achieve at least a coarse localization or loop closure, even if the accuracy is slightly reduced due to the obstructions.

Question:

What factors within RTAB-Map's processing could be contributing to these failures in the presence of partial occlusions, despite the apparent availability of matching features? Are there specific parameters or configurations that could be adjusted to improve robustness in such scenarios?

@matlabbe
Copy link
Member

matlabbe commented Feb 4, 2025

Are you using a stereo or RGB-D camera? If a depth image is used, by default features are not extracted when there is no depth. You may disable this by setting Mem/DepthAsMask: false and Vis/DepthAsMask: false. The motion estimation would be accepted only if the number of inliers is above 20 by default, it can be changed with parameter Vis/MinInliers. Also make sure rtabmap is using SIFT: Kp/DetectorStrategy: 1 and Mem/UseOdomFeatures: false.

Note that another way to debug localization is to backup your map database, then restart in localization mode with Mem/LocalizationDataSaved: true. Do the the localization session, then close. The database will contain the data recorded during the localization session. Open the database in rtabmap-databaseViewer, then you can browse one map frame and one localization frame, then with Constraint View, check the checkbox to enable adding loop closures and click Add. You can enable Debug log under Gui settings panel to look at why a new added constraint would fail. It is also possible to change the Core Parameters and re-do Add to see how the parameters affect loop closure transform estimation. Enable RGBD/LoopClosureReextractFeatures under Core parameters to force re-extracting features depending on the current strategy used to test other features for example.

@jsreveal
Copy link
Author

I am using monocular localization. Those configuration changes did not produce better results.

Also tried to use superpoint+superglue but without improvements.

After doing localization with save localization data, I cannot open the database from databaseViewer.

Image

Thank you,
João

@jsreveal
Copy link
Author

jsreveal commented Feb 12, 2025

@matlabbe so I have set the location images with a dummy pose and was able to open the databse in rtabmap-databaseViewer with the location images.

I have ran location, against a map created with superpoint and superglue (complete config end of the comment). The matches I can see in rtabmap-databaseViewer are much less than the onews I obtain when I run superpoint+superglue from the superglue repository.
Does location run superglue at all?

Matches shown in databaseViewer:
Image

Matches running superpoint+superglue using demo_superglue.py (config identical):

Image

map config:
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/Gpu= false
GFTT/K= 0.04
GFTT/MinDistance= 7
GFTT/QualityLevel= 0.001
GFTT/UseHarrisDetector= false
GMS/ThresholdFactor= 6
GMS/WithRotation= false
GMS/WithScale= false
GTSAM/IncRelinearizeSkip= 1
GTSAM/IncRelinearizeThreshold= 0.01
GTSAM/Incremental= 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
Grid/NoiseFilteringMinNeighbors= 5
Grid/NoiseFilteringRadius= 0.0
Grid/NormalK= 20
Grid/NormalsSegmentation= true
Grid/PreVoxelFiltering= true
Grid/RangeMax= 5
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/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/FiltersEnabled= 3
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
33mKp/DetectorStrategy= 11 (default=8)
Kp/FlannRebalancingFactor= 2.0
Kp/GridCols= 1
Kp/GridRows= 1
Kp/IncrementalDictionary= true
Kp/IncrementalFlann= true
Kp/MaxDepth= 0
33mKp/MaxFeatures= 0 (default=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/SSC= false
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
33mMem/DepthAsMask= false (default=true)
Mem/DepthCompressionFormat= .rvl
Mem/DepthMaskFloorThr= 0.0
Mem/GenerateIds= true
Mem/GlobalDescriptorStrategy= 0
Mem/ImageCompressionFormat= .jpg
Mem/ImageKept= false
Mem/ImagePostDecimation= 1
Mem/ImagePreDecimation= 1
33mMem/IncrementalMemory= false (default=true)
Mem/InitWMWithAllNodes= false
Mem/IntermediateNodeDataKept= false
Mem/LaserScanDownsampleStepSize= 1
Mem/LaserScanNormalK= 0
Mem/LaserScanNormalRadius= 0.0
Mem/LaserScanVoxelSize= 0.0
33mMem/LocalizationDataSaved= true (default=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/RotateImagesUpsideUp= false
33mMem/STMSize= 40 (default=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/Deskewing= true
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= 2.5e-05
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
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/AccNoise= 0.1
OdomORBSLAM/AccWalk= 0.0001
OdomORBSLAM/Bf= 0.076
OdomORBSLAM/Fps= 0
OdomORBSLAM/GyroNoise= 0.01
OdomORBSLAM/GyroWalk= 0.000001
OdomORBSLAM/Inertial= false
OdomORBSLAM/MapSize= 3000
OdomORBSLAM/MaxFeatures= 1000
OdomORBSLAM/SamplingRate= 0
OdomORBSLAM/ThDepth= 40.0
OdomOpen3D/MaxDepth= 3.0
OdomOpen3D/Method= 0
OdomOpenVINS/AccelerometerNoiseDensity=0.01
OdomOpenVINS/AccelerometerRandomWalk=0.001
OdomOpenVINS/CalibCamExtrinsics= false
OdomOpenVINS/CalibCamIntrinsics= false
OdomOpenVINS/CalibCamTimeoffset= false
OdomOpenVINS/CalibIMUGSensitivity= false
OdomOpenVINS/CalibIMUIntrinsics= false
OdomOpenVINS/DtSLAMDelay= 0.0
OdomOpenVINS/FeatRepMSCKF= 0
OdomOpenVINS/FeatRepSLAM= 4
OdomOpenVINS/FiMaxBaseline= 40
OdomOpenVINS/FiMaxCondNumber= 10000
OdomOpenVINS/FiMaxRuns= 5
OdomOpenVINS/FiRefineFeatures= true
OdomOpenVINS/FiTriangulate1d= false
OdomOpenVINS/GravityMag= 9.81
OdomOpenVINS/GyroscopeNoiseDensity=0.001
OdomOpenVINS/GyroscopeRandomWalk= 0.0001
OdomOpenVINS/InitDynInflationBa= 100.0
OdomOpenVINS/InitDynInflationBg= 10.0
OdomOpenVINS/InitDynInflationOri= 10.0
OdomOpenVINS/InitDynInflationVel= 100.0
OdomOpenVINS/InitDynMLEMaxIter= 50
OdomOpenVINS/InitDynMLEMaxThreads= 6
OdomOpenVINS/InitDynMLEMaxTime= 0.05
OdomOpenVINS/InitDynMLEOptCalib= false
OdomOpenVINS/InitDynMinDeg= 10.0
OdomOpenVINS/InitDynMinRecCond= 1e-15
OdomOpenVINS/InitDynNumPose= 6
OdomOpenVINS/InitDynUse= false
OdomOpenVINS/InitIMUThresh= 1.0
OdomOpenVINS/InitMaxDisparity= 10.0
OdomOpenVINS/InitMaxFeatures= 50
OdomOpenVINS/InitWindowTime= 2.0
OdomOpenVINS/Integration= 1
OdomOpenVINS/MaxClones= 11
OdomOpenVINS/MaxMSCKFInUpdate= 50
OdomOpenVINS/MaxSLAM= 50
OdomOpenVINS/MaxSLAMInUpdate= 25
OdomOpenVINS/MinPxDist= 15
OdomOpenVINS/NumPts= 200
OdomOpenVINS/TryZUPT= true
OdomOpenVINS/UpMSCKFChi2Multiplier=1.0
OdomOpenVINS/UpMSCKFSigmaPx= 1.0
OdomOpenVINS/UpSLAMChi2Multiplier= 1.0
OdomOpenVINS/UpSLAMSigmaPx= 1.0
OdomOpenVINS/UseFEJ= true
OdomOpenVINS/UseKLT= true
OdomOpenVINS/UseStereo= true
OdomOpenVINS/ZUPTChi2Multiplier= 0.0
OdomOpenVINS/ZUPTMaxDisparity= 0.5
OdomOpenVINS/ZUPTMaxVelodicy= 0.1
OdomOpenVINS/ZUPTNoiseMultiplier= 10.0
OdomOpenVINS/ZUPTOnlyAtBeginning= false
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= 1e-05
Optimizer/GravitySigma= 0.3
Optimizer/Iterations= 20
Optimizer/LandmarksIgnored= false
Optimizer/PriorsIgnored= true
Optimizer/Robust= false
Optimizer/Strategy= 2
Optimizer/VarianceIgnored= false
PyDescriptor/Dim= 4096
PyDetector/Cuda= true
PyMatcher/Cuda= true
PyMatcher/Iterations= 20
PyMatcher/Model= indoor
33mPyMatcher/Path= ~/Downloads/SuperGluePretrainedNetwork/rtabmap_superglue.py (default=)
PyMatcher/Threshold= 0.2
RGBD/AggressiveLoopThr= 0.05
RGBD/AngularSpeedUpdate= 0.0
RGBD/AngularUpdate= 0.1
33mRGBD/CreateOccupancyGrid= true (default=false)
33mRGBD/Enabled= false (default=true)
RGBD/ForceOdom3DoF= 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/LocalizationPriorError= 0.001
RGBD/LocalizationSmoothing= true
RGBD/LoopClosureIdentityGuess= false
33mRGBD/LoopClosureReextractFeatures= true (default=false)
RGBD/LoopCovLimited= false
RGBD/MarkerDetection= false
RGBD/MaxLocalRetrieved= 2
RGBD/MaxLoopClosureDistance= 0
RGBD/MaxOdomCacheSize= 10
RGBD/NeighborLinkRefining= false
RGBD/NewMapOdomChangeDistance= 0
RGBD/OptimizeFromGraphEnd= false
RGBD/OptimizeMaxError= 3
RGBD/PlanAngularVelocity= 0
RGBD/PlanLinearVelocity= 0
RGBD/PlanStuckIterations= 0
RGBD/ProximityAngle= 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= false
Reg/Force3DoF= false
33mReg/RepeatOnce= false (default=true)
Reg/Strategy= 0
Rtabmap/ComputeRMSE= true
Rtabmap/CreateIntermediateNodes= false
33mRtabmap/DetectionRate= 0 (default=1)
33mRtabmap/ImageBufferSize= 0 (default=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
Rtabmap/VirtualPlaceLikelihoodRatio=0
SIFT/ContrastThreshold= 0.04
SIFT/EdgeThreshold= 10
SIFT/GaussianThreshold= 2
SIFT/Gpu= false
SIFT/NOctaveLayers= 3
SIFT/PreciseUpscale= false
SIFT/RootSIFT= false
SIFT/Sigma= 1.6
SIFT/Upscale= false
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/Gpu= false
Stereo/Iterations= 30
Stereo/MaxDisparity= 128
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
33mSuperPoint/ModelPath= ~/Downloads/superpoint_v1.pt (default=)
SuperPoint/NMS= true
SuperPoint/NMSRadius= 4
SuperPoint/Threshold= 0.01
VhEp/Enabled= false
VhEp/MatchCountMin= 8
VhEp/RansacParam1= 3
VhEp/RansacParam2= 0.99
Vis/BundleAdjustment= 1
Vis/CorFlowEps= 0.01
Vis/CorFlowGpu= false
Vis/CorFlowIterations= 30
Vis/CorFlowMaxLevel= 3
Vis/CorFlowWinSize= 16
Vis/CorGuessMatchToProjection= false
33mVis/CorGuessWinSize= 0 (default=40)
Vis/CorNNDR= 0.8
33mVis/CorNNType= 6 (default=1)
Vis/CorType= 0
33mVis/DepthAsMask= false (default=true)
Vis/DepthMaskFloorThr= 0.0
Vis/EpipolarGeometryVar= 0.1
Vis/EstimationType= 1
33mVis/FeatureType= 11 (default=8)
Vis/ForwardEstOnly= true
Vis/GridCols= 1
Vis/GridRows= 1
Vis/InlierDistance= 0.1
Vis/Iterations= 300
Vis/MaxDepth= 0
33mVis/MaxFeatures= 0 (default=1000)
Vis/MeanInliersDistance= 0.0
Vis/MinDepth= 0
33mVis/MinInliers= 6 (default=20)
Vis/MinInliersDistribution= 0.0
Vis/PnPFlags= 0
Vis/PnPMaxVariance= 0.0
Vis/PnPRefineIterations= 0
Vis/PnPReprojError= 2
Vis/PnPSamplingPolicy= 1
Vis/PnPSplitLinearCovComponents= false
Vis/PnPVarianceMedianRatio= 4
Vis/RefineIterations= 5
Vis/RoiRatios= 0.0 0.0 0.0 0.0
Vis/SSC= false
Vis/SubPixEps= 0.02
Vis/SubPixIterations= 0
Vis/SubPixWinSize= 3
g2o/Baseline= 0.075
g2o/Optimizer= 0
g2o/PixelVariance= 1
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="")
OdomOpenVINS/LeftMaskPath= NA (default="")
OdomOpenVINS/RightMaskPath= NA (default="")
OdomVINS/ConfigPath= NA (default="")
PyDescriptor/Path= NA (default="")
PyDetector/Path= NA (default="")
Rtabmap/WorkingDirectory= NA (default="")

@matlabbe
Copy link
Member

matlabbe commented Mar 1, 2025

To verify that superglue is giving similar results on both cases, you can try rtabmap-matcher tool that can be used to test the matching algorithms.

rtabmap-matcher --help
...
rtabmap-matcher \
   --Vis/FeatureType 11 \
   --SuperPoint/ModelPath "superpoint.pt" \
   --Vis/CorNNType 6 \
   --PyMatcher/Path "~/SuperGluePretrainedNetwork/rtabmap_superglue.py" \
   from.png to.png
...

You can post the log here with --udebug for more help.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants