John Stechschulte

Reading IMU specs for fun and profit

Every time I have to make sense of an IMU spec sheet, I feel like I have to re-learn the whole IMU noise model, which manufacturer specs correspond to which model parameters, and how to convert between different units. There are many good references to understand the “what” and “why” of the IMU noise model, which I’ve linked below, but I intend this to be a how-to cheatsheet, to serve as a pragmatic guide to get the right answers.

But wait, all these square roots

However, one bit of theory is so crucial that it’s worth spending a few sentences on it: the standard deviation of the position of a random walk increases with the square root of the number of steps. There are a lot of random walks happening in an IMU (or, at least, in the model we’re using here), so this comes up a lot. A random walk is defined as the sum of several independent, identically distributed steps.

\[w = \sum_{t=0}^T s_t\] \[s_i \sim N(0, \sigma_s)\]

The distribution of the walk after \(T\) steps is

\[w \sim N(0, \sqrt{T}\sigma_s).\]

(The steps don’t have to be normally distributed, but that’s another can of worms.) Why the square root? The variance of the sum of independent random variables is the sum of their variances, so the variance scales linearly with the number of steps, and standard deviation scales with the square root.

IMU noise parameter units

Back to IMUs. The noise model for both the accelerometer and gyroscope has two components: white noise, and bias. The white noise is a zero-mean random independent variable added to each measurement, and the bias is modeled as a random walk. Each noise element is parameterized by a standard deviation.

From this description you might think the two parameters would have the same units as their respective sensor: \(\frac{\text{m}}{\text{s}^2}\) for the accelerometer and \(\frac{\text{rad}}{\text{s}}\) for the gyroscope. This is true when the model is actually executed per sample, but if the IMU has an adjustable sampling rate (and I’ve never heard of one that doesn’t), the white noise on each measurement is larger at higher sampling rates, and the bias will drift less between measurements. The white noise standard deviation per sample scales linearly with the square root of the sampling frequency because each IMU reading is itself a random walk, as it is the integration of an underlying continuous signal. The bias standard deviation per sample scales linearly with the square root of the time between samples, which is of course the inverse sampling frequency. The result of all this is that the white noise parameter needs to be multiplied by the square root of the sampling frequency to get sensor units, and the bias parameter needs to be divided by the square root of the sampling frequency to get sensor units:

Accelerometer white noise \(\frac{\text{m}}{\text{s}^2} \frac{1}{\sqrt{\text{Hz}}}\)
Accelerometer bias \(\frac{\text{m}}{\text{s}^2} \sqrt{\text{Hz}}\)
Gyroscope white noise \(\frac{\text{rad}}{\text{s}} \frac{1}{\sqrt{\text{Hz}}}\)
Gyroscope bias \(\frac{\text{rad}}{\text{s}} \sqrt{\text{Hz}}\)

Sometimes the bias parameters are written with the \(\sqrt{\text{Hz}}\) in the denominator, which works out if you put an extra \(\text{s}\) in the denominator also, because \(\sqrt{\text{Hz}} = \frac{1}{\text{s}\sqrt{\text{Hz}}}\). I like the formulation above because it captures the opposite effect that sampling frequency has on the two types of noise.

Reading a spec sheet

This noise model and the corresponding units are used frequently in robotics software. Unfortunately, you shouldn’t expect to be able to read them straight off a spec sheet. Usually the white noise parameters need to be converted, and often the bias parameters aren’t even on the sheet (mostly because this bias model isn’t actually right). So I’ve worked through an example, below, of identifying the necessary specs and converting them. This example is for an IMU spec sheet that I happened to be reading recently.

White noise

The white noise parameter can be derived from the “noise density.” The example sheet specifies the gyroscope noise density as \(4.68 \frac{\text{deg}}{\text{hr}} \frac{1}{\sqrt{\text{Hz}}}\). Converting seconds to hours and degrees to radians gives:

\[4.68 \frac{\text{deg}}{\text{hr}} \frac{1}{\sqrt{\text{Hz}}} = 4.68 \frac{\text{deg}}{\text{hr}} \frac{1}{\sqrt{\text{Hz}}} \times \frac{\pi \text{ rad}}{180 \text{ deg}} \times \frac{1 \text{ hr}}{3600 \text{ s}} = 2.2689 \times 10^{-5} \frac{\text{rad}}{\text{s}} \frac{1}{\sqrt{\text{Hz}}}\]

