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

Doubt regarding unit of IMU noise params #36

Open
Pallav1299 opened this issue Nov 11, 2021 · 20 comments
Open

Doubt regarding unit of IMU noise params #36

Pallav1299 opened this issue Nov 11, 2021 · 20 comments

Comments

@Pallav1299
Copy link

I am using the package to find the IMU noise parameters. The units mentioned in the README and the output file after the execution seems to be conflicting.

README:
image

O/P YAML file:
image

Comparing units of gyr_n in the above two pics suggest some conflicts. Former suggests "Noise density" while the other suggests "Noise standard deviation". @gaowenliang, can you please clarify the doubt?

@hankhsueh
Copy link

hankhsueh commented Nov 18, 2021

I have the same question.
After I got the output of yaml (gyroscope white noise), should I divide by sqrt(Hz)? or not?

@makolele12
Copy link

I also have the same question. I am trying to calibrate my IMU to use it with ORB-SLAM3.
Therefore I need the data in the following units:

IMU gyro noise: rad/s/sqrt(Hz)
IMU gyro walk: rad/s^2/sqrt(Hz)
IMU accelerometer noise: m/s^2/sqrt(Hz)
IMU accelerometer walk: m/s^3/sqrt(Hz)

--> Do I need to divide by sqrt(Hz)? or is the output of imu_utils doing it already?

@mintar
Copy link

mintar commented Nov 27, 2021

@gaowenliang hasn't been active in this repo for over 3 years, so I'll try to answer. You're right, the units were wrong. Check out my fork of this repo where I fixed this and many other problems:

https://github.com/mintar/imu_utils

@gaowenliang : Feel free to merge my changes into your repo, or contact me if you want me to send a pull request.

@FishInWave
Copy link

@gaowenliang hasn't been active in this repo for over 3 years, so I'll try to answer. You're right, the units were wrong. Check out my fork of this repo where I fixed this and many other problems:

https://github.com/mintar/imu_utils

@gaowenliang : Feel free to merge my changes into your repo, or contact me if you want me to send a pull request.

Hi,I don't know much about IMU. I want to use this repo to get bias and noise for LIO-SAM, so this repo's bias Instability is not what I think but a random work?
How can I get the bias and noise ?

@mintar
Copy link

mintar commented Nov 27, 2021

You can get the bias and noise using one of these repos:

@Kaapeine
Copy link

@gaowenliang hasn't been active in this repo for over 3 years, so I'll try to answer. You're right, the units were wrong. Check out my fork of this repo where I fixed this and many other problems:

https://github.com/mintar/imu_utils

@gaowenliang : Feel free to merge my changes into your repo, or contact me if you want me to send a pull request.

The 'white noise' values from your repo are the same as 'noise density', right? i.e. the noise standard deviation divided by the square root of the sampling rate of the signal. Is this the value required by VIO packages? I'll ask this over at VINS also.

@mintar
Copy link

mintar commented Nov 29, 2021

The 'white noise' values from your repo are the same as 'noise density', right? i.e. the noise standard deviation divided by the square root of the sampling rate of the signal.

Yes, correct. And the "random walk" values from my repo are the continuous-time angle rate random walk (for gyros) and acceleration random walk (for accelerometers) values, also called bias random walk, i.e. the random walk standard deviation multiplied by the square root of the sampling rate of the signal.

Is this the value required by VIO packages?

I think so. These should be exactly the gyr_n, acc_n, gyr_w and acc_w parameters from the VINS fusion config (e.g., here).

In fact, I've been doing all this work to figure out the correct parameters for VINS.

However, something I noted is that after carefully calibrating my IMU, I still had to multiply the parameters with a factor of 10-15x to make it work in VINS fusion.

I think there are multiple explanations for this:

  • The allan variance estimation methods (mintar/imu_utils and ori-drs/allan_variance_ros) estimate a model based on Q, N, B, K, R or at least N ("rate/acceleration white noise"), B ("bias instability"), K ("rate/acceleration random walk"). But all VIO packages and Kalibr just use N and K.
  • The calibration is done under close to ideal circumstances in a static setup. In a dynamic setting, with other factors like temperature changes etc., the noise will be higher.
  • The calibration packages take the average of the axes, but some IMUs have different gyros/accelerometers for different axes, so one should probably use the maximum and not the average to be on the safe side.
  • In my setup, there's no hardware synchronization between IMU and camera. Maybe using a higher standard deviation for the IMU prevents VINS from trusting the IMU too much and deviating when the real error is from a wrong time synchronization.
  • And lastly, there's still the possibility that I still got the units/values wrong, and VINS expects something different from what I provide.

