Skip to main content
Version: 12.0

IMU Models

Below are all supported IMU intrinsics models in MetriCal. If there is a model that you use that is not listed here, just contact us! We're always looking to expand our support.

Common Variables and Definitions

VariablesDescription
ωi\omega^iCorrected (Calibrated) angular velocity.
fif^iCorrected (Calibrated) specific force.
ω^g\hat{\omega}^gDistorted (Uncalibrated) gyroscope measurement.
f^a\hat{f}^aDistorted (Uncalibrated) accelerometer measurement. Also referred to as the specific force measurement.

Specific Force is the mass-specific force experienced by the proof mass in an accelerometer. This is commonly known as the accelerometer measurement. It differs from acceleration in that it has an additive term due to gravity operating on the proof mass in the accelerometer. To convert between acceleration of the accelerometer and specific-force, one can apply the equation

fi=ai+gi\begin{align} f^i = a^i + g^i \end{align}

where gig^i is the gravity vector expressed in the IMU's frame.

Modeling (Calibrated → Uncalibrated) refers to transforming an ideal angular velocity, or specific force and modeling the uncalibrated measurement produced by an IMU sensor given the intrinsics provided. In other words, it models the effect of the intrinsics on the angular velocity or specific force experienced by the IMU.

Correcting (Uncalibrated → Calibrated) refers to transforming an uncalibrated gyroscope or accelerometer measurement produced by an IMU sensor and correcting for intrinsics effects using the intrinsics provided. In other words, it corrects the measurement produced by an IMU approximating the true angular velocity or specific force experienced by the IMU.

Correcting Models

All the IMU intrinsic models used in MetriCal are correcting models in that they naturally express the corrected quantities in terms of the measured quantities. However, these models may also be used to model the IMU intrinsics. This simply requires inverting the model by solving for the measured quantities in terms of the corrected quantities. The modeling equations for each of the intrinsic models are given below.

IMU Frames

A coordinate frame is simply the position and directions defining the basis which can be used to numerically express a quantity. The coordinate frames used for IMU models are given in the following table.

FrameDescription
aaThe accelerometer coordinate frame
ggThe gyroscope coordinate frame
iiThe imu coordinate frame

In the currently supported IMU models in MetriCal, the aa, gg, and ii coordinate frames are assumed to be at the same position in space. Furthermore, the aa and gg frames are not assumed to be orthonormal. The ii frame, however, will always be a proper orthonormal coordinate frame.

Numerical quantities use a superscript to describe their frame of reference. As such, the above frame variables should only be interpreted as a frame if they appear as a superscript. For example, the gravity vector in the IMU's frame is given as gig^i, but gg should not be interpreted as a frame in this context.

IMU Bias

Recommended Reading

Woodman, O. (2007). An introduction to inertial navigation. Read here.

Farrell, J. Silva, F. Rahman, F. Wendel, J. (2022). IMU Error Modeling Tutorial. IEEE Control Systems Magazine, Vol 42, No 6, pp. 40-66. Read here.

IMUs have a time-varying bias on the measurements they produce. In MetriCal, this is modeled as an additive bias on top of the intrinsically distorted measurements.

ParameterMathematical NotationDescription
gyro_biasbfab_f^aAdditive bias on the accelerometer measurement.
specific_force_biasbggb_g^gAdditive bias on the gyroscope measurement.

By necessity, MetriCal infers the additive biases on both the accelerometer and the gyroscope measurements. However, the IMU bias is a time-varying quantity that is highly influenced by electrical noise, temperature fluctuations and other factors. These biases can change simply by power cycling the IMU sensor. As such, it is recommended that the IMU biases inferred by MetriCal are only used as an initial estimate of bias in applications.

Intrinsics Models

No Intrinsics

MetriCal keyword: no_intrinsics

This model simply accounts for the bias effects. This model is applicable when you're confident in the intrinsics that your IMU is providing, and you only need to infer spatial constraints related to your IMU.

Correction

ωi=ω^gbggfi=f^abfa\begin{align} \omega^i &= \hat{\omega}^g - b_g^g \\ f^i &= \hat{f}^a - b_f^a \end{align}

Modeling

ω^g=ωi+bggf^a=fi+bfa\begin{align} \hat{\omega}^g &= \omega^i + b_g^g \\ \hat{f}^a &= f^i + b_f^a \end{align}

