Hi everyone,
Note: The original post was edited to make clear the “additive” form of the Unscented Kalman Filter is considered here.
This post is about the “additive” form of the Unscented Kalman Filter, where the process noise is Gaussian and provided as a covariance matrix, see Table 7.3 in Wan and Merwe [1].
(For completeness, the “augmented” (non-additive) form, which is not discussed here, can be found in Table 7.2 in Wan and Merwe [1].)
I was looking at the Hipparchus implementation of the Unscented Kalman Filter and came across a potential limitation in how the innovation is computed.
The notation here is based on Table 7.3 in Wan and Merwe [1], where the “additive” form of the UKF is formulated. Below, I abbreviate the sampling of sigma points as
What is currently done in the method UnscentedKalmanFilter::estimationStep
is the following:
In order to incorporate the process noise, the non-Gaussian predicted sigma points \bm{\mathcal X}_{k|k-1}^* are used to compute the predicted mean and covariance \bm x_{k|k-1}, \bm P_{k|k-1}^* (after which the sigma points are discarded). Then the process noise \bm Q_{k|k-1} is added and new sigma points \bm{\mathcal X}_{k|k-1} are sampled from the mean and (process noise including) covariance.
This approach is valid, however, it “discards any odd-moments information captured by the original propagated sigma points.” [1, p.233, footnote 6]. This means that odd-moments information is lost for computing the innovation and its covariance. Hence we lose part of the benefit of using an unscented transform.
To maintain the odd-moments information, rather than discarding the original sigma points they can be kept and additional sigma points can be added to reflect the addition of process noise, as shown in [1, Eq. (7.56)]:
where \bm{\mathcal X}_{k|k-1}^* are the original predicted sigma points, \bm{\mathcal X}_{0, k|k-1}^* is the first (central) sigma point and \bm Q_{k|k-1} is the process noise.
Note that we now have 4L + 1 sigma points instead of 2L+1 (L is the dimension of x). These are used compute the innovation, and innovation and cross covariance.
I have not tried out this addition of sigma point myself, but I’d think that preserving the information in the originally predicted sigma points to compute the innovation has a beneficial effect on the performance of the UKF, specifically in case of long gaps between measurements.
I would love to hear your thoughts on this.
Best,
David
…
Reference:
[1] Wan, E., & van der Merwe, R. (2001). 7 the Unscented Kalman Filter. https://api.semanticscholar.org/CorpusID:14862265
Notation:
-
\bm x: State vector
-
\bm y: Measurement vector
-
\bm{\mathcal{X}}: State sigma-points
-
\bm{\mathcal{Y}}: Measurement sigma-points
-
\bm{P}: State covariance
-
\bm Q_{k|k-1}: Process noise between t_{k-1} and t_k
-
\sqrt{\bm A} : the lower-triangular Cholesky factorisation of matrix \bm A
-
\bm F : function to propagate sigma points and process noise (
UnscentedProcess::getEvolution(...)
) -
\bm H: function to map sigma points from state space to measurement space (
UnscentedProcess::getPredictedMeasurements(...)
) -
\gamma: Unscented Transform multiplication factor (
AbstractUnscentedTransform::getMultiplicationFactor
) -
(\cdot)_k: Corrected at t_k
-
(\cdot)_{k|k-1}: Predicted at time t_k based on state estimate from t_{k-1}
-
(\cdot)^*: Before considering process noise