Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

EKF and UKF differ on linear problem with linear measurement #172

Closed
vhartman opened this issue Nov 24, 2018 · 16 comments
Closed

EKF and UKF differ on linear problem with linear measurement #172

vhartman opened this issue Nov 24, 2018 · 16 comments
Assignees
Labels

Comments

@vhartman
Copy link

Hey,
I was testing some of the filters to figure out if I am doing something wrong in my own implementation. Namely, I am interested in the covariance in both filters. From my understanding, this should be equal in a linear problem with a linear measurement.

The example (https://gist.github.com/vhartman/4e25e5521f0940e370e6019dcc6b5ea1) demonstrates that there is a difference between the two, i.e. P is larger in the UKF Is there a different meaning of P in the two filters? (The error in the position tends to zero in the trivial problem)

Thanks!

@rlabbe
Copy link
Owner

rlabbe commented Nov 26, 2018

You know, I don't have a good answer at the moment.

I'll observe that the UKF is sampling from a 1D space; I don't think it is really designed for that degenerate case (I know, this is hand waving). For example, look at the sigma points for the simpler Julier construction:

JulierSigmaPoints object
n = 1
kappa = 0.0
Wm = [0. 0.5 0.5]
Wc = [0. 0.5 0.5]

You can see that it gives 0 weight to the center point (which is the actual prior), and then 50% to the sigma points spread on each side. With the KF state giving no extra information (via velocity or what have you), perhaps it is reasonable that the UKF is more uncertain.

I altered your code by changing Q = [.0001]. In this case P is essentially identical between the two. A Q of 1 is extremely large. You are simulating a stationary process, yet telling the filters there is very significant movement between every epoch.

Ultimately, the KF is designed for dynamic systems with a process model, and you are simulating a system with no process model, and giving it a very large process error. This is hand-wavey again, but I'm not surprised there is a difference in their covariances (uncertainty in the state) in this case.

@vhartman
Copy link
Author

I don't agree with the point on the 1D case: the UKF fails in the same way in higher dimensions, it is simply easier to observe it on the simple 1D problem. In theory, the UKF is accurate to the second order (i.e. the variance of the distribution), and should thus be able to solve the problem exactly (as the kalman filter does).

I also don't agree with the point you make with the decreased measurement variance. The error in P between EKF and UKF becomes smaller, yes. But relative to Q, it stays almost the same (give or take some numerical errors). (It goes from Q = 1: P_EKF - P_UKF = -1 to Q = 0.0001: P_EKF - P_UKF = -9.99647e-5 \approx -1e-4).

The model I have here is simply a random walk, represented with its dynamical model. So I would not say that there is no dynamical model, it is just very simple. (But again: the same issue can be reproduced with a different model, i.e. one with position and velocity as states, and even in 2D - this just makes the difference harder to observe).

I am not saying that the implementation is wrong (I observe the same problem in my implementation), I am just trying to understand what drives the difference, respectively to figure out why they are different.

@rlabbe
Copy link
Owner

rlabbe commented Nov 26, 2018

Your right, I just coded a 1D problem with velocity, where z = i + randn(), and the same issue occurs.

Interestingly, P prior of the Kalman filter equals P posterior of the UKF. To me this implies Q is being inappropriately applied twice somehow. I'll dig into this a bit tonight.

@vhartman
Copy link
Author

Figured it out. A recomputation of the sigma points is necessary after the prediction. Otherwise the sigma points do not represent the variance of the predicted pdf correctly, and it comes into the cross covariance, and in the measurement covariance wrong.

In my implementation, this looks something like this:
m_x, p_xx = UT(pts, lambda x: A * x, Q)
prop_pts_corr = sigma_pts(m_x, p_xx)
m_y, p_yy = UT(prop_pts_corr, lambda x: C * x, R)

Note that the measurement sigma points do not have to be resampled.

@rlabbe
Copy link
Owner

rlabbe commented Nov 29, 2018

Hey, fantastic! I restructured my code a few months ago by adding the methodcompute_process_sigmas, I don't know if I introduced the bug then or if it always lurked in the code. I'll try to get a fix out in FilterPy ASAP.

@rlabbe rlabbe added the bug label Nov 29, 2018
@rlabbe rlabbe self-assigned this Nov 29, 2018
@vhartman
Copy link
Author

I would assume that it was always around. I was not able to find a single paper that mentions the recomputation explicitly, and another library (pykalman) has the same problem from glancing quickly over it.

Should not be too hard to fix though!

@rlabbe
Copy link
Owner

rlabbe commented Nov 29, 2018

You are probably right.

If so, there is a paper to write in your future!

@da-phil
Copy link

da-phil commented Dec 19, 2018

Interesting, I noticed exactly the same when I used the UKF on a linear problem and later switched to a linear KF and realized that the linear KF had a lower P.

@rlabbe
Copy link
Owner

rlabbe commented Dec 21, 2018

My unit tests were passing because Q was in the form of [[0, 0],[0 .001]]. At this point i don't fully understand why that allowed the tests to pass; I'm guessing there was not enough change in P' (prior) to cause computational difficulties. If I change Q to a more realistic definition, such as provided by Q_discrete_white_noise, the unit tests fail.

However, with the code change, and altering Q to use more realistic, other tests are failing because P fails to remain positive definite in all cases. For example, test_linear_rts fails because R (sig_o in that code) is extremely small, leading to P being ~ 0 in most of its terms. Applying the P = (P + P.T)/2 does not fix this problem.

Anyway, I am not going to make a check in of the fix until I figure out why the instabilities occur and a way to compensate for it.

In the meantime, if you place the line

        self.sigmas_f = self.points_fn.sigma_points(self.x, self.P)

after the call to UT in UnscentedKalmanFilter.predict() you will get the desired functionality.

If you don't want to alter the FilterPy code, you can also do something like this:

for z in zs:
   ukf.predict()
   ukf.sigmas_f = ukf.points_fn.sigma_points(ukf.x, ukf.P)
   ukf.update(z)

However, if you do this then you will be unable to use the batch functions.

I haven't worked on it yet, but I suspect the same problem exists in the method rts_smoother(). If the covariance of the state is important to you you may want to hold off on using this method.

@taliesin
Copy link

Hi,
I'm pretty sure I'm running into the very same issue. This is not yet fixed in filterpy-1.4.5, am I right?

@vhartman
Copy link
Author

Does not seem to be fixed. I wanted to look into it at some point, and even fixed in my own implementation, but didn't get around writing a fix for the implementation here. The fix posted by rlabbe above should do the job just fine.

I will hopefully have time to look into it on the weekend.

@taliesin
Copy link

taliesin commented May 22, 2019

Ok, thanks for the response. Just got hooked up by other troubles. I'll recheck next week, if you're fast this will probably save me some time :-)

vhartman pushed a commit to vhartman/filterpy that referenced this issue Oct 25, 2019
@vhartman
Copy link
Author

Hey @taliesin, I finally got around fixing the issue in the source - sorry that it took so long. I was assuming that it was pretty self contained, but as @rlabbe mentioned above already, some other tests were affected by the change as well, which complicated the fix.

@taliesin
Copy link

Thx for your work, my project however is dead, still hoping to come back to it one day.

@jonathanjfshaw
Copy link
Contributor

However, with the code change, and altering Q to use more realistic, other tests are failing because P fails to remain positive definite in all cases. For example, test_linear_rts fails because R (sig_o in that code) is extremely small, leading to P being ~ 0 in most of its terms. Applying the P = (P + P.T)/2 does not fix this problem.

Anyway, I am not going to make a check in of the fix until I figure out why the instabilities occur and a way to compensate for it.

There's some discussion in #62 about the positive definite stuff that may have a small relevance

rlabbe added a commit that referenced this issue May 4, 2020
Added unit test code provided on issue #172 that found an
issue with UKF not behaving the same as EKF for linear
problems.
@rlabbe
Copy link
Owner

rlabbe commented May 4, 2020

All of these changes have been made and tests are passing. I'll close for now.

@rlabbe rlabbe closed this as completed May 4, 2020
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

5 participants