Scale Model

MetriCal keyword: scale

This model corrects any scale factor errors in the accelerometer and gyroscope measurements.

ParameterMathematical NotationDescription
gyro_scale[sgx,sgy,sgz][s_{gx}, s_{gy}, s_{gz}]Scaling applied to each component of the gyroscope measurement
specific_force_scale[sfx,sfy,sfz][s_{fx}, s_{fy}, s_{fz}]Scaling applied to each component of the accelerometer measurement

Where the intrinsic correction matrices are formed from the other variables as

Dg=[sgx000sgy000sgz]Df=[sfx000sfy000sfz]\begin{aligned} D_g &= \begin{bmatrix} s_{gx} & 0 & 0 \\ 0 & s_{gy} & 0 \\ 0 & 0 & s_{gz} \\ \end{bmatrix} \\ D_f &= \begin{bmatrix} s_{fx} & 0 & 0 \\ 0 & s_{fy} & 0 \\ 0 & 0 & s_{fz} \\ \end{bmatrix} \end{aligned}

Correction

ωi=Dg(ω^gbgg)fi=Df(f^abfa)\begin{aligned} \omega^i &= D_g(\hat{\omega}^g - b_g^g) \\ f^i &= D_f(\hat{f}^a - b_f^a) \end{aligned}

Modeling

ω^g=Dg1ωi+bggf^a=Df1fi+bfa\begin{aligned} \hat{\omega}^g &= D_g^{-1}\omega^i + b_g^g \\ \hat{f}^a &= D_f^{-1}f^i + b_f^a \end{aligned}

Scale and Shear Model

MetriCal keyword: scale_shear

This model corrects any scale factor errors and non-orthogonality errors in the accelerometer or gyroscope measurements. These non-orthogonality errors are often called "shear" errors which gives the scale and shear model its name.

ParameterMathematical NotationDescription
gyro_scale[sgx,sgy,sgz][s_{gx}, s_{gy}, s_{gz}]Scaling applied to each component of the gyroscope measurement
specific_force_scale[sfx,sfy,sfz][s_{fx}, s_{fy}, s_{fz}]Scaling applied to each component of the accelerometer measurement
gyro_shear[σgxy,σgxz,σgyz][\sigma_{gxy}, \sigma_{gxz}, \sigma_{gyz}]Non-orthogonality compensation applied to the gyroscope measurement
accelerometer_shear[σfxy,σfxz,σfyz][\sigma_{fxy}, \sigma_{fxz}, \sigma_{fyz}]Non-orthogonality compensation applied to the accelerometer measurement

Where the intrinsic correction matrices are formed from the other variables as

Dg=[sgxσgxyσgxz0sgyσgyz00sgz]Df=[sfxσfxyσfxz0sfyσfyz00sfz]\begin{aligned} D_g &= \begin{bmatrix} s_{gx} & \sigma_{gxy} & \sigma_{gxz} \\ 0 & s_{gy} & \sigma_{gyz} \\ 0 & 0 & s_{gz} \\ \end{bmatrix} \\ D_f &= \begin{bmatrix} s_{fx} & \sigma_{fxy} & \sigma_{fxz} \\ 0 & s_{fy} & \sigma_{fyz} \\ 0 & 0 & s_{fz} \\ \end{bmatrix} \end{aligned}

Correction

ωi=Dg(ω^gbgg)fi=Df(f^abfa)\begin{aligned} \omega^i &= D_g(\hat{\omega}^g - b_g^g) \\ f^i &= D_f(\hat{f}^a - b_f^a) \end{aligned}

Modeling

ω^g=Dg1ωi+bggf^a=Df1fi+bfa\begin{aligned} \hat{\omega}^g &= D_g^{-1}\omega^i + b_g^g \\ \hat{f}^a &= D_f^{-1}f^i + b_f^a \end{aligned}

Scale, Shear, and Rotation Model

MetriCal keyword: scale_shear_rotation

This model corrects any scale factor errors and non-orthogonality errors in the accelerometer or gyroscope measurements. Additionally, this model corrects for any rotational misalignment between the gyroscope and the IMU's frame. In this model, the IMU frame is assumed to be the same as the scale and shear corrected accelerometer frame.

