introlab / rtabmap

RTAB-Map library and standalone application
https://introlab.github.io/rtabmap
Other
2.72k stars 775 forks source link

Azure Kinect standalone mapping freezes #837

Open Chiyo-no-sake opened 2 years ago

Chiyo-no-sake commented 2 years ago

I'm trying to run mapping with rtabmap using only an Azure Kinect, but suddenly the mapping freezes for 5+ minutes before coming back to working (rtabmap has huge CPU load in the meanwhile). After un-freezing, the odometry is lost (as indicated by the red background) and an extreme amount of warnings gets logged:

[ WARN] (2022-03-15 16:03:07.794) OdometryF2M.cpp:519::computeTransform() Trial with no guess still fail.
[ WARN] (2022-03-15 16:03:07.794) OdometryF2M.cpp:529::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=36) between -1 and 1380" (guess=xyz=0.000000,0.000000,0.000000 rpy=-0.051612,-0.039730,-0.551234)
[ WARN] (2022-03-15 16:03:07.846) OdometryF2M.cpp:529::computeTransform() Registration failed: "Not enough inliers 7/20 (matches=22) between -1 and 1381" (guess=xyz=0.000000,0.000000,0.000000 rpy=-0.051630,-0.039702,-0.551051)
[ WARN] (2022-03-15 16:03:07.846) OdometryF2M.cpp:290::computeTransform() Failed to find a transformation with the provided guess (xyz=0.000000,0.000000,0.000000 rpy=-0.051630,-0.039702,-0.551051), trying again without a guess.
[ WARN] (2022-03-15 16:03:07.896) OdometryF2M.cpp:519::computeTransform() Trial with no guess still fail.

I noticed that, if rtabmap is configured to use IR mode on the Kinect, the time it freezes during mapping reduces to 3-7 seconds, and warning are printed again but differently:

[ WARN] (2022-03-15 16:19:20.189) OdometryF2M.cpp:519::computeTransform() Trial with no guess still fail.
[ WARN] (2022-03-15 16:19:20.189) OdometryF2M.cpp:529::computeTransform() Registration failed: "Missing correspondences for registration (-1->271). fromWords = 2000 fromImageEmpty=1 toWords = 0 toImageEmpty=0" (guess=xyz=0.000000,0.000000,0.000000 rpy=-0.155662,-0.393887,0.817585)
[ WARN] (2022-03-15 16:19:20.216) OdometryF2M.cpp:529::computeTransform() Registration failed: "Missing correspondences for registration (-1->272). fromWords = 2000 fromImageEmpty=1 toWords = 0 toImageEmpty=0" (guess=xyz=0.000000,0.000000,0.000000 rpy=-0.155667,-0.394014,0.817812)
[ WARN] (2022-03-15 16:19:20.216) OdometryF2M.cpp:290::computeTransform() Failed to find a transformation with the provided guess (xyz=0.000000,0.000000,0.000000 rpy=-0.155667,-0.394014,0.817812), trying again without a guess.
[ WARN] (2022-03-15 16:19:20.222) OdometryF2M.cpp:519::computeTransform() Trial with no guess still fail.
[ WARN] (2022-03-15 16:19:20.222) OdometryF2M.cpp:529::computeTransform() Registration failed: "Missing correspondences for registration (-1->272). fromWords = 2000 fromImageEmpty=1 toWords = 0 toImageEmpty=0" (guess=xyz=0.000000,0.000000,0.000000 rpy=-0.155667,-0.394014,0.817812)
[ WARN] (2022-03-15 16:19:20.249) OdometryF2M.cpp:529::computeTransform() Registration failed: "Missing correspondences for registration (-1->273). fromWords = 2000 fromImageEmpty=1 toWords = 0 toImageEmpty=0" (guess=xyz=0.000000,0.000000,0.000000 rpy=-0.155778,-0.393815,0.817956)
[ WARN] (2022-03-15 16:19:20.249) OdometryF2M.cpp:290::computeTransform() Failed to find a transformation with the provided guess (xyz=0.000000,0.000000,0.000000 rpy=-0.155778,-0.393815,0.817956), trying again without a guess.
[ WARN] (2022-03-15 16:19:20.256) OdometryF2M.cpp:519::computeTransform() Trial with no guess still fail.
[ WARN] (2022-03-15 16:19:20.256) OdometryF2M.cpp:529::computeTransform() Registration failed: "Missing correspondences for registration (-1->273). fromWords = 2000 fromImageEmpty=1 toWords = 0 toImageEmpty=0" (guess=xyz=0.000000,0.000000,0.000000 rpy=-0.155778,-0.393815,0.817956)
[ WARN] (2022-03-15 16:19:20.280) OdometryF2M.cpp:529::computeTransform() Registration failed: "Missing correspondences for registration (-1->274). fromWords = 2000 fromImageEmpty=1 toWords = 0 toImageEmpty=0" (guess=xyz=0.000000,0.000000,0.000000 rpy=-0.155664,-0.393734,0.817912)
[ WARN] (2022-03-15 16:19:20.280) OdometryF2M.cpp:290::computeTransform() Failed to find a transformation with the provided guess (xyz=0.000000,0.000000,0.000000 rpy=-0.155664,-0.393734,0.817912), trying again without a guess.
[ WARN] (2022-03-15 16:19:20.286) OdometryF2M.cpp:519::computeTransform() Trial with no guess still fail.
[ WARN] (2022-03-15 16:19:20.286) OdometryF2M.cpp:529::computeTransform() Registration failed: "Missing correspondences for registration (-1->274). fromWords = 2000 fromImageEmpty=1 toWords = 0 toImageEmpty=0" (guess=xyz=0.000000,0.000000,0.000000 rpy=-0.155664,-0.393734,0.817912)

