An inertial navigation system (INS) uses data collected from an IMU to form a self-contained navigation system by integrating the IMU measurements to track the position, velocity, and orientation of an object relative to an initial position, velocity, and orientation. When combined with data from a GNSS receiver through advanced Kalman filtering, the INS relative navigation solution can be tied to an absolute inertial reference frame, with no drift or long-term error accumulation. But absent such aiding, the relative INS navigation solution is subject to drift over time.
A variety of error sources within the inertial sensors' measurements themselves lead to unbounded error growth in the INS navigation solution, such as bias, noise, scale factor errors, misalignments, temperature dependencies, and gyro g-sensitivity. These sources of error and how they are specified are discussed more in-depth in Section 3.1. This error budget provides the means to calculate how those inertial sensor errors propagate to errors in the INS attitude, position, and velocity solutions over time.
The attitude of a system is calculated by integrating angular rate (angular velocity) as measured by the gyros over a defined time period. For the purposes of this analysis we consider single-axis motion, as the non-linear coupling of attitude makes multi-axis analysis impossible in the general case. The equation for a measured angular rate for a single axis can be represented with error sources as follows:
\begin{equation} \tilde{\omega} = (1+k)\omega_t + b_g +\eta_g\end{equation}
where $\tilde{\omega}$ is the measured angular rate, $\omega_t$ is the true angular rate, $k$ is the scale factor error, $b_g$ is the time-varying bias, and $\eta_g$ is the random Gaussian noise (defined by the angle random walk (ARW) specification).
The error in the attitude calculation is found by integrating the difference between the measured angular rate and the true angular rate:
\begin{equation} \theta_{err} = \int_0^t(\tilde{\omega} - \omega_t)dt\end{equation}
Substituting the prior definition of $\tilde{\omega}$ and the relationship between noise integrals and ARW yields:
\begin{equation} \theta_{err} = (\mbox{ARW})\sqrt{t} + \int_0^t(k\omega_t + b_g)dt\end{equation}
We will first consider attitude errors under stationary---non-rotating and non-accelerating---conditions. If the bias can be considered constant over the time interval in question (depending on the time constant of the minimum on the Allan variance curve---see Section 3.1), then the angular error can be given by:
\begin{equation} \theta_{err} = b_gt+(\mbox{ARW})\sqrt{t}\end{equation}
For longer durations, where bias is a non-constant factor, the integral of the bias must be handled as a variable rather than a constant. Let the variable bias, which will drift over time, be equal to some initial bias error, $b_{g_0}$, plus a time-varying bias, $b'_g(t)$, such that:
\begin{equation} \int_0^t{b_{g}}dt=\int({b_{g_0}}+b'_g(t))dt=b_{g_0}t+\int_0^t{b'_g(t)}dt\end{equation}
Substitute this equation for non-constant bias into the original equation for attitude error and it results in the following:
\begin{equation} \theta_{err}=b_{g_0}t+(\mbox{ARW})\sqrt{t}+\int{b'_g(t)}dt\end{equation}
It is important to note that $b_{g_0}$ will always be greater than or equal to the in-run bias stability---hence the criticality of that specification. In dynamic GNSS/INS applications where the gyro bias is tracked utilizing imperfect GNSS measurements, $b_{g_0}$is typically five to ten times greater than the in-run bias stability.
Building on this stationary case, now consider a situation in which the system is rotating about a single axis. Under these dynamic conditions, $\omega_t$ is non-zero, and we will define the integral of the true angular velocity over time to be $\Delta\theta$. This yields an updated angular error of:
\begin{equation} \theta_{err}=k\Delta\theta+b_{g_0}t+(\mbox{ARW})\sqrt{t} + \int_0^tb'_g(t)dt\end{equation}
Note that the scale factor error $k$ produces an error proportional to the total angle traversed over the time period, so oscillatory motions see a negligible contribution from scale factor errors.
Along with the error sources included in the previous equations, there are a few additional errors that are present under general dynamic conditions, but are either typically negligible or only present under multi-axis motion. These include:
In order to determine the velocity and position error that arises from an INS, another series of integrations must be performed. There are certain challenges that arise when multiple integrations are performed including attitude dependence and accounting for the presence of gravity in the calculations.
For the case of velocity and position, we will consider a non-rotating case with single-axis accelerations. With an understanding of fundamental kinematics, given some acceleration vector, velocity can be found by integrating the acceleration solution over a finite period of time. Likewise, position is found by integrating the velocity solution over a finite period of time.
When dealing with linear acceleration in this manner, it is important to differentiate between acceleration in a horizontal direction and a vertical direction. Similar to the measurement equation used to find the angular rate of the gyro, the linear acceleration of the system can be modeled by this equation for both directions:
\begin{equation} \tilde{a}=(1+k)a_t+b_a+\eta_a+\begin{cases}g\sin\theta_{err}&\quad \mbox{horizontal}\\g(1-\cos\theta_{err})& \quad\mbox{vertical}\end{cases}\end{equation}
where $\tilde{a}$ is the measured linear acceleration, $k$ is the scale factor error, $a_t$ is the true linear acceleration, $b_a$ is the bias, $\eta_a$ is the Gaussian random noise defined by Velocity Random Walk (VRW), and $g$ is gravity. The gravity terms exist because the accelerometers measure both linear acceleration and gravity, and the pitch and roll estimates are required to subtract out the gravity signal---leading to an attitude dependence for the position and velocity integrals.
Assuming the attitude error is small over the integration time, a small angle approximation reduces those terms as follows:
\begin{equation} \begin{split} g\sin{\theta_{err}} &\approx g\theta_{err}\quad\mbox{(horizontal)} \\ g(1-\cos{\theta_{err}}) &\approx 0\quad\mbox{(vertical)} \end{split}\end{equation}
Following that simplification, the equation for angular error under static conditions found in the previous section can be substituted. For the purposes of this analysis, we assume the accelerometer bias is constant, though it is actually time varying like the gyro.
The velocity error is found by integrating the acceleration and adding that to an initial velocity error at the start of the integration:
\begin{equation}\label{eq:velerr} V_{err}=V_{err_0}+\int_0^t(\tilde{a}-a_t)dt\end{equation}
By employing substitutions similar to those used in the section on attitude integration, Equation \ref{eq:velerr} can be rewritten:
\begin{equation} V_{err}=V_{err_0}+\int_0^t(ka_t+b_a+\eta_a+g\theta_{err})dt\end{equation}
\begin{equation} V_{err}=V_{err_0}+\int_0^t\left[ka_t+b_a+\eta_a+g(b_gt+(\mbox{ARW})\sqrt{t})\right]dt\end{equation}
\begin{equation}\label{eq:velerrfinal} V_{err}=V_{err_0}+k\Delta V+b_at+(\mbox{VRW})\sqrt{t}+g\left[\frac{1}{2}b_gt^2+\frac{2}{3}(\mbox{ARW})t^{\frac{3}{2}}\right]\end{equation}
The final term (multiplied by $g$) can be excluded when considering errors in the vertical channel. As with the attitude integration, scale factor errors only act on the change in velocity over the time period of interest and are negligible for oscillatory accelerations.
Finding position error requires integrating Equation \ref{eq:velerrfinal} and adding it to an initial position error:
\begin{equation} P_{err}=P_{err_0}+\int_0^t V_{err}dt\end{equation}
\begin{equation} P_{err}=P_{err_0}+\int_0^t \left[V_{err_0}+k\Delta V+b_at+(\mbox{VRW})\sqrt{t}+g\left(\frac{1}{2}b_gt^2+ \frac{2}{3}(\mbox{ARW})t^{\frac{3}{2}}\right)\right]dt\end{equation}
\begin{equation} P_{err}=P_{err_0}+k\Delta P+V_{err_0}t+\frac{1}{2}b_at^2+\frac{2}{3}(\mbox{VRW})t^{\frac{3}{2}}+g\left[\frac{1}{6}b_gt^3+\frac{4}{15}(\mbox{ARW})t^{\frac{5}{2}}\right]\end{equation}
Finally, a solution for position error has been found that factors all significant sources of error found in inertial navigation. As a reminder, this solution takes into account a linear acceleration in the purely horizontal axis. Removing the last component in the equation would result in a solution based on vertical linear acceleration.
This position integration result shows why most INS systems are assessed initially on their gyro performance, particularly the in-run bias stability: the positioning errors proportional to the gyro bias grow as a function of time cubed!
Table 3.1 presents position errors over multiple time periods in a purely static condition, as calculated from the last equations derived above, to demonstrate how important and effective error budgeting is for an INS system to determine the best possible navigation solution. We have used representative values for each grade of inertial sensor as seen in Table 3.2 (these numbers do not reflect any particular sensor on the market), and assumed initial position and velocity errors are zero. Care must be taken during these calculations to ensure all parameters are in SI units.
Note that these calculations assume the gyro biases are known to the accuracy of the in-run bias stability (which is unrealistic in a dynamic scenario), and the errors contributed by the random walk terms represent 1-sigma standard deviations, and could therefore be ˜3x higher. The other assumptions made (static, no initial velocity errors) also act to make these numbers lower than would be encountered in a real-world application. And once you reach the high-end performance of navigation-grade inertial sensors, additional error sources not discussed here become relevant.
GRADE/TIME | 1 s | 10 s | 60 s | 10 min | 1 hr |
---|---|---|---|---|---|
Consumer | 6 cm | 6.5 m | 400 m | 200 km | 39,000 km |
Industrial | 6 mm | 0.7 m | 40 m | 20 km | 3,900 km |
Tactical | 1 mm | 8 cm | 5 m | 2 km | 400 km |
Navigation | <1 mm | 1 mm | 50 cm | 100 m | 10 km |
GRADE | ACCELEROMETER BIAS (mg) | VELOCITY RANDOM WALK (m/s/$\sqrt{\mbox{hr}}$) | GYRO BIAS (deg/hr) | ANGLE RANDOM WALK (deg/$\sqrt{\mbox{hr}}$) |
---|---|---|---|---|
Consumer | 10 | 1 | 100 | 2 |
Industrial | 1 | 0.1 | 10 | 0.2 |
Tactical | 0.1 | 0.03 | 1 | 0.05 |
Navigation | 0.01 | 0.01 | 0.01 | 0.01 |