Closed matlabbe closed 1 month ago
Is it possible to post process the recorded data on device to generate optimized poses? And what's the equivalent in CLI? Is it rtab-reprocess
?
I didn't implement a way to reprocess on device.
The GUI way to reprocess is to open RTAB-Map Desktop, open Preferences->Source, then select Database as input source. Scroll down to select the path of the recorded database. Say yes to use odometry from the database, but no for setting rtabmap detection rate to 0 (if images were recorded faster than 1 Hz). Check database stamps for framerate (or uncheck and set manually the rate at the top of the dialog for faster than real-time processing). Go back on main UI and press play.
To use the CLI tool (with these parameters, it should be equivalent than default parameters on device):
rtabmap-reprocess \
--Rtabmap/DetectionRate 1 \
--Mem/RehearsalSimilarity 0.3 \
--Kp/MaxFeatures 400 \
--Rtabmap/MaxRetrieved 2\
--RGBD/MaxLocalRetrieved 2\
--Mem/MapLabelsAdded true \
--Rtabmap/MemoryThr 0 \
--Mem/STMSize 10 \
--RGBD/ProximityBySpace true \
--RGBD/LinearUpdate 0.05 \
--RGBD/AngularUpdate 0.05 \
recording.db output.db
If you recorded at 1 Hz (default) on device, you can set Rtabmap/DetectionRate=0
here to process all frames.
Closing as now already available on iOS app under Menu -> Advanced -> New Data Recording.
Like android app's "Trajectory Mode", we could do something similar for iOS. This could save battery and make it able to scan in order of a hour or more. See this thread for more info: http://official-rtab-map-forum.206.s1.nabble.com/iOS-best-practices-for-only-tracking-long-recordings-td10300.html