The configuration of the kinect in source tab is the following: RGB-D:

Odometry Sensor: None

matlabbe commented 2 years ago

If there is a 100% CPU usage issue, see this:

High CPU Usage (100% all cores/threads): Most of the cases, this is related to OpenMP, try setting environment variable OMP_WAIT_POLICY to passive.

Otherwise, when it is lost, to recover follow instructions here: https://github.com/introlab/rtabmap/wiki/Kinect-mapping#lost-odometry-red-screens

Chiyo-no-sake commented 2 years ago

It's not a 100% CPU usage issue, however I tried setting the env var to passive but it doesn't work either, the problem of the 5+ minutes freeze still remains. It seems that the software is taking a lot of time to do some computation that is causing the freeze. Moreover, when the system comes back alive, as soon as I try to recover odometry by positioning near the last "good" frame, it freezes again.

Chiyo-no-sake commented 2 years ago

Here is the config file I used and a video demonstrating the issue with IR mode enabled. As you can see from the video, CPU is not saturated (only 200-300% on 8-cores) and as soon as the odometry recovers, the system freezes again.

Demonstration Video: https://imgur.com/a/bJhxGRr Config File: https://pastebin.com/GSLp80by

matlabbe commented 2 years ago

I reproduced the same thing with your config file. Looking at the timing statistics, it was the occupancy grid creation that required a lot of time: Screenshot from 2022-04-10 15-30-45

Do you need to occupancy grid? you can opt-out under Preferences->Local Occupancy Grid (first checkbox).

Note also that feeding the raw point cloud without decimation requires a lot of resources (for occupancy grid creation and for rendering). I suggest to downsample the depth image before creating the point cloud: Screenshot from 2022-04-10 15-32-16

Then if you want to keep the occupancy grid, you may increase the cell size to 5 cm, and disable Ray tracing (though in your case ray tracing was ignored because rtabmap is not built with OctoMap): Screenshot from 2022-04-10 15-35-03 Screenshot from 2022-04-10 15-34-48

With those changes, I get around 65 ms map updates (rtabmap using 15% cpu, peaks are when a loop closure is detected): Screenshot from 2022-04-10 15-49-26