rlabbe / filterpy

Python Kalman filtering and optimal estimation library. Implements Kalman filter, particle filter, Extended Kalman filter, Unscented Kalman filter, g-h (alpha-beta), least squares, H Infinity, smoothers, and more. Has companion book 'Kalman and Bayesian Filters in Python'.
MIT License
3.34k stars 623 forks source link

scipy linalg cholesky n-th leading minor not positive definite #62

Closed geoffviola closed 6 years ago

geoffviola commented 7 years ago

I sporadically get errors like "numpy.linalg.linalg.LinAlgError: 2-th leading minor not positive definite" when running the UKF's update and predict methods. What is this error a symptom of? Is there a way to bound the uncertainty?

rlabbe commented 7 years ago

It is hard to say exactly what is happening. However.... in general, KFs assume that everything is Gaussian and linear. But, it isn't, especially for UKFs. This often causes the covariance matrix P to slowly become not symmetric or positive definite.

The usual engineering fix is to do P = (P + P')/2 after every epoch. I don't think this is a well researched topic in academia. You might think/hope there would be a better fix depending the specifics of your problem, and perhaps there is, but I haven't seen anything on it. Once you start linearizing nonlinear equations you just lose accuracy and numerical stability. UKFs tend to be a lot more stable than EKFs, but they still have issues where you have to just brute force them back into stability.

If you are designing this for something real where the results matter, you'll need to invest a lot of effort in tests on real or simulated data to determine the bounds of performance. There you use things like the Cramer-Rao bound, Weiss-Weinstein Bound, or Barankin bound to compare your output with the best possible output. I can't reasonably expand on that in a github issue, but you can google it. Challa's "Fundamentals of Object Tracking" goes into it in useful/practical detail.

mbloem commented 5 years ago

I found this approach for finding the nearest symmetric positive definite matrix to a matrix, which may be an alternative to the engineering fix proposed in the answer. https://stackoverflow.com/questions/43238173/python-convert-matrix-to-positive-semi-definite https://gist.github.com/fasiha/fdb5cec2054e6f1c6ae35476045a0bbd

I used this in a few places with some success:

try:
    _ = np.linalg.cholesky(self.P)
except np.linalg.LinAlgError:
    self.P = nearestPD(self.P)
jonathanjfshaw commented 4 years ago

Some points:

1) I hit this immediately when trying to implement even a basic constant acceleration kinematic 1d UKF. So it seems like it's common and fundamental enough an issue that it would be kind to have a fix like this in the UKF class. Could be opt-out so that people could roll their own if they wanted to.

2) You can hit this in the SigmaPoints class (as well as the UKF class I guess)

3) For anyone else like me not familiar with matrix notation, I think P = (P + P')/2 in rlabbe's answer means filter.P = (filter.P + filter.P.T)/2

4) I can't speak to the algebra or theory of the gist linked to by @mbloem (it looks more sophisticated than th approach suggested by rlabbe), but as it stands it doesn't work well for us because it only takes effect if the matrix is not evaluated as positive definite by np.linalg.cholesky, and we use scipy.linalg.cholesky. Sometimes scipy complains when numpy doesn't. (see the isPD function in the gist, it's trivial to fix)

5) Fixing filter.P on every iteration in the way suggested by rlabbe doesn't work if you implement it in the most obvious way, i.e. in a loop just before calling predict(). This is because the SigmaPoints class performs some operations on P before calling the sqrt function, and so it can lose its positive definiteness even after you've fixed it up.

6) The better solution is instead to roll your own sqrt method that includes the fix and pass it into the SigmaPoints class or UKF class when it's initialised.

def sqrt_func(x):
    try:
        result = scipy.linalg.cholesky(x)
    except scipy.linalg.LinAlgError:
        x = (x + x.T)/2
        result = scipy.linalg.cholesky(x)
    return result

sigmas = MerweScaledSigmaPoints(state_dimensions, alpha=alpha, beta=beta, kappa=kappa, sqrt_method=sqrt_func)
jack-obrien commented 6 months ago

Hey, I spent an hour or two dealing with this issue today. In addition to following jonothan's solution above, I found that I needed to set kappa = n-3 in my initialisation of MerweScaledSigmaPoints.