The state definition and general propagation equations are covered in the IMU Propagation Derivations page. Here we will cover the continuous-time integration of the state dynamics and inclusion of IMU intrinsic parameters. First we will cover how we can propagate our mean forward, afterwhich we cover how to derive the linearized error-state system propagation and approximations used. Key references for analytical inertial integration include:
First we can re-write our IMU measurement models to find the the true (or corrected) angular velocity and linear acceleration
. This is how we will relate incoming measurements to IMU dynamics (see IMU Kinematic Equations).
where and
. Note that here we have factored out the
gravity term (see below state evolution equations). In practice, we calibrate
,
,
(or
) and
to prevent unneeded matrix inversions and transposes in the measurement equation. We only calibrate either
or
since the base "inertial" frame must coincide with one frame arbitrarily. If both
and
are calibrated, it will make the rotation between the IMU and camera unobservable due to over parameterization [Yang2020RSS] [Yang2023TRO]. We define two different models of interested:
It is important to note that one should use the KALIBR model if there is a non-negligible transformation between the gyroscope and accelerometer (it is negligible for most MEMS IMUs, see [Li2014ICRA] [Schneider2019Sensor]) since it assumes the accelerometer frame to be the inertial frame and rigid bodies share the same angular velocity at all points. We can define the following matrices:
In the following derivations, we will compute the Jacobians for all the variables that might appear in the IMU models, including scale/axis correction for gyroscope (6 parameters), scale/axis correction for accelerometer
(6 parameters), rotation from gyroscope to IMU frame
, rotation from accelerometer to IMU frame
and gravity sensitivity
(9 parameters). The state vector contains the IMU state and its intrinsics:
where denotes the rotation matrix
from
to
.
and
denote the IMU position and velocity in
.
denotes the IMU navigation states and
denotes the IMU biases. The IMU intrinsics,
, contain the non-zero elements stored column-wise:
First we redefine the continuous-time integration equations mentioned in the Continuous-time Inertial Integration section. They are summarized as follows:
where ,
,
is the
matrix exponential [Chirikjian2011], and vectors are evaluated at their subscript timesteps (e.g.
). We have the following integration components:
where we define the following integrations:
where and the
and
integration components can be evaluated either analytically (see Integration Component Definitions) or numerically using RK4.
and
are defined as (dropping the timestamp):
Under the assumption of constant and
, the above equations are also constant over the time interval. The mean propagation for the new state at
can be written after taking the expectation:
We first remind the reader of the error states used throughout the system. It is crucial that all error states are consistent between propagation and update. OpenVINS has a type system (see ov_type and Type System) for which Jacobians need to be derived from. We have the following pose (orientation + position) errors (based on ov_type::PoseJPL)
For all other vectors (such as IMU intrinsics etc), we leverage simple additive error (based on ov_type::Vec)
We first define the and
error states. For
and
, we have:
For and
, we have:
where we need to define ,
and
. For the KALIBR model, we have:
For the RPNG model, we have:
By summarizing the above equations, we have:
where we have defined:
We then linearize ,
and
. For the
, we can get:
For the integration of , we get:
For the integration of , we get:
where and
are shown in the Integration Component Definitions section.
is the right Jacobian of
[see ov_core::Jr_so3() [Barfoot2017]]. In summary, we have the following linearized integration components (see Integration Component Definitions):
where and
and
are defined as:
Hence, the linearized IMU system is:
The overall linearized error state system is:
where and
are the state transition matrix and noise Jacobians for IMU dynamic model;
are Jacobians related to bias, IMU intrinsics and noises, which can be found from previous derivations;
is the discrete-time IMU noises;
and
can be computed as:
@m_class{m-note m-frame}
Note that and hence the covariance for
can be written as:
Finally, the covariance propagation can be derived as:
When deriving the components, we drop the subscripts for simplicity. As we define angular velocity , rotation axis
, and the small interval we are integrating over as
. The first integration we need is:
The second integration we need is:
The third integration can be written as:
The fourth integration we need is:
When is too small, in order to avoid numerical instability, we can compute the above integration identities as (see L'Hôpital's rule):
We currently do not implement a RK4 version of the above integrations. This would likely improve performance if leveraged as it would allow for the measurement to evolve over the integration period.