连续时间噪声
imu的datasheet里面给出的通常是连续时间噪声,单位分别如下:
噪声参数 | 代码中的表示 | 文档中的表示 | 单位1 | 单位2 |
---|---|---|---|---|
陀螺仪白噪声 | gyr_n | σ g \sigma_{g} σg | r a d s 1 H Z \frac{rad}{s}\frac{1}{\sqrt{HZ}} sradHZ1 | r a d s \frac{rad}{\sqrt{s}} srad |
加速度计白噪声 | acc_n | σ a \sigma_{a} σa | m s 2 1 H Z \frac{m}{s^{2}}\frac{1}{\sqrt{HZ}} s2mHZ1 | m s s \frac{m}{s\sqrt{s}} ssm |
陀螺仪偏置不稳定性 | gyr_w | σ b g \sigma_{bg} σbg | r a d s H Z \frac{rad}{s} \sqrt{HZ} sradHZ | r a d s s \frac{rad}{s\sqrt{s}} ssrad |
加速度计偏置不稳定性 | acc_w | σ b a \sigma_{ba} σba | m s 2 H Z \frac{m}{s^{2}} \sqrt{HZ} s2mHZ | m s 2 s \frac{m}{s^{2}\sqrt{s}} s2sm |
注: 上面单位1和单位2可通过 H Z = 1 / s HZ = 1/s HZ=1/s 进行转换。
离散时间噪声
假设imu的输出数据时间间隔为
Δ
t
\Delta t
Δt,转换公式如下:
σ
g
d
=
σ
g
Δ
t
(
单位
r
a
d
s
)
σ
a
d
=
σ
a
Δ
t
(
单位
m
s
2
)
σ
b
g
d
=
σ
b
g
Δ
t
(
单位
r
a
d
s
)
σ
b
a
d
=
σ
b
a
Δ
t
(
单位
m
s
2
)
\begin{aligned} \sigma_{gd} &= \frac{\sigma_{g}}{\sqrt{\Delta t}}(单位\frac{rad}{s}) \\ \sigma_{ad} &= \frac{\sigma_{a}}{\sqrt{\Delta t}}(单位\frac{m}{s^{2}}) \\ \sigma_{bgd} &= \sigma_{bg}\sqrt{\Delta t}(单位\frac{rad}{s}) \\ \sigma_{bad} &= \sigma_{ba}\sqrt{\Delta t}(单位\frac{m}{s^{2}}) \end{aligned}
σgdσadσbgdσbad=Δtσg(单位srad)=Δtσa(单位s2m)=σbgΔt(单位srad)=σbaΔt(单位s2m)
使用时注意事项(注意单位)
举例ESKF论文中的噪声设置,其噪声项单位如下:
从单位可见,测量白噪声是采用离散时间噪声单位,而偏置不稳定性采用的是连续时间噪声单位,所以在实际应用时,不能简单的使用allan方差标定工具输出的噪声结果,要结合公式确定是否要进行离散和连续噪声之间的转换。
寻找结论过程中的一些结论
- 仓库 https://github.com/gaowenliang/imu_utils 标定出来的噪声是连续时间噪声,其输出的结果文件中未注明正确的单位。
- ORB_SLAM3 使用的噪声参数是连续时间的
代码里面有将连续时间噪声转换成离散时间噪声 - VINS-Mono使用的噪声公式有问题
参考 推导 里面的误差状态估计方程如下(该公式与代码基本一致):
式中 δ b w k + 1 = δ b w k + 1 + δ t ∗ n b w \boldsymbol{\delta b}_{w_{k+1}} = \boldsymbol{\delta b}_{w_{k+1}} + \delta t * \mathbf{n}_{bw} δbwk+1=δbwk+1+δt∗nbw,该等式在单位上是不成立的, δ b w k + 1 \boldsymbol{\delta b}_{w_{k+1}} δbwk+1和 δ b w k \boldsymbol{\delta b}_{w_{k}} δbwk的单位是 r a d s \frac{rad}{s} srad,但 n b w \mathbf{n}_{bw} nbw 不管是离散的 ( r a d s ≠ s ∗ r a d s ) (\frac{rad}{s} \ne s*\frac{rad}{s}) (srad=s∗srad)还是连续的 ( r a d s ≠ s ∗ r a d s s ) (\frac{rad}{s} \ne s*\frac{rad}{s\sqrt{s}}) (srad=s∗ssrad)都不成立的。还是推荐看 Forster预积分论文 吧,该论文里面非常严谨的在公式上区分了离散imu噪声和连续imu噪声。