Here are some plots of the estimated models when only using the N and K components for just the Y axis gyro + accelerometer and of the values I ended up using in my VINS config. You can see that the values of the estimated models are clearly too low; the estimated model should overbound the measured values. Still, the values I ended up using are ridiculously high, so there's still a chance I'm missing something.

gyro

acceleration

Parameter Units vins default current ADIS16460 datasheet allan_variance_ros mintar/imu_tools (my fork)
Acc White Noise (N) (m/s)/√s acc_n 0.1 0.055 0.0015 0.00453 0.00351
Gyr White Noise (N) rad/√s gyr_n 0.01 0.0016 0.000049 0.00013 0.00012
Acc Random Walk (K) (m/s²)/√s acc_w 0.001 0.0013 N/A 0.00017 0.000028
Gyr Random Walk (K) (rad/s)/√s gyr_w 0.0001 0.000027 N/A 0.000002967 0.000001645

I'll ask this over at VINS also.

Good idea! Perhaps I missed something, and the parameters are not correct, so better ask.

@arenas7307979
Copy link

arenas7307979 commented Apr 15, 2022

@mintar
hi, Martin

Thank you for your sharing.
whether the calibration result can be directly used in ORBSLAM3 and kalibr?
or need to multiply the parameters with a factor like sqrt(hz)?

IMU.NoiseGyro:
IMU.GyroWalk:
IMU.NoiseAcc:
IMU.AccWalk:

@mintar
Copy link

mintar commented Apr 15, 2022

Yes, the parameters from my fork can be used directly in kalibr and probably also ORBSLAM3. Also see this wiki page: https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model

You definitely shouldn't multiply by sqrt(Hz) or something. But you probably have to increase the values by 10x to 15x to account for more noise during realistic conditions compared to the static calibration scenario.

@asimonov
Copy link

Martin @mintar ,

Thank you for this great discussion!

I was looking at VINS-fusion params for a while now, for different integrated and custom cam+imu sensors.
I managed to make it work quite reliably on all sensors after one crucial observation - all example IMU params in VINS-fusion repo are the same:

#imu parameters       The more accurate parameters you provide, the better performance
acc_n: 0.1          # accelerometer measurement noise standard deviation. 
gyr_n: 0.01         # gyroscope measurement noise standard deviation.     
acc_w: 0.001        # accelerometer bias random work noise standard deviation.  
gyr_w: 0.0001       # gyroscope bias random work noise standard deviation. 

for example here for EUROC:
https://github.com/HKUST-Aerial-Robotics/VINS-Fusion/blob/master/config/euroc/euroc_mono_imu_config.yaml#L49

but when I calibrate, say Realsense D455, I get something like this:

#imu parameters       The more accurate parameters you provide, the better performance
acc_n: 0.0018         # accelerometer measurement noise standard deviation. 
gyr_n: 0.013         # gyroscope measurement noise standard deviation.     
acc_w: 0.000004         # accelerometer bias random work noise standard deviation.  
gyr_w: 0.0002       # gyroscope bias random work noise standard deviation. 

the problem is accelerometer params - they seem to be way too narrower than example VINS-fusion parameters, for pretty much all sensors I tried.
And they are not different by 10-15x, but couple of orders of magnitude.

If I try to use parameters as calibrated I always get VINS-fusion drift into infinity straight after initialisation.

But if I use the example parameters as mentioned in VINS-fusion repo, then odometry works nicely after initialisation is done. At least for stereo sensors.

Did you observe something like this?
Or do you have any idea what is going on here?

@NikolausDemmel
Copy link

Interesting, thanks for sharing. Just a random thought about the Realsense IMU. Not sure about the D455, but at least for the T265 the accelerometer has a lower sampling rate than the gyro and there is a mode where values are interpolated or duplicated internally to output accelerometer data at the same rate as gyro. Maybe that messes with the noise calibration.

@mintar
Copy link

mintar commented Apr 20, 2022

FWIW, here are the calibration values I obtained for my Realsense D455.

First, the d455_imu_param.yaml from my fork of imu_utils:

%YAML:1.0
---
type: IMU
name: d455
Gyr:
   unit: "gyr_n: rad / sqrt(s), gyr_w: rad / s^2 / sqrt(Hz)"
   avg-axis:
      gyr_n: 1.1247817539293294e-04
      gyr_w: 6.8560096244238481e-07
   x-axis:
      gyr_n: 9.9526574733667635e-05
      gyr_w: 1.9686824895632978e-10
   y-axis:
      gyr_n: 1.3819925830281483e-04
      gyr_w: 1.4313630360580132e-06
   z-axis:
      gyr_n: 9.9708693142316399e-05
      gyr_w: 6.2524298302018503e-07
Acc:
   unit: "acc_n: m / s^2 / sqrt(Hz), acc_w: m / s^3 / sqrt(Hz)"
   avg-axis:
      acc_n: 1.2284895136765762e-03
      acc_w: 9.9082719328218624e-05
   x-axis:
      acc_n: 1.1235279258458876e-03
      acc_w: 1.0251140823532781e-04
   y-axis:
      acc_n: 1.0885250751070067e-03
      acc_w: 1.1355246318501114e-04
   z-axis:
      acc_n: 1.4734155400768347e-03
      acc_w: 8.1184286564316914e-05

Next, the imu.yaml from allan_variance_ros on the same data:

#Accelerometer
accelerometer_noise_density: 0.001409773432203808 
accelerometer_random_walk: 0.0001329062251978931 

#Gyroscope
gyroscope_noise_density: 0.0001133526607488234 
gyroscope_random_walk: 2.3196512261002865e-06 

In summary:

VINS default your values my values (imu_utils) my values (allan_variance_ros)
acc_n 0.1 0.0018 0.00122849 0.00140977
gyr_n 0.01 0.013 0.00011248 0.00011335
acc_w 0.001 0.000004 0.00009908 0.00013291
gyr_w 0.0001 0.0002 0.00000069 0.00000232

Did you perhaps mix up some of those values? Or weren't you using my fork?

That being said, my values in the table above are also 10x - 150x smaller than the VINS defaults, and with these values, VINS won't work. I haven't used VINS with the D455, but with a different camera + IMU setup, and I had the same effect there. I ended up reducing the VINS defaults by factors between 2 and 6, because if you diverge further from the VINS defaults, VINS stops working. My calibrated values were actually about 15x lower than that. At this point, I wonder if calibrating your IMU is actually worth the effort if you're going to manually fiddle with the parameters anyway.

@arenas7307979
Copy link

arenas7307979 commented Apr 20, 2022

Hii, @mintar @NikolausDemmel
thanks for sharing
in terms of theory, What reason causes this factor? (multiply the parameters with a factor of 1x - 1xx)
How do I choose the right value for different SLAM algorithms?

@mintar
Copy link

mintar commented Apr 20, 2022

I think there's multiple reasons for this:

  • The main reason is probably the following: You're recording the calibration data while the device is completely stationary. When the device is in motion, experiences vibrations or temperature changes, the actual noise may be much higher than when it is stationary.
  • The calibration procedures often find an "average" model that minimizes the error to the observed data, but to be on the safe side, you will probably want a model that strictly overbounds the observed data (see the "fitted model" lines in the graphs I posted above).
  • I systems like VINS Fusion, the IMU model ultimately balances how much the SLAM system trusts the IMU vs. how much it trusts the visual odometry. There may be situations where the right thing to do would be to lower the variance of the visual odometry, but if instead you increase the variance of the IMU, you get the same effect. So if you're only experimenting with the IMU parameters, you may miss that there's some other parameter or model assumption that would also need to be changed.
  • Lastly, I'm only 90% certain that we're calculating the right values here. I spent several weeks on this (much longer than anticipated), but perhaps I still missed something, and we're forgetting a factor somewhere.

@asimonov
Copy link

Interesting, thanks for sharing. Just a random thought about the Realsense IMU. Not sure about the D455, but at least for the T265 the accelerometer has a lower sampling rate than the gyro and there is a mode where values are interpolated or duplicated internally to output accelerometer data at the same rate as gyro. Maybe that messes with the noise calibration.

yes, that's the mode I use - interpolate accelerometer values. may be this is the reason...

@NikolausDemmel
Copy link

