introlab / rtabmap

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

OAK Internal Sync & DepthAI HF-Net Support #1193

Closed borongyuan closed 3 months ago

borongyuan commented 6 months ago

All messages except IMU are synchronized using the Sync node introduced in v2.24.0. LGTM, but I'll keep this PR as a draft until the depthai in ROS repo is updated to 2.24.0. In addition, they have not added doc for Sync node yet, only providing new examples. We can do more inspections and tests during this time. The IR settings have also been changed to new methods in v2.24.0.

borongyuan commented 5 months ago

Since I have recently received several new OAK cameras equipped with BNO086, I presume they have stopped producing the ones equipped with BMI270. According to the document and datasheet, the accelerometer and gyroscope of the BNO086 cannot be set to the same sample rate.

  • Accelerometer: 15Hz, 31Hz, 62Hz, 125Hz, 250Hz 500Hz
  • Gyroscope: 25Hz, 33Hz, 50Hz, 100Hz, 200Hz, 400Hz
  • Magnetometer: 100Hz

I tested different configs. Either

imu->enableIMUSensor({dai::IMUSensor::ACCELEROMETER_RAW, dai::IMUSensor::GYROSCOPE_RAW}, 100);

or

imu->enableIMUSensor(dai::IMUSensor::ACCELEROMETER_RAW, 125);
imu->enableIMUSensor(dai::IMUSensor::GYROSCOPE_RAW, 100);

will cause the IMU data to be output at 100Hz. Part of the accelerometer data will be discarded directly to reduce to 100 Hz without linear interpolation. In this configuration, the VIO's robustness is affected and may begin to drift during sudden stops. This problem can be greatly avoided by setting the IMU output rate to 200 Hz. This can be compatible with both BMI270 and BNO086 devices. But it may not be the optimal configuration for both types of devices. BMI270 is actually unable to stably reach an output of 200 Hz, generally only 160Hz~180Hz. If we only consider supporting BNO086, we can actually

imu->enableIMUSensor({dai::IMUSensor::ACCELEROMETER_RAW, dai::IMUSensor::GYROSCOPE_RAW, dai::IMUSensor::ROTATION_VECTOR}, 200);

In this way, we directly use the orientation output of BNO086 that fuses 9-axis data, without using Madgwick filter or complementary filter later.

borongyuan commented 5 months ago

Set sync threshold to half of the frame interval. This avoids incorrect sync between different cameras.

borongyuan commented 4 months ago

The depthai-core in the ROS repository is still at 2.23.0. I will remind them.

matlabbe commented 4 months ago

Ah yeah I didn't verify if the ros package was released with 0.24 (just assumed it since it is almost 3 months ago old), I created a label to quickly know that we are waiting for dependency update.

matlabbe commented 3 months ago

depthai 2.24 binaries are out: