introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
956 stars 557 forks source link

Rtabmap database seems to grow even when no visual words are added to the dictionary. #671

Closed peredwardsson closed 1 year ago

peredwardsson commented 2 years ago

Rtabmap listens to two cameras at 15fps 720p, which produces a database file which grows with about 2 mb/s. This is even when the robot is stationary and even when no or very few visual words are added at all. At time of writing, robot has been stationary but active for 25 minutes. Rtabmap has accumulated 4 visual words, and the database file weighs in at 3.0 Gb. For parameters,

    subscribe_depth: False
    subscribe_rgb: False
    subscribe_stereo: False
    subscribe_rgbd: True
    subscribe_scan: False
    approx_sync: True
    odom_frame_id: "odom"
    map_always_update: False
    map_empty_ray_tracing: True
    rgbd_cameras: 2
    database_path: "/hugoros2/rtabmap.db"

    Grid/RayTracing: "True"
    Grid/RangeMax: "4.0"
    Grid/CellSize: "0.1"
    Grid/NoiseFilteringRadius: "0.1"
    Grid/NoiseFilteringMinNeighbors: "6"
    Grid/NormalK: "20"
    GridGlobal/Eroded: "True"
    GridGlobal/FootprintRadius: "0.6"
    RGBD/AngularUpdate: "0.2"
    RGBD/LinearUpdate: "0.2"
    RGBD/OptimizeFromGraphEnd: "True"
    RGBD/OptimizeMaxError: "0.1"
    Mem/IncrementalMemory: "True"
    Mem/ReduceGraph: "True"
    Reg/Force3DoF: "True"
    Kp/MaxFeatures: "200"
    Stereo/MaxDisparity: "200"
    Vis/CorFlowMaxLevel: "5"
    Vis/EstimationType: "0" # should be 0 for multi-camera input
    Odom/ResetCountdown: "10"
    OdomF2M/BundleAdjustment: "0" # should be 0 for mult-camera input
    SURF/GpuVersion: "True"

Is this correct behavior? Is it possible to trim the database? The size makes the databases very cumbersome to move between robots.

matlabbe commented 2 years ago

For debugging purpose, by default rtabmap saves all data. You can set Mem/NotLinkedNodesKept to false to avoid saving data when the robot is not moving.

Other optimization, you can also set Mem/BinDataKept to false to avoid saving RGB/Depth images to database. However, this reduces the convenience to debug the map afterwards.

Divelix commented 2 years ago

These two params are really useful, but is there any way to remove these RGB/Depth data and not linked nodes in post-processing? Like if I built map, then verified in rtabmap-databaseViewer its quality is acceptable, and now want to delete debug data from .db file to use it in production.

matlabbe commented 1 year ago

You can reprocess the database with those parameters set to false:

rtabmap-reprocess --Mem/NotLinkedNodesKept false --Mem/BinDataKept false rtabmap.db output.db

However, the loop closures detected may be not exactly the same, so the resulting map may be slightly different than the one you inspected.

I guess --Mem/NotLinkedNodesKept false could be always set, even in your original mapping session. For Mem/BinDataKept, instead of reprocessing, you could delete the data from the database with a sqlite3 query and shrink it afterwards:

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