Similarly, the accelerometer noise density is \(60 \frac{\mu \text{G}}{\sqrt{\text{Hz}}}\). Again, we just convert units:

\[60 \frac{\mu \text{G}}{\sqrt{\text{Hz}}} = 60 \times 10^{-6} \times 9.8 \frac{\text{m}}{\text{s}^2} \frac{1}{\sqrt{\text{Hz}}} = 5.88 \times 10^{-4} \frac{\text{m}}{\text{s}^2} \frac{1}{\sqrt{\text{Hz}}}\]

Sometimes, however, there is no noise density specified. Look instead for the “angular random walk” or “linear velocity random walk”: after integrating, the linear acceleration white noise becomes a random walk on the linear velocity, and similiarly for the angular velocity and angle. Again, this just comes down to unit conversion:

\[0.06 \frac{\circ}{\sqrt{\text{hr}}} = 0.06 \frac{\circ}{\sqrt{\text{hr}}} \times \frac{\pi \text{ rad}}{180^\circ} \times \frac{\sqrt{\text{1 hr}}}{\sqrt{3600 \text{ sec}}} = 1.745 \times 10^{-5} \frac{\text{rad}}{\text{sec}} \frac{1}{\sqrt{\text{Hz}}}\] \[0.025 \frac{\text{m}}{\text{s}} \frac{1}{\sqrt{\text{hr}}} = 0.025 \frac{\text{m}}{\text{s}} \frac{1}{\sqrt{\text{hr}}} \times \frac{\sqrt{1 \text{ hr}}}{\sqrt{3600 \text{ sec}}} = 4.167 \times 10^{-4} \frac{\text{m}}{\text{s}^2} \frac{1}{\sqrt{\text{Hz}}}\]

But wait, the numbers don’t match! True, they don’t, but they’re the same order of magnitude. In fact, the Kalibr wiki page on the IMU noise model explains that these values are taken from ideal operating conditions, and to account for the extra variability that occurs in the real world, “increasing the noise model parameters by a factor of 10x or more may be necessary.”

Bias

Whereas the white noise can sometimes be found in two places on the spec sheet, the bias parameter is usually nowhere to be found. While some spec sheets provide an Allan variance plot, which has the information necessary to determine the bias standard deviation, sometimes your best hope is the “bias instability”, which is also called “bias stability” (I guess it depends on whether the spec sheet writer is a pessimist or an optimist). Without getting into the details, the bias stability is usually a decent upper bound on the bias standard deviation. The units will be missing the \(\sqrt{\text{Hz}}\), but you can just insert it.

So, for our working example:

\[0.8 \frac{\circ}{\text{hr}} = 0.8 \frac{\circ}{\text{hr}} \frac{\pi\text{ rad}}{180^\circ} \frac{3600\text{ s}}{1\text{ hr}} = 3.878 \times 10^{-6} \frac{\text{rad}}{\text{s}} \stackrel{\text{fudge}}{=} 3.878 \times 10^{-6} \frac{\text{rad}}{\text{s}} \sqrt{\text{Hz}}\] \[12 \mu \text{G} = 12 \times 9.8 \times 10^{-6} \frac{\text{m}}{\text{s}^2} = 1.117 \times 10^{-4} \frac{\text{m}}{\text{s}^2} \stackrel{\text{fudge}}{=} 1.117 \times 10^{-4} \frac{\text{m}}{\text{s}^2} \sqrt{\text{Hz}}\]

As with the white noise parameters, it’s likely these values are still too optimistic, so increasing them is a good idea.

IMU library

Below is a list of IMUs with links to spec sheets and the converted parameters. I’ll update this as I work with different IMUs.

Model Price Grade Gyro white noise Gyro bias Acc. white noise Acc. bias
Epson M-G370PDF1 ? Tactical 2.2689e-5 3.878e-6 5.88e-4 1.117e-4
OxTS RT3000 v3 ? Tactical 5.817e-5 9.696e-6 8.3333e-5 1.96e-5
MicroStrain 3DM-CX5-IMU $700 Industrial 8.727e-5 3.878e-5 1.96e-4 3.92e-4
Bosch BHI260AP $10 Consumer 1.221e-4 2.424e-5 8.315e-4 ?

Go forth and read spec sheets

An IMU spec sheet can seem confusing, but it’s not too hard to learn what you’re looking for. The white noise parameter will be a “noise density” or “random walk”, and the “bias (in)stability” can be used for the bias parameter. Make sure you convert the units to match the software’s expectations, and you’ll be good to go.

Further reading