rtabmap icon indicating copy to clipboard operation
rtabmap copied to clipboard

D455 trouble with OpenVins addon, need help

Open cdb0y511 opened this issue 9 months ago • 12 comments

Hi, @borongyuan. I notice you have given a useful commit #1107. I think the VIO may applicable for rtabmap, but I try D455 with your default parameters and can not run odometry properly, start with :

[init]: not enough feats to compute disp: 0,0 < 15 [init]: not enough feats to compute disp: 0,0 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 [init]: not enough feats to compute disp: 0,61 < 15 Propagator::select_imu_readings(): No IMU measurements to propagate with (0 of 2). IMU-CAMERA are likely messed up!!! [ZUPT]: There are no IMU data to check for zero velocity with!!

For a while and then failed with Propagator::select_imu_readings(): No IMU measurements to propagate with (0 of 2). IMU-CAMERA are likely messed up!!! [ZUPT]: There are no IMU data to check for zero velocity with!!

Any advice? I build with latest https://github.com/rpng/open_vins/tree/4534a2f32d4763bdc8c95121b3292c7423e12aca with some small modifications to work with OpenCV 4.8. and build with rtabmap standalone with the latest commit.

cdb0y511 avatar Oct 08 '23 02:10 cdb0y511

For the RealSense series, I have only used the D435i before. Since the D455 has been discontinued, and it is said that the color problem of its color camera affects outdoor applications, I have never tried it. But there is a d455 configuration in the config directory of OpenVINS, you can use this as a reference. The biggest difference when using RTAB-Map standalone should be the driver part. The initial "not enough feats to compute disp" warning is normal. Later warning will occur when image data arrives earlier than IMU data. We have also discussed this part in https://github.com/introlab/rtabmap/pull/1107#issuecomment-1740832434. My understanding is that for most cameras with hardware synchronization, the IMU data will be transmitted immediately after sampling, while the camera data will have to go through ISP processing, encoding, depth calculation, etc., so it will always arrive later. I'm not sure how the current hardware synchronization and driver of d455 are implemented. Have you enabled publishInterIMU? This needs to be enabled for most VIOs. I also get the warning once when I disable it using OAK camera, but then it still works. Although this is not recommended.

borongyuan avatar Oct 08 '23 05:10 borongyuan

Thanks, @borongyuan, for the help. After I turn on the publishInterIMU, it barely works.

  1. It somtimes ended with : Propagator::select_imu_readings(): Zero DT between IMU reading 1 and 2, removing it! Propagator::select_imu_readings(): Zero DT between IMU reading 1 and 2, removing it! Propagator::select_imu_readings(): Zero DT between IMU reading 1 and 2, removing it! [FATAL] (2023-10-08 14:35:27.737) CameraRealSense2.cpp:1477::captureImage() Condition (imuStamp > lastImuStamp_) not met! [FATAL] (2023-10-08 14:35:27.737) CameraRealSense2.cpp:1477::captureImage() Condition (imuStamp > lastImuStamp_) not met! This may be the synchronization problem.

  2. And it works for a few frames and drafts away quickly, especially when I stop moving and the IR is on; any advice? I will try d435i and t265 next week.

  3. I am not so sure about the visual part, for use stereo is true, that stereo is used as visual odometry? But the IR is on, I think the odometry is suffering. How can I change to the RGB camera for visual odometry, and by the way, another visual improvement can be done? Is another visual front end like superpoint with superglue possible?

cdb0y511 avatar Oct 08 '23 07:10 cdb0y511

I think this is a good VIO for rtabmap so long as ORB_SLAM3 integration is disabled with the IMU part.

cdb0y511 avatar Oct 08 '23 07:10 cdb0y511

  1. Zero DT between IMU reading 1 and 2, removing it!

This is a bit unusual. Data timestamps should generally increase monotonically. I guess this may be related to the IMU output method. The accelerometer and gyroscope in some IMUs will work at different frequencies and output data separately. They need to be set to the same frequency or interpolated to the same frequency to output together.

  1. And it works for a few frames and drafts away quickly, especially when I stop moving and the IR is on; any advice?

Current default noise configuration is for OAK camera (BMI270 IMU). So for other devices you need to adjust according to their allan variance. I also have disp-based ZUPT enabled by default. You can also enable imu-based ZUPT. This helps handle extreme situations at zero velocity. If you use mono cameras, IR should be turned off. Because it produces a non-static texture, it will obviously mislead VIO. It doesn't matter if you use a color camera because the infrared light will be filtered.

  1. I am not so sure about the visual part, for use stereo is true, that stereo is used as visual odometry? But the IR is on, I think the odometry is suffering. How can I change to the RGB camera for visual odometry, and by the way, another visual improvement can be done? Is another visual front end like superpoint with superglue possible?

