introlab / rtabmap_ros

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

inconsistent results in TUM benchmarks #1008

Open alexk1976 opened 1 year ago

alexk1976 commented 1 year ago

Hi, We run rtabmap in RGBD mode in ROS environment. Even when we playback same clip on same strong PC - we get different results each execution. Difference might be 10cm sometimes and even more preventing us to understand real accuracy/improve results. No such issue we run TUM sequences. any ideas to get consistent results? thanks

matlabbe commented 1 year ago

If you reprocess the database (rtabmap-reprocess), there should not have any difference between the computers, unless rtabmap is not built with same dependencies.

With a rosbag, there could be difference on which frame is used to compute odometry or mapping.

On a real robot, you get same time sync issue than rosbag, and the environment/trajectory may be slightly different between the runs.

alexk1976 commented 11 months ago

@matlabbe We rebased code with latest and now we get inconsistent results even when run rtabmap-rgbd_dataset on a TUM sequence a few times. Even number of poses are different each time. Any ideas what change in an half-year caused to it?

matlabbe commented 11 months ago

Which TUM sequence are you using? and what command did you use?

alexk1976 commented 11 months ago

For example: rtabmap-rgbd_dataset --Reg/Force3DoF false --Mem/UseOdomFeatures true --Rtabmap/DetectionRate 2 --Odom/AlignWithGround false /root/data/TUM/rgbd_dataset_freiburg2_pioneer_slam3

matlabbe commented 11 months ago

The variability may be caused by RANSAC on image registration. Here three runs: Screenshot from 2023-09-09 14-07-28 Screenshot from 2023-09-09 14-07-13 Screenshot from 2023-09-09 14-07-44

rtabmap-report .
Directory: .
   rtabmap_run1.db (196, s=1.000):  error lin=0.098m (max=0.101m, odom=0.142m) ang=3.6deg, slam: avg=23ms (max=164ms) loops=3, odom: avg=31ms (max=89ms), camera: avg=6ms, map=367MB
   rtabmap_run2.db (182, s=1.000):  error lin=0.276m (max=0.276m, odom=0.292m) ang=4.5deg, slam: avg=23ms (max=165ms) loops=1, odom: avg=31ms (max=89ms), camera: avg=6ms, map=357MB
   rtabmap_run3.db (194, s=1.000):  error lin=0.136m (max=0.136m, odom=0.203m) ang=3.8deg, slam: avg=25ms (max=166ms) loops=5, odom: avg=31ms (max=89ms), camera: avg=6ms, map=365MB

Where there are missing poses on second one, we can log like this:

Iteration 1671/2266: camera=6ms, odom(quality=284/949, kfs=580)=37ms, slam=0ms, rmse=0.074733m
[ WARN] (2023-09-09 13:58:48.286) OdometryF2M.cpp:566::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=32) between -1 and 1672" (guess=xyz=-0.020133,0.207793,-0.056495 rpy=-0.250968,0.058539,0.987020)
[ WARN] (2023-09-09 13:58:48.287) OdometryF2M.cpp:314::computeTransform() Failed to find a transformation with the provided guess (xyz=-0.020133,0.207793,-0.056495 rpy=-0.250968,0.058539,0.987020), trying again without a guess.
[ WARN] (2023-09-09 13:58:48.319) OdometryF2M.cpp:556::computeTransform() Trial with no guess still fail.
[ WARN] (2023-09-09 13:58:48.319) OdometryF2M.cpp:566::computeTransform() Registration failed: "Not enough inliers 7/20 (matches=113) between -1 and 1672" (guess=xyz=-0.020133,0.207793,-0.056495 rpy=-0.250968,0.058539,0.987020)
[ERROR] (2023-09-09 13:58:48.319) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1672 is ignored!
Iteration 1672/2266: camera=6ms, odom(quality=7/907, kfs=580)=54ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.365) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=68) between -1 and 1673"
Iteration 1673/2266: camera=6ms, odom(quality=0/912, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.410) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=69) between -1 and 1674"
Iteration 1674/2266: camera=6ms, odom(quality=0/914, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.454) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=72) between -1 and 1675"
Iteration 1675/2266: camera=6ms, odom(quality=0/921, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.499) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=61) between -1 and 1676"
Iteration 1676/2266: camera=6ms, odom(quality=0/901, kfs=580)=37ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.544) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=74) between -1 and 1677"
Iteration 1677/2266: camera=6ms, odom(quality=0/911, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.589) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=80) between -1 and 1678"
Iteration 1678/2266: camera=6ms, odom(quality=0/905, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.634) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=79) between -1 and 1679"
Iteration 1679/2266: camera=6ms, odom(quality=0/919, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.679) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=54) between -1 and 1680"
Iteration 1680/2266: camera=6ms, odom(quality=0/912, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.724) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=87) between -1 and 1681"
Iteration 1681/2266: camera=6ms, odom(quality=0/923, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.769) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=75) between -1 and 1682"
Iteration 1682/2266: camera=6ms, odom(quality=0/926, kfs=580)=37ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.814) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=71) between -1 and 1683"
Iteration 1683/2266: camera=6ms, odom(quality=0/907, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.859) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=69) between -1 and 1684"
Iteration 1684/2266: camera=6ms, odom(quality=0/927, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.904) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=71) between -1 and 1685"
Iteration 1685/2266: camera=6ms, odom(quality=0/932, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.949) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=76) between -1 and 1686"
Iteration 1686/2266: camera=6ms, odom(quality=0/934, kfs=580)=37ms, slam=0ms
[ WARN] (2023-09-09 13:58:48.994) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=68) between -1 and 1687"
[ERROR] (2023-09-09 13:58:48.995) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1687 is ignored!
Iteration 1687/2266: camera=6ms, odom(quality=0/892, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.039) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=62) between -1 and 1688"
Iteration 1688/2266: camera=6ms, odom(quality=0/930, kfs=580)=37ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.084) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=66) between -1 and 1689"
Iteration 1689/2266: camera=6ms, odom(quality=0/918, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.129) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=72) between -1 and 1690"
Iteration 1690/2266: camera=6ms, odom(quality=0/925, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.175) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=65) between -1 and 1691"
Iteration 1691/2266: camera=6ms, odom(quality=0/924, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.220) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=65) between -1 and 1692"
Iteration 1692/2266: camera=6ms, odom(quality=0/938, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.266) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=79) between -1 and 1693"
Iteration 1693/2266: camera=6ms, odom(quality=0/929, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.311) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=56) between -1 and 1694"
Iteration 1694/2266: camera=6ms, odom(quality=0/916, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.357) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=73) between -1 and 1695"
Iteration 1695/2266: camera=6ms, odom(quality=0/920, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.403) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=69) between -1 and 1696"
Iteration 1696/2266: camera=6ms, odom(quality=0/934, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.451) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=77) between -1 and 1697"
[ERROR] (2023-09-09 13:58:49.452) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1697 is ignored!
Iteration 1697/2266: camera=7ms, odom(quality=0/911, kfs=580)=40ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.498) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=70) between -1 and 1698"
Iteration 1698/2266: camera=7ms, odom(quality=0/937, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.545) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=68) between -1 and 1699"
Iteration 1699/2266: camera=7ms, odom(quality=0/846, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.593) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=65) between -1 and 1700"
Iteration 1700/2266: camera=6ms, odom(quality=0/902, kfs=580)=41ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.641) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=66) between -1 and 1701"
Iteration 1701/2266: camera=6ms, odom(quality=0/917, kfs=580)=41ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.689) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=72) between -1 and 1702"
Iteration 1702/2266: camera=6ms, odom(quality=0/925, kfs=580)=41ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.738) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=65) between -1 and 1703"
Iteration 1703/2266: camera=7ms, odom(quality=0/903, kfs=580)=40ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.785) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=57) between -1 and 1704"
Iteration 1704/2266: camera=7ms, odom(quality=0/912, kfs=580)=40ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.833) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=63) between -1 and 1705"
[ERROR] (2023-09-09 13:58:49.833) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1705 is ignored!
Iteration 1705/2266: camera=7ms, odom(quality=0/914, kfs=580)=40ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.879) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=69) between -1 and 1706"
Iteration 1706/2266: camera=6ms, odom(quality=0/919, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.926) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=74) between -1 and 1707"
Iteration 1707/2266: camera=6ms, odom(quality=0/918, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:49.971) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=53) between -1 and 1708"
Iteration 1708/2266: camera=6ms, odom(quality=0/910, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.017) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=74) between -1 and 1709"
Iteration 1709/2266: camera=6ms, odom(quality=0/923, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.063) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=69) between -1 and 1710"
Iteration 1710/2266: camera=6ms, odom(quality=0/921, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.109) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=60) between -1 and 1711"
Iteration 1711/2266: camera=6ms, odom(quality=0/924, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.155) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=71) between -1 and 1712"
Iteration 1712/2266: camera=6ms, odom(quality=0/917, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.201) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=58) between -1 and 1713"
Iteration 1713/2266: camera=7ms, odom(quality=0/924, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.247) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=60) between -1 and 1714"
[ERROR] (2023-09-09 13:58:50.247) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1714 is ignored!
Iteration 1714/2266: camera=6ms, odom(quality=0/909, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.287) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=37) between -1 and 1715"
Iteration 1715/2266: camera=6ms, odom(quality=0/337, kfs=580)=32ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.333) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=72) between -1 and 1716"
Iteration 1716/2266: camera=6ms, odom(quality=0/916, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.380) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=68) between -1 and 1717"
Iteration 1717/2266: camera=6ms, odom(quality=0/910, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.426) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=46) between -1 and 1718"
Iteration 1718/2266: camera=6ms, odom(quality=0/922, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.471) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=78) between -1 and 1719"
Iteration 1719/2266: camera=6ms, odom(quality=0/933, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.517) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=65) between -1 and 1720"
Iteration 1720/2266: camera=6ms, odom(quality=0/915, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.563) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=57) between -1 and 1721"
[ERROR] (2023-09-09 13:58:50.563) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1721 is ignored!
Iteration 1721/2266: camera=6ms, odom(quality=0/916, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.609) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=58) between -1 and 1722"
Iteration 1722/2266: camera=6ms, odom(quality=0/920, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.654) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=63) between -1 and 1723"
Iteration 1723/2266: camera=6ms, odom(quality=0/927, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.700) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=59) between -1 and 1724"
Iteration 1724/2266: camera=6ms, odom(quality=0/918, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.746) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=77) between -1 and 1725"
Iteration 1725/2266: camera=6ms, odom(quality=0/918, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.792) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=70) between -1 and 1726"
Iteration 1726/2266: camera=6ms, odom(quality=0/931, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.837) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=62) between -1 and 1727"
Iteration 1727/2266: camera=6ms, odom(quality=0/935, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.883) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=62) between -1 and 1728"
Iteration 1728/2266: camera=6ms, odom(quality=0/928, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.928) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=66) between -1 and 1729"
Iteration 1729/2266: camera=6ms, odom(quality=0/922, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:50.974) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=57) between -1 and 1730"
[ERROR] (2023-09-09 13:58:50.974) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1730 is ignored!
Iteration 1730/2266: camera=6ms, odom(quality=0/920, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.019) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=83) between -1 and 1731"
Iteration 1731/2266: camera=6ms, odom(quality=0/933, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.066) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=74) between -1 and 1732"
Iteration 1732/2266: camera=6ms, odom(quality=0/915, kfs=580)=40ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.112) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=57) between -1 and 1733"
Iteration 1733/2266: camera=6ms, odom(quality=0/927, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.158) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=61) between -1 and 1734"
Iteration 1734/2266: camera=6ms, odom(quality=0/906, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.204) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=73) between -1 and 1735"
Iteration 1735/2266: camera=6ms, odom(quality=0/901, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.251) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=78) between -1 and 1736"
Iteration 1736/2266: camera=6ms, odom(quality=0/922, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.296) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=76) between -1 and 1737"
[ERROR] (2023-09-09 13:58:51.297) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1737 is ignored!
Iteration 1737/2266: camera=6ms, odom(quality=0/898, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.343) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=80) between -1 and 1738"
Iteration 1738/2266: camera=6ms, odom(quality=0/899, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.388) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=71) between -1 and 1739"
Iteration 1739/2266: camera=6ms, odom(quality=0/913, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.435) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=76) between -1 and 1740"
Iteration 1740/2266: camera=6ms, odom(quality=0/916, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.480) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=79) between -1 and 1741"
Iteration 1741/2266: camera=6ms, odom(quality=0/921, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.526) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=80) between -1 and 1742"
Iteration 1742/2266: camera=6ms, odom(quality=0/927, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.572) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=81) between -1 and 1743"
Iteration 1743/2266: camera=6ms, odom(quality=0/910, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.618) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=73) between -1 and 1744"
Iteration 1744/2266: camera=6ms, odom(quality=0/921, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.663) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=76) between -1 and 1745"
[ERROR] (2023-09-09 13:58:51.663) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1745 is ignored!
Iteration 1745/2266: camera=6ms, odom(quality=0/907, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.709) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=79) between -1 and 1746"
Iteration 1746/2266: camera=6ms, odom(quality=0/910, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.756) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=75) between -1 and 1747"
Iteration 1747/2266: camera=6ms, odom(quality=0/922, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.802) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=72) between -1 and 1748"
Iteration 1748/2266: camera=6ms, odom(quality=0/922, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.849) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=90) between -1 and 1749"
Iteration 1749/2266: camera=6ms, odom(quality=0/929, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.896) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=88) between -1 and 1750"
[ERROR] (2023-09-09 13:58:51.897) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1750 is ignored!
Iteration 1750/2266: camera=7ms, odom(quality=0/942, kfs=580)=40ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.944) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=85) between -1 and 1751"
Iteration 1751/2266: camera=6ms, odom(quality=0/923, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:51.990) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=92) between -1 and 1752"
Iteration 1752/2266: camera=6ms, odom(quality=0/920, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.036) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=90) between -1 and 1753"
Iteration 1753/2266: camera=6ms, odom(quality=0/929, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.081) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 7/20 (matches=88) between -1 and 1754"
Iteration 1754/2266: camera=6ms, odom(quality=7/923, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.127) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=85) between -1 and 1755"
Iteration 1755/2266: camera=6ms, odom(quality=0/917, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.172) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=86) between -1 and 1756"
Iteration 1756/2266: camera=6ms, odom(quality=0/926, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.218) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=81) between -1 and 1757"
[ERROR] (2023-09-09 13:58:52.218) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1757 is ignored!
Iteration 1757/2266: camera=6ms, odom(quality=0/941, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.264) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=89) between -1 and 1758"
Iteration 1758/2266: camera=6ms, odom(quality=0/924, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.309) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=71) between -1 and 1759"
Iteration 1759/2266: camera=7ms, odom(quality=0/926, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.355) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=81) between -1 and 1760"
Iteration 1760/2266: camera=6ms, odom(quality=0/938, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.399) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=85) between -1 and 1761"
Iteration 1761/2266: camera=6ms, odom(quality=0/920, kfs=580)=37ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.445) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=92) between -1 and 1762"
Iteration 1762/2266: camera=6ms, odom(quality=0/910, kfs=580)=38ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.491) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=74) between -1 and 1763"
Iteration 1763/2266: camera=6ms, odom(quality=0/935, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.538) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=77) between -1 and 1764"
[ERROR] (2023-09-09 13:58:52.539) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1764 is ignored!
Iteration 1764/2266: camera=6ms, odom(quality=0/940, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.584) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=84) between -1 and 1765"
Iteration 1765/2266: camera=6ms, odom(quality=0/928, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.631) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=77) between -1 and 1766"
Iteration 1766/2266: camera=6ms, odom(quality=0/920, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.678) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 10/20 (matches=118) between -1 and 1767"
Iteration 1767/2266: camera=7ms, odom(quality=10/928, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.724) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 11/20 (matches=103) between -1 and 1768"
Iteration 1768/2266: camera=6ms, odom(quality=11/921, kfs=580)=39ms, slam=0ms
[ WARN] (2023-09-09 13:58:52.771) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 16/20 (matches=102) between -1 and 1769"
[ERROR] (2023-09-09 13:58:52.771) Rtabmap.cpp:1343::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 1769 is ignored!
Iteration 1769/2266: camera=7ms, odom(quality=16/921, kfs=580)=39ms, slam=0ms

I am surprised that it can recover from lost at some point, generarly on datasets, the robot would stay lost for the rest of the dataset unless it sees again same previously mapped areas.

Note that if you interested to record all odometry poses, add --Rtabmap/CreateIntermediateNodes true: Screenshot from 2023-09-09 14-20-53

rtabmap-report rtabmap.db 
Database: rtabmap.db
   rtabmap.db (2254, s=1.000):  error lin=0.111m (max=0.112m, odom=0.173m) ang=4.1deg, slam: avg=2ms (max=162ms) loops=2, odom: avg=29ms (max=89ms), camera: avg=6ms, map=370MB

Just remembered that this sequence is missing some frames, for example here there is a 3 seconds missing: Screenshot from 2023-09-09 14-24-36 some other places the stamps are fine but there is a large sudden rotation. It seems the sequence has some recording issues.