ParameterMathematical NotationDescription
gyro_scale[sgx,sgy,sgz][s_{gx}, s_{gy}, s_{gz}]Scaling applied to each component of the gyroscope measurement
specific_force_scale[sfx,sfy,sfz][s_{fx}, s_{fy}, s_{fz}]Scaling applied to each component of the accelerometer measurement
gyro_shear[σgxy,σgxz,σgyz][\sigma_{gxy}, \sigma_{gxz}, \sigma_{gyz}]Non-orthogonality compensation applied to the gyroscope measurement
accelerometer_shear[σfxy,σfxz,σfyz][\sigma_{fxy}, \sigma_{fxz}, \sigma_{fyz}]Non-orthogonality compensation applied to the accelerometer measurement
accel_from_gyro_rotRgiR^i_gThe rotation from the gyroscope frame to the IMU's frame

The intrinsic correction matrices are formed with the two equations

Dg=[sgxσgxyσgxz0sgyσgyz00sgz]Df=[sfxσfxyσfxz0sfyσfyz00sfz]\begin{aligned} D_g &= \begin{bmatrix} s_{gx} & \sigma_{gxy} & \sigma_{gxz} \\ 0 & s_{gy} & \sigma_{gyz} \\ 0 & 0 & s_{gz} \\ \end{bmatrix} \\ D_f &= \begin{bmatrix} s_{fx} & \sigma_{fxy} & \sigma_{fxz} \\ 0 & s_{fy} & \sigma_{fyz} \\ 0 & 0 & s_{fz} \\ \end{bmatrix} \end{aligned}

Correction

ωi=RgiDg(ω^gbgg)fi=Df(f^abfa)\begin{aligned} \omega^i &= R^i_gD_g(\hat{\omega}^g - b_g^g) \\ f^i &= D_f(\hat{f}^a - b_f^a) \end{aligned}

Modeling

ω^g=Dg1Rigωi+bggf^a=Df1fi+bfa\begin{aligned} \hat{\omega}^g &= D_g^{-1}R^g_i\omega^i + b_g^g \\ \hat{f}^a &= D_f^{-1}f^i + b_f^a \end{aligned}

Scale, Shear, Rotation, and G-sensitivity Model

MetriCal keyword: scale_shear_rotation_g_sensitivity

This model corrects any scale factor errors, non-orthogonality errors and rotational misalignment errors in the accelerometer or gyroscope measurements. Additionally, this model corrects for a phenomenon known as G-sensitivity. G-sensitivty is a property of an oscillating gyroscope that causes a gyroscope to register a bias on its measurements when the gyroscope experiences a specific-force.

ParameterMathematical NotationDescription
gyro_scale[sgx,sgy,sgz][s_{gx}, s_{gy}, s_{gz}]Scaling applied to each component of the gyroscope measurement
specific_force_scale[sfx,sfy,sfz][s_{fx}, s_{fy}, s_{fz}]Scaling applied to each component of the accelerometer measurement
gyro_shear[σgxy,σgxz,σgyz][\sigma_{gxy}, \sigma_{gxz}, \sigma_{gyz}]Non-orthogonality compensation applied to the gyroscope measurement
accelerometer_shear[σfxy,σfxz,σfyz][\sigma_{fxy}, \sigma_{fxz}, \sigma_{fyz}]Non-orthogonality compensation applied to the accelerometer measurement
accel_from_gyro_rotRgiR^i_gThe rotation from the gyroscope frame to the IMU's frame
g_sensitivity[γx,γy,γz][\gamma_x, \gamma_y, \gamma_z]The in-axis G-sensitivity of the gyroscope induced by the specific-force
g_sensitivity_cross_axis[γxy,γxz,γyz][\gamma_{xy}, \gamma_{xz}, \gamma_{yz}]The cross-axis G-sensitivity of the gyroscope induced by the specific-force

The intrinsic correction matrices are formed with the two equations

Dg=[sgxσgxyσgxz0sgyσgyz00sgz]Df=[sfxσfxyσfxz0sfyσfyz00sfz]\begin{aligned} D_g &= \begin{bmatrix} s_{gx} & \sigma_{gxy} & \sigma_{gxz} \\ 0 & s_{gy} & \sigma_{gyz} \\ 0 & 0 & s_{gz} \\ \end{bmatrix} \\ D_f &= \begin{bmatrix} s_{fx} & \sigma_{fxy} & \sigma_{fxz} \\ 0 & s_{fy} & \sigma_{fyz} \\ 0 & 0 & s_{fz} \\ \end{bmatrix} \end{aligned}