use_stereo option only affects the tracker part. It adds stereo constraints to features. But if extrinsic is not accurate enough, it may lead to reduced accuracy. So I turn this off most of the time. Someone suggested to use XYZ representation when use_stereo is enabled, and inverse depth representation when it is disabled. Enabling online parameter calibration may help, but degenerate motion needs to be avoided (such as in-vehicle use). The official recommendation is to enable it for handheld use. I haven't added this part of the params yet. OpenVINS uses a small number of features. The default is 50, and the accuracy will not improve much when it is increased to more than 100. So I didn't add its features to SensorData. I think superpoint won't be of much help to the front-end, it's more useful to the back-end.

borongyuan avatar Oct 08 '23 08:10 borongyuan

After recent updates, I recorded a new demo. https://youtu.be/WiyaTdKvOmg

borongyuan avatar Oct 12 '23 07:10 borongyuan

@cdb0y511

2. And it works for a few frames and drafts away quickly, especially when I stop moving and the IR is on; any advice?
   I will try d435i and t265 next week.

3. I am not so sure about the visual part, for use stereo is true, that stereo is used as visual odometry? But the IR is on, I think the odometry is suffering. How can I change to the RGB camera for visual odometry, and by the way, another visual improvement can be done? Is another visual front end like superpoint with superglue possible?

Make sure the IR emitter is disabled if you are using IR cameras, otherwise the random IR pattern will confuse VO.

matlabbe avatar Oct 15 '23 18:10 matlabbe

After recent updates, I recorded a new demo. https://youtu.be/WiyaTdKvOmg

Hi,@borongyuan 1.I see it reaching a promising result with openvins integration, but I am curious about the Superpoint setting (indoor and outdoor), with both indoor and outdoor scenes; which setting are you using (indoor and outdoor)? Does the setting (indoor and outdoor) make no difference? 2. I see the odometry part shows superpoint feature, but you commented before, superpoint is only used for loopcloure. Not actual openvins visual odometry? 3. Is the matcher the default method? Not superGlue?

cdb0y511 avatar Oct 18 '23 08:10 cdb0y511

I see it reaching a promising result with openvins integration, but I am curious about the Superpoint setting (indoor and outdoor), with both indoor and outdoor scenes; which setting are you using (indoor and outdoor)? Does the setting (indoor and outdoor) make no difference?

What is used here is SuperPoint running on OAK, which we added in this PR. This may be slightly different from SuperPoint running with PyTorch. There is no special setting, the video is one shot without any editing. I think it is mainly the NNDR strategy that enables good matching for different keypoint configurations.

I see the odometry part shows superpoint feature, but you commented before, superpoint is only used for loopcloure. Not actual openvins visual odometry?

If we add keypoints to sensor data, both VO and loop closure can choose whether to use it or not. I only use the SuperPoint provided by the camera for loop closure.

Is the matcher the default method? Not superGlue?

OAK’s computing power is only enough to run SuperPoint.

borongyuan avatar Oct 18 '23 15:10 borongyuan

After recent updates, I recorded a new demo. https://youtu.be/WiyaTdKvOmg

May I ask you a question about the versions of RTAB-Map and OpenVINS?

Are you using the latest versions of RTAB-Map and OpenVINS?

If not, could you please tell me which versions you are using?

I want to use RTAB-Map + OpenVINS with ZED2, Thank you very much!!

ericlai0323 avatar Nov 20 '23 15:11 ericlai0323

Are you using the latest versions of RTAB-Map and OpenVINS?

Tested: Latest version of RTAB-Map + OpenVINS v2.7

borongyuan avatar Nov 22 '23 02:11 borongyuan

对于RealSense系列,我之前只使用过D435i。由于D455已经停产,而且据说其彩色相机的色彩问题影响户外应用,所以我一直没有尝试过。但OpenVINS的config目录下有一个d455的配置,可以作为参考。 独立使用 RTAB-Map 时最大的区别应该是驱动程序部分。最初的“没有足够的功能来计算 disp”警告是正常的。当图像数据早于 IMU 数据到达时,会出现稍后警告。我们也在#1107(评论)中讨论了这一部分。我的理解是,对于大多数硬件同步的相机来说,IMU数据在采样后会立即传输,而相机数据则要经过ISP处理、编码、深度计算等,所以总是会晚到。不太清楚目前d455的硬件同步和驱动是如何实现的。您启用了publishInterIMU吗?大多数 VIO 都需要启用此功能。当我使用 OAK 相机禁用它时,我也会收到一次警告,但它仍然有效。虽然不建议这样做。

HELLO! I'm trying to use d435i to run rtabmap. I see you have used d435i before. Can you tell me how to operate it? Thank you very much.

tulingcheng86 avatar Mar 11 '24 12:03 tulingcheng86

@tulingcheng86 This issue is related to D435i + open_vins and rtabmap. For general D435i usage with rtabmap see this tutorial, in particular the "RealSense D435i camera (IR-Depth)" example.

matlabbe avatar Mar 13 '24 05:03 matlabbe