Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Running R-VIO on the Kitti dataset #23

Closed
JanOpper opened this issue Oct 23, 2020 · 9 comments
Closed

Running R-VIO on the Kitti dataset #23

JanOpper opened this issue Oct 23, 2020 · 9 comments

Comments

@JanOpper
Copy link

Hi,

first of all thank you for sharing your code with the community!
I am trying to apply the code to the kitti raw dataset, specifically a residential recording (2011_10_03_drive_0027).
I am starting the estimation from a point where the car is at standstill und doing a right turn afterwards, because I was hoping the gravity and bias estimation would benefit from this.
I already found out that the accuracy is highly dependent on the IMU parameters, but unfortunately I couldn't find the actual values for kitti. I tried to estimate them myself via an Allan standard deviation plot from a few seconds of standstill data from a different track, but from my understanding this is only sufficient for the white noise values, but not the bias random walk. I therefore guessed an appropriate value for the latter.
I also found out that I need much higher white noise values than calculated for the turns to be recognized at all, about two orders of magnitude (used sigma_g: 0.0046, sigma_a: 0.06).
R-VIO_Kitti
As you can see in the attached screenshot the algorithm is doing massive position corrections at each 90 degree turn. I am assuming this is because the uncertainty is reduced when the car is turning. But I am wondering why the uncertainty und deviation is so high in the first place. From what I have seen in your paper, you had much less deviation and corrections when you run the code on your urban driving test data.
I was hoping maybe you have an idea why the performance is not as good as in your paper and how I might improve this.
I will happily provide further details of the configuration or data I have used, if necessary.
Thank you very much!

@huaizheng
Copy link
Member

huaizheng commented Oct 25, 2020

First of all, thanks for your interest, @JanOpper. Yes, the IMU parameters play a very important role in the visual-inertial estimation, because those values will contribute to the covariance which is the key component for computing the state update. It would cause some critical problem if the IMU parameters are set with random numbers, as shown in your result, because this may incorrectly change the uncertainty about IMU measurement in the sense of sensor fusion with Kalman filter.
If those values are not provided with the dataset, you can instead get the reference values based on the sensor datasheet. For example, kitti uses RT3003 GNSS/INS as the inertial sensor whose datasheet (RT3000 v3) can easily be found online. Therefore, the IMU parameters can be computed yourself by referring to the 'bias stability' (n_ba, n_bg) and 'random walk' (n_a, n_g), with particular care about the unit conversion https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model. Once you get those reference values, you can try it again to see what you can get now. Good luck.

@JanOpper
Copy link
Author

Thank you for your feedback.
I have now tried the values from https://www.oxts.com/software/navsuite/documentation/datasheets/RT3000v3_ds.pdf and hopefully converted them correctly. One example is the conversion from OXTS' Gyro "Random walk" to Kalibr's "White Noise" / "IMU.sigma_g" in the config yaml:
kitti_gyro_random_walk_white_noise
Those parameters yielded the following result:
rvio_kitti_datasheet_noise
Unfortunately this performs worse than with the manually set values.
I have also observed that the Mahalanobis distance check excludes most of the visual features.
I made another experiment and turned off the update step, so that only the IMU data is being integrated.
rvio_kitti_update_only
Interestingly, there are no visible turns at all. I am wondering, how much is the performance of the algorithm being affected by the IMU data rate (100dps) and the camera frame rate (10fps)?
I would also like to know: What are good start conditions for this algorithm, especially in urban driving?

@JanOpper
Copy link
Author

JanOpper commented Nov 9, 2020

I have another question: To what extent does the algorithm depend on time-synchronized data? Because I noticed that EUROC is actually time synchronized, whereas Kitti is not.

@huaizheng
Copy link
Member

huaizheng commented Nov 10, 2020

Currently our algorithm requires the results of both spatial and temporal calibrations i.e., the data time offset between camera and IMU is needed (as listed in the config file). So if this value is not set properly, the performance shall not be guaranteed. Especially, if the data rates of camera and IMU are too different, the influence of this value will become more significant which could lead to the result that you have shown.

@JanOpper
Copy link
Author

Both the IMU and the camera have absolute timestamps, so there should be no fixed time offset. However, the camera was coupled to the lidar and not to the IMU, i.e. the photos were taken when the lidar pointed forward. This can lead to some jitter-like fluctuations in the camera frequency.

@JanOpper
Copy link
Author

I continued working on the dataset and was able to increase the accuracy substantially.

  1. I lowered the threshold for the initial detection of movement to 1/10 of the value for EuroC.
  2. I deactivated the Sampsons error.
  3. I set the noise values for the IMU to 10x of the converted values from the datasheet. I think that is a reasonable way to account for any unmodeled effects.

With these changes I get the following result:
R_VIO_FAST_INIT_NO_SAMPSON_DATASHEET_NOISE10_github
So it still jumps at some points, but much less than before.

@huaizheng
Copy link
Member

Very glad to see this result @JanOpper. The threshold for motion detection is tunable (marked in the config file) depending on the sensitivity of IMU. However, the Sampson error is used for the ransac which is also tunable, so maybe you can try to increase that value instead to allow more features to be involved. While recently I have not found time to test this dataset myself, if it is possible, could you share with me the config file and data you are using so that I can try it sometime.

@JanOpper
Copy link
Author

Interestingly I had to decrease the inlier threshold for the ransac, because there were too many features included. Regardless of this, the code ran just as well as without the Sampson error.
I also uploaded the data you requested here: https://www.dropbox.com/s/09ys3ndxuaeyc8z/Kitti_RVIO.zip?dl=0
I hope that this is a suitable way to share these large amounts of data.

And thank you again for your support.

@wsh122333
Copy link

Interestingly I had to decrease the inlier threshold for the ransac, because there were too many features included. Regardless of this, the code ran just as well as without the Sampson error. I also uploaded the data you requested here: https://www.dropbox.com/s/09ys3ndxuaeyc8z/Kitti_RVIO.zip?dl=0 I hope that this is a suitable way to share these large amounts of data.

And thank you again for your support.

@JanOpper
Thank you for your contribution!
I am interesting in using R-VIO with the kitti raw dataset, and also had some problems about it. I tried your dataset and config file, it worked well. But when I changed the dataset to my kitti rosbag ( 2011_10_03_drive_0027 raw unsynced IMU data and gray left cam), the code couldn't work. I am hoping your support and you may tell how your rosbag is composed. Thank you so much!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants