乱七八糟的,查了半天资料,整理如下。
(网上其他地方的资料也很混乱,这篇总结是我综合比对,得出的结论)
统一符号
连续形式:
gyroscope white noise: σg\sigma_gσg
accelerator white noise: σa\sigma_aσa
gyroscope random work: σbg\sigma_{bg}σbg
accelerator random work: σba\sigma_{ba}σba
离散(discrete)形式:
discrete gyroscope white noise: σgd\sigma_{gd}σgd
discrete accelerator white noise: σad\sigma_{ad}σad
discrete gyroscope random work: σbgd\sigma_{bgd}σbgd
discrete accelerator random work: σbad\sigma_{bad}σbad
单位
连续形式
名称 | 符号 | 单位 | 其他名称 |
---|---|---|---|
gyroscope white noise | σg\sigma_gσg | rads1Hz\frac{rad}{s}\frac{1}{\sqrt{Hz}}sradHz1, =rads=\frac{rad}{\sqrt{s}}=srad | gryo_noise_density |
gyroscope random work | σbg\sigma_{bg}σbg | rads21Hz\frac{rad}{s^2}\frac{1}{\sqrt{Hz}}s2radHz1, =rads3=\frac{rad}{\sqrt{s^3}}=s3rad | gyro's bias instability |
accelerator white noise | σa\sigma_aσa | ms21Hz\frac{m}{s^2}\frac{1}{\sqrt{Hz}}s2mHz1 | acc_noise_density |
accelerator random work | σba\sigma_{ba}σba | ms31Hz\frac{m}{s^3}\frac{1}{\sqrt{Hz}}s3mHz1 | acc's bias instability |
这也是Kalibr、GTSAM、allan_variance_ros、ORBSLAM3采用的单位。
官方连接:
Kalibr: Kalibr IMU Noise Model units problem
Allan_variance_ros: About units of params Accel Random Walk and Rate Random Walk
GTSAM: IMUFactor example noise/bias units
ORB-SLAM3: 在issue中有不少讨论,但我认为是连续形式,因为yaml文件中给出了单位是连续形式的对应。ORB-SLAM3的yaml文件
(补充:imu_utils的标定被认为是有问题的,详见:这个链接中Martin的回复)
离散形式:
参考:http://mars.cs.umn.edu/tr/reports/Trawny05b.pdf
需要将acc和gyro的随机噪声除以时间间隔根号,随机游走乘以。直观上的理解,采样频率越高,随机噪声应该越大,随机游走的应该越小。
注意:
这里的 r
是 “rate noise” 的缩写,对应上文的 “white noise”; w
是 “walk” 的缩写,对应 “random walk"。
c
和 d
对应的是 “contineous” 和 “discrete”。
所以结论,white nosie 应该除以 Δt\sqrt{\Delta t}Δt 即乘以 Hz\sqrt{Hz}Hz,random work 应该乘以 Δt\sqrt{\Delta t}Δt 即除以Hz\sqrt{Hz}Hz
名称 | 符号 | 单位 |
---|---|---|
discrete gyroscope white noise | σgd\sigma_{gd}σgd | rads\frac{rad}{s}srad |
discrete gyroscope random work | σbgd\sigma_{bgd}σbgd | rads\frac{rad}{s}srad |
discrete accelerator white noise | σad\sigma_{ad}σad | ms2\frac{m}{s^2}s2m |
discrete accelerator random work | σbad\sigma_{bad}σbad | ms2\frac{m}{s^2}s2m |
VINS-mono 采用的是离散化的噪声:
VINS-mono: Camera position is moving fast while robot is only tilted and rotated
总结
- IMU的噪声有连续形式和离散形式,两种;二者的差异:noise项需除以根号时间间隔(或乘以Hz\sqrt{Hz}Hz),walk项需要反过来。
- Kalibr,allan_variance_ros,GTSAM等用的是连续形式;
- VINS-mono采用的是离散形式;
- ORB-SLAM3应该是连续形式,和Kalibr的一致;
- 连续形式或离散形式的噪声,英文名比较混乱,一般连续形式叫:white noise 或 noise density,但由于单位非常混乱有可能作者也没搞清楚,因此主要还是看单位的对应。
其他参考资料:
IMU specifications
IMU Error Modeling Tutorial: INS state estimation with real-time sensor calibration