@mintar has all very good points. One additional factor---related to what was mentioned about calibrating in static vs running in dynamic conditions---might be that the IMU model used in all these VO / SLAM algorithms is practical, but still simplistic. I.e. it simply doesn't model many of the effects on the physical device. I'm thinking of temperature-dependent bias, cross-axis sensitivity, etc. All this means that the errors in your model aren't actually independent and bias-free and one way to deal with it is by increasing the measurement uncertainty to "mask" out the un-modelled behaviour.

But yes, it's a valid question what's the point of calibrating the IMU when you just hand-tune the values anyway. I think hand-tuning will always be needed. Calibration can still inform you about the relative quality of different IMUs and thus help when tuning the parameters (e.g. tell you if your values for a new IMU should be higher or lower than for some reference IMU that you know works well).

@arenas7307979
Copy link

arenas7307979 commented May 23, 2022

@mintar hi, martin

following tools to calculate the imu noise results and used them for Kalibr, but the acc convergence effect and reprojection error were not good in Kalibr

I tried to get better acc convergence results (reprojection error still high) when multiply factor with x10 for accelerometer_noise_density and accelerometer_random_walk

https://github.com/mintar/imu_utils
https://github.com/ori-drs/allan_variance_ros

kalibr_result only vo

report-cam-our_nascar_datasetp50_imei7289calibr_728920220523_calibration20220523_calibration.pdf

allan_variance_ros result :
acceleration
gyro
#Accelerometer
accelerometer_noise_density: 0.0023093122966287663
accelerometer_random_walk: 9.754280328273595e-05
#Gyroscope
gyroscope_noise_density: 8.556686388277563e-05
gyroscope_random_walk: 1.7024430789088757e-06

report-imucam-our_nascar_datasetp50_imei728920220523_calibration20220523_calibration.pdf

imu_utils results :
Gyr:
unit: "gyr_n: rad / sqrt(s), gyr_w: rad / s^2 / sqrt(Hz)"
avg-axis:
gyr_n: 6.4571634112763670e-05
gyr_w: 7.5463540571697402e-08
x-axis:
gyr_n: 8.2809540837727724e-05
gyr_w: 2.2624825132915823e-07
y-axis:
gyr_n: 7.0443502725776796e-05
gyr_w: 8.4495086640230569e-11
z-axis:
gyr_n: 4.0461858774786483e-05
gyr_w: 5.7875299293741360e-11
Acc:
unit: "acc_n: m / s^2 / sqrt(Hz), acc_w: m / s^3 / sqrt(Hz)"
avg-axis:
acc_n: 7.9859666683206910e-04
acc_w: 2.6832686051089446e-05
x-axis:
acc_n: 9.1287741201428606e-04
acc_w: 5.1106059191407176e-05
y-axis:
acc_n: 9.3866594974910584e-04
acc_w: 2.9383859860592782e-05
z-axis:
acc_n: 5.4424663873281519e-04
acc_w: 8.1391012683762964e-09
report-imucam-our_nascar_datasetp50_imei728920220523_calibration20220523_calibration.pdf

@ggelmi
Copy link

ggelmi commented Feb 28, 2024

We have to keep in mind that vins-mono imu parameters are in discrete domain and while output of allan-variance ros and datasheets are in continuous domain. Orbslam3 on the other hands, takes in the continuous form and does the discretization under the hood. That could explain why vins mono imu params are way different from continuous form params.

@FANFANFAN2506
Copy link

Hi @mintar, thanks for sharing all the insights. I am also trying to get the parameters for my Realsense D435i, however, I am really new to the ros thing. I tried to use the record program from ORB-SLAM3, to record the gyro.txt, and acceleration.txt but I don't know what should be the right file structure to convert it into a rosbag. Currently I am using the Kalibr_bagcreater, not sure if that's the right way. I couldn't extract the example rosbag from the allan_variance_ros using the kalibr_bagextracter as well. Could you share some advice on how you record the rosbag with your Realsense D455? Thanks in advance.

@SJTUlibochen
Copy link

Hi @FANFANFAN2506, I'm not sure whether it is too late now, maybe you can run the default rs_camera.launch installed with ros-noetic-realsense2-camera (ROS1/2 wrapper for Realsense) with some args changed:
roslaunch realsense2_camera rs_camera.launch enable_gyro:=true enable_accel:=true unite_imu_method:=linear_interpolation
And a rostopic /camera/imu will be published, so you can use rosbag record -O <bag_name> /camera/imu to record msg

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