rtabmap_ros icon indicating copy to clipboard operation
rtabmap_ros copied to clipboard

Tuning feature extraction params help

Open dcdonk opened this issue 3 months ago • 4 comments

Description

I am using rtabmap for SLAM-ming indoor hospital theatres with my two-wheeled diff driven robot. It uses a realsense D435 camera to create the RGBD images used by rtabmap. It also uses a 2D lidar at the base of the robot. A few weeks ago, I recorded a dataset of a hospital theatre. During navigation missions, my robot consistently lost localisation in the same area. To investigate, I opened the database using:

rtabmap-databaseViewer -f theatre_3/theatre_3.db

I noticed that RTAB-Map extracted many features from the grey floor, which I suspect is causing false positives and may be contributing to localization failure. Also in some frames it just dropped all feature extraction probably resulting in the lost of localisation.

To improve this, I wanted to tune the parameters to reduce features extracted from the floor. My plan was to selectively modify parameters in an .ini file and reprocess the database using:

rtabmap-reprocess -default -c ./theatre_3/theatre_3.ini ./theatre_3/theatre_3.db ./theatre_3/theatre_3_tuned.db
Using default parameters.
Using 5 parameters from config file "./theatre_3/theatre_3.ini"
Set working directory to "./theatre_3".
Reprocessing data of "./theatre_3/theatre_3.db"...
High variance detected, triggering a new map...
Processed 1/1488 nodes [id=1 map=0 opt_graph=1]... 4ms
Processed 2/1488 nodes [id=2 map=0 opt_graph=1]... 3ms
Processed 3/1488 nodes [id=3 map=0 opt_graph=1]... 5ms
Processed 4/1488 nodes [id=4 map=0 opt_graph=1]... 2ms
Processed 5/1488 nodes [id=5 map=0 opt_graph=1]... 2ms
Processed 6/1488 nodes [id=6 map=0 opt_graph=1]... 2ms
Processed 7/1488 nodes [id=7 map=0 opt_graph=1]... 2ms
Processed 8/1488 nodes [id=8 map=0 opt_graph=1]... 2ms
Processed 9/1488 nodes [id=9 map=0 opt_graph=1]... 2ms
....
Total loop closures = 49 (Loop=0, Prox=49, In Motion=49/1488)
Closing database "./theatre_3/theatre_3_tuned.db"...
Closing database "./theatre_3/theatre_3_tuned.db"... done!

After reprocessing, I opened the new database with:

rtabmap-databaseViewer -f theatre_3/theatre_3_tuned.db

But the params I started out with did not seem to help a lot with the feature extraction:


[Core]
GFTT/QualityLevel=0.1
Vis/DepthAsMask=True
Vis/DepthMaskFloorThr=0.1
Kp/MaxDepth=4.0
Kp/GridRows=2
Kp/MaxFeatures=1
Kp/GridCols=2
Vis/GridRows=2
Vis/GridCols=2
Vis/MinInliers=40
Vis/MinInliersDistribution=0.1
Rtabmap/LoopThr=0.15
RGBD/OptimizeMaxError=2.0
Grid/MaxGroundHeight=0.05
Grid/MinGroundHeight=-0.05
Grid/MaxGroundAngle=10.0

Question

Generally, what is the best approach for re-tuning a RTAB-Map setup specifically for localisation? My current approach is:

  1. Go through rtabmap --params to see all available parameters.
  2. Cherry-pick parameters that I believe will impact localisation.
  3. Run rtabmap-reprocess.
  4. Inspect feature extraction in the database viewer to see the effect.

Does this make sense as a tuning workflow, or are there better practices?

I’ve looked around for tuning guides, but most are outdated or don’t address this type of issue. Any guidance or best practices on systematically tuning parameters for improved localisation would be highly appreciated.

Any help or tips are welcoming on how I can approach tuning/improving my rtabmap stack

Example from .db with false feature extraction:

Image

Example from .db with false positive of correspondents within two different places of the grey floor

Image

Example of dropped feature extraction:

Image

Current params:

rtabmap:
  ros__parameters:
    Reg/Strategy: "2" # Vis and ICP
    Reg/Force3DoF: "True"
    Reg/RepeatOnce: "True"

    Vis/BundleAdjustment: "1" #g2o
    Vis/FeatureType: "8" # GFTT/ORB
    Vis/EstimationType: "1" # 3D->2D/PnP
    Vis/SSC: "True"

    Icp/Strategy: "1" # libpointmatcher
    Icp/Force4DoF: "True"
    Icp/FiltersEnabled: "3" # Both from and to cloud

    Optimizer/Strategy: "1"  # g2o
    Optimizer/Robust: 'True'

    g2o/Optimizer: "0" # Levenberg-Marquardt
    g2o/Solver: "0" # cparse

    RGBD/Enabled: "True"
    RGBD/ForceOdom3DoF: "True"
    RGBD/ProximityPathMaxNeighbors: "10"

    Grid/3D: "False"
    Grid/CellSize: "0.05"
    Grid/FlatObstacleDetected: "True"
    Grid/FootprintHeight: '2.0'
    Grid/FootprintLength: '0.504'
    Grid/FootprintWidth: '0.504'
    Grid/GroundIsObstacle: "False"
    Grid/MapFrameProjection: "False"
    Grid/MaxGroundAngle: "15.0"
    Grid/MaxGroundHeight: "0.025"
    Grid/MaxObstacleHeight: "2.0"
    Grid/MinGroundHeight: "0.0"
    Grid/NormalsSegmentation: "True"
    Grid/PreVoxelFiltering: "True"
    Grid/RayTracing: "False"
    Grid/Sensor: "2"
    Grid/NoiseFilteringRadius: "0.2"
    Grid/NoiseFilteringMinNeighbors: "3"

    Kp/DetectorStrategy: "8" # GFTT/ORB
    Kp/SSC: "True"
    Kp/NewWordsComparedTogether: "True"
    Kp/ByteToFloat: "False"
    Kp/IncrementalDictionary: "True"
    Kp/IncrementalFlann: "True"
    Kp/TfIdfLikelihoodUsed: "True"
    Kp/Parallelized: "True"

    Mem/UseOdomFeatures: "True"
    Mem/UseOdomGravity: "False"

    Rtabmap/LoopClosure/Enabled: "True"
    Rtabmap/LoopGPS: "False"
    Rtabmap/PublishLastSignature: "False"
    Rtabmap/PublishLikelihood: "False"
    Rtabmap/PublishPdf: "False"
    Rtabmap/CreateIntermediateNodes: "False"
    Rtabmap/DetectionRate: "5.0"

    frame_id: "base_footprint"
    odom_frame_id: "odom"
    approx_sync: True
    subscribe_rgbd: True
    subscribe_rgb: False
    subscribe_depth: False
    subscribe_scan: True
    qos_image: 2 # Best effort
    qos_scan: 2 # Best effort
    database_path: ''
    delete_db_on_start: False
    odom_sensor_sync: True

dcdonk avatar Sep 23 '25 15:09 dcdonk

how about Kp/MaxFeatures? It's a parameter that limits the maximum number of keypoints (feature points)

KimchiPizza avatar Sep 24 '25 00:09 KimchiPizza

how about Kp/MaxFeatures? It's a parameter that limits the maximum number of keypoints (feature points)

Yes I tried that as well but putting it at a debug value i.e '1' (0 Would make it infinite) doesn’t have an impact on the database. In the viewer you will still see more then 1 feature extracted.

Also ideally I would retain a high amount of features just have stricter criteria for feature extraction. But it would be a good starting off point, I agree.

dcdonk avatar Sep 24 '25 08:09 dcdonk

@matlabbe I was wondering if you might know why running rtabmap-reprocess with certain params such as Kp/MaxFeatures are not reflected in the new reprocessed database.

Currently blocked retuning my database because of this.

dcdonk avatar Sep 26 '25 10:09 dcdonk

If you want to test changes on Vis/ or Kp/ parameters, you need to disable usage of odometry features. Otherwise, the features from the database are passed through the Memory. Launch rtabmap-reprocess with --Mem/UseOdomFeatures false, then the features will be re-extracted using your current parameters.

For the debugging workflow, I also use rtabmap-reprocess a lot to test with different parameters. Another way to debug loop closure detection on a database is to use rtabmap-databaseViewer. For example, if some loop closures were missed or rejected, we can use Constraints View to try manually adding a loop closure. To try different Vis/ parameters to help the loop closure, we can change them in the Core Parameters view, then enable RGBD/LoopClosureReextractFeatures to force re-extracting feature when hitting the button "Add" constraint.

  • In this workflow, I can also tune the local occupancy grid parameters (Grid/) with the UI, open the 3D view to see the local grid and hit Edit->Regenerate local grids... to see their effect with new parameters I've set.

If you are using the default parameters, you may want to play with GFTT parameters to extract more or less features.

For the images without any features, this may be caused by parameter Kp/BadSignRatio, which can be set to 0 to disable it.

matlabbe avatar Sep 28 '25 18:09 matlabbe