本文将详细介绍AirSim中的惯性测量单元IMU传感器的噪声参数模型以及如何在VIO算法中应用这些参数。
我们首先从IMU传感器的参数说起。
IMU,即惯性测量单元,是一种常见的传感器。应用于移动机器人的IMU一般输出两类测量值:
因此,IMU有时可以看作是“加速度计”和“陀螺仪”的结合体。
加速度计和陀螺仪的误差可以分为:确定性误差(系统误差),随机误差。
确定性误差可以事先标定确定,包括:bias,scale等;随机误差通常假设噪声服从高斯分布,包括:高斯白噪声,bias随机游走等
下面我们重点讨论无法方便地事先确定的随机误差:
这一项随机误差的名字可能有很多,例如“高斯白噪声”、“随机行走误差(random walk)”、“Noise density”等,表达的都是这项内容。以陀螺仪为例,单位为dps/rt(Hz),或者deg/rt(h)。
陀螺仪测量的角速度,加速度计测量的加速度的噪声是高斯白噪声。因此这一项误差表示的物理意义就是单位时间内角度不确定性(标准差)、速度不确定性(标准差)的增量。
例如,如果陀螺仪的的随机行走误差是20deg/rt(h),那意味着在一个小时后,积分得到的角度的误差的标准差是20deg。
以下表格为IMU随机误差的单位:
Parameter | YAML element | Symbol | Units |
---|---|---|---|
Gyroscope “white noise” | gyr_n |
||
Accelerometer “white noise” | acc_n |
||
Gyroscope “bias Instability” | gyr_w |
||
Accelerometer “bias Instability” | acc_w |
理论上讲,当IMU完全不受激励时,输出应该为零,但现实往往不是这样。一般我们将传感器所受激励为零时的输出读数成为传感器的“零偏(bias)”。IMU的零偏属于系统误差,可以通过某些操作在事先进行标定。但IMU在使用过程中,会出现零偏慢慢变化的情况。直观上理解,零偏不稳定性误差会使陀螺仪和加速度计的零偏随时间慢慢变化,逐渐偏离开机时校准的零偏误差;同时还会造成一部分随机行走误差的效果。可以简要理解为在一段时间内零偏的变化量,其他名称可能还有“零偏随机游走(bias random walk)”、“零偏稳定性(bias stability)”等。
根据瑞士苏黎世理工学院的kalibr标定工具库中的介绍:IMU-Noise-Model,IMU随机误差参数可以由以下方式获得:
Allan标准差分析法是通过对一段时间内的已采集IMU数据估计IMU随机误差参数的一种数值计算方法。简要介绍
网上有很多根据这一方法编写的程序,可以用来处理IMU数据从而得到随机误差参数,例如香港科技大学研究人员提供的工具imu_utils:按照README介绍的流程,即可得到输出的acc_n acc_w gyr_n gyr_w等;再例如open_vins团队提供的kalibr_allan,也能够得到以上参数。
根据IMU-Noise-Model和讨论中的内容,参数表和Allan标准差分析法得出的都是连续噪声模型的误差参数,在具体应用时,需要使用离散化噪声模型的误差参数,也就是根据所使用IMU的输出频率进行修正。如以上两个链接所示。
IMU随机误差参数的具体应用场景例如:
但就如IMU-Noise-Model最后所说,噪声模型推导出的随机误差参数都是在传感器静止和恒定温度下得出的,在IMU运动过程中,随机误差会更大,因此具体使用这些随机误差参数时,建议将参数扩大10倍以上使用
具体到AirSim中,IMU的噪声是怎么设定的呢?
目前来讲,AirSim中的IMU噪声是在代码中写定的,尚不支持用户自己配置。IMU噪声设置的代码在AirSim/AirLib/include/sensors/imu/文件夹下:
ImuSimpleParams文件中设置了噪声参数值(参考的数据来源在源文件注释中有提到):
struct Gyroscope {
//angule random walk (ARW)
real_T arw = 0.30f / sqrt(3600.0f) * M_PIf / 180; //deg/sqrt(hour) converted to rad/sqrt(sec) 这项是gyr_n
//Bias Stability (tau = 500s)
real_T tau = 500;
real_T bias_stability = 4.6f / 3600 * M_PIf / 180; //deg/hr converted to rad/sec //这项是gyr_w
Vector3r turn_on_bias = Vector3r::Zero(); //assume calibration is done
} gyro;
struct Accelerometer {
//velocity random walk (ARW)
real_T vrw = 0.24f * EarthUtils::Gravity / 1.0E3f; //mg converted to m/s^2 //这项是acc_n
//Bias Stability (tau = 800s)
real_T tau = 800;
real_T bias_stability = 36.0f * 1E-6f * 9.80665f; //ug converted to m/s^2 //这项是acc_w
Vector3r turn_on_bias = Vector3r::Zero(); //assume calibration is done
} accel;
但是请注意,以上的acc_w和gyr_w的数值不是发布的传感器仿真信号的最终噪声参数值,因为我们还需要参考IMU传感器实现的另一个头文件:
ImuSimple中的23\24行写到:
gyro_bias_stability_norm = params_.gyro.bias_stability / sqrt(params_.gyro.tau);
accel_bias_stability_norm = params_.accel.bias_stability / sqrt(params_.accel.tau);
也就是说gyro.bias_stability和accel.bias_stability在传递给噪声信号生成函数
void addNoise(Vector3r& linear_acceleration, Vector3r& angular_velocity)
之前还要除以常数 τ \tau τ的平方根。
所以最终,AirSim中的IMU传感器的噪声参数为:
gyro.arw is the gyroscope_noise_density, and is equal to 8.7266462e-5
gyro_bias_stability_norm is the gyroscope_random_walk, and is equal to 9.9735023e-7
accel.vrw is the accelerometer_noise_density, and is equal to 0.002353596
accel_bias_stability_norm is the accelerometer_noise_density, and is equal to 1.2481827e-5
在github上,有博主使用kalibr_allan工具对这组参数进行了验证:comment
以上AirSim中的IMU噪声参数,都是连续时间噪声模型的参数,我们需要根据实际需要,来决定是否将这些参数进行离散化后再送给视觉slam算法。
以下用open_vins和vins_mono举例。
open_vins需要的是连续噪声模型的参数
因为在ov_msckf的imu积分代码中,噪声会经过乘以或除以dt来进行离散化后才会作用在协方差矩阵的prediction上:
// Construct our discrete noise covariance matrix
// Note that we need to convert our continuous time noises to discrete
// Equations (129) amd (130) of Trawny tech report
Eigen::Matrix<double,12,12> Qc = Eigen::Matrix<double,12,12>::Zero();
Qc.block(0,0,3,3) = _noises.sigma_w_2/dt*Eigen::Matrix<double,3,3>::Identity();
Qc.block(3,3,3,3) = _noises.sigma_a_2/dt*Eigen::Matrix<double,3,3>::Identity();
Qc.block(6,6,3,3) = _noises.sigma_wb_2*dt*Eigen::Matrix<double,3,3>::Identity();
Qc.block(9,9,3,3) = _noises.sigma_ab_2*dt*Eigen::Matrix<double,3,3>::Identity();
// Compute the noise injected into the state over the interval
Qd = G*Qc*G.transpose();
Qd = 0.5*(Qd+Qd.transpose());
其中sigma_w_2/sigma_a_2/sigma_wb_2/sigma_ab_2都是配置文件输入的IMU相应参数的平方值: from ros
vins_mono需要的是离散噪声模型的参数。
这是因为在代码中:
构建噪声矩阵:
noise = Eigen::Matrix::Zero();
noise.block<3, 3>(0, 0) = (ACC_N * ACC_N) * Eigen::Matrix3d::Identity();
noise.block<3, 3>(3, 3) = (GYR_N * GYR_N) * Eigen::Matrix3d::Identity();
noise.block<3, 3>(6, 6) = (ACC_N * ACC_N) * Eigen::Matrix3d::Identity();
noise.block<3, 3>(9, 9) = (GYR_N * GYR_N) * Eigen::Matrix3d::Identity();
noise.block<3, 3>(12, 12) = (ACC_W * ACC_W) * Eigen::Matrix3d::Identity();
noise.block<3, 3>(15, 15) = (GYR_W * GYR_W) * Eigen::Matrix3d::Identity();
把噪声作用在协方差矩阵的prediction上:
covariance = F * covariance * F.transpose() + V * noise * V.transpose();
这其中ACC_N/GYR_N/ACC_W/GYR_W都是从配置文件读入的IMU参数值: read settings
我们可以看到在vins_mono中,噪声参数并没有用 dt 进行离散化,所以说明,在写vins_mono的配置文件时,需要我们自己提前对IMU的噪声参数离散化。