and the G-sensitivity matrix is given by

T=[γxγxyγxz0γyγyz00γz]\begin{aligned} T &= \begin{bmatrix} \gamma_{x} & \gamma_{xy} & \gamma_{xz} \\ 0 & \gamma_{y} & \gamma_{yz} \\ 0 & 0 & \gamma_{z} \\ \end{bmatrix} \end{aligned}

Correction

ωi=RgiDg(ω^gTfibgg)fi=Df(f^abfa)\begin{aligned} \omega^i &= R^i_gD_g(\hat{\omega}^g - Tf^i - b_g^g) \\ f^i &= D_f(\hat{f}^a - b_f^a) \end{aligned}
Correction Order

By adding G-sensivity, the gyroscope correction becomes dependent upon the specific-force correction. As such, it is necessary to first correct the accelerometer measurement and then use the corrected specific-force to correct the gyroscope measurement.

Modeling

ω^g=Dg1Rigωi+Tfi+bggf^a=Df1fi+bfa\begin{aligned} \hat{\omega}^g &= D_g^{-1}R^g_i\omega^i + Tf^i + b_g^g \\ \hat{f}^a &= D_f^{-1}f^i + b_f^a \end{aligned}

Noise Model

Noise Specification

A full understanding of the IMU noise model is not necessary to use MetriCal. MetriCal chooses default values for the noise model that should work with most MEMS consumer grade IMUs. However, the interested reader is referred to the IEEE Specification Appendix C, where these values are more rigorously defined.

In addition to bias and intrinsics, IMUs experience noise on their measurement outputs. This noise must be modeled to properly infer the bias and intrinsic parameters of an IMU. At a high-level, the noise model is given as

x(t)=y(t)+n(t)+b(t)+k(t)x(t) = y(t) + n(t) + b(t) + k(t)

where

  • x(t)x(t) is the noisy time-varying signal
  • y(t)y(t) is the true time-varying signal
  • n(t)n(t) is the component of the noise with constant power spectral density (white noise)
  • b(t)b(t) is the component of the noise with 1/f1/f power spectral density (pink noise)
  • k(t)k(t) is the component of the noise with 1/f21/f^2 power spectral density (brown noise)

This noise model is applied to each component of the gyroscope and accelerometer output. More details on this noise model can be found in the IEEE Specification.

Noise Parameters

The noise parameters for the IMU noise model are given as

ParameterUnitsDescription
angular_random_walkrad/s\text{rad}/\sqrt{s}Angular random walk coefficients
gyro_bias_instabilityrad/s\text{rad}/sGyroscope bias instability coefficients
gyro_rate_random_walkrad/s(3/2)\text{rad} / s^{(3/2)}Gyroscope rate random walk coefficients
gyro_correlation_time_constantunitlessGyroscope correlation time constant for bias instability process
gyro_turn_on_bias_uncertaintyrad/s\text{rad}/sPrior standard deviation of the gyroscope bias components
velocity_random_walkm/s(3/2)m/s^{(3/2)}Velocity random walk coefficients
accelerometer_bias_instabilitym/s2m/s^2Accelerometer bias instability coefficients
accelerometer_rate_random_walkm/s(5/2)m/s^{(5/2)}Accelerometer rate random walk coefficients
accelerometer_correlation_time_constantunitlessAccelerometer correlation time constant for bias instability process
accelerometer_turn_on_bias_uncertaintyrad/s\text{rad}/sPrior standard deviation of the specific force bias components

MetriCal will automatically set these with reasonable values for consumer grade IMUs (like the BMI055 used in Intel's Realsense D435i). However, if you have better values from an IMU datasheet or an Allan Variance analysis, you can modify the defaults to better suit your needs. If you are using values given in a datasheet, be sure to convert to the units used by MetriCal, since many datasheets will give units like mg/smg / \sqrt{s} (milli-g's) or (/hour)/Hz(^{\circ}/\text{hour}) / \sqrt{Hz}