ExtendedKalmanFilter.cpp 2.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879
  1. #include "ExtendedKalmanFilter.h"
  2. #include "AP_Math/matrixN.h"
  3. float ExtendedKalmanFilter::measurementpredandjacobian(VectorN<float,N> &A)
  4. {
  5. // This function computes the Jacobian using equations from
  6. // analytical derivation of Gaussian updraft distribution
  7. // This expression gets used lots
  8. float expon = expf(- (powf(X[2], 2) + powf(X[3], 2)) / powf(X[1], 2));
  9. // Expected measurement
  10. float w = X[0] * expon;
  11. // Elements of the Jacobian
  12. A[0] = expon;
  13. A[1] = 2 * X[0] * ((powf(X[2],2) + powf(X[3],2)) / powf(X[1],3)) * expon;
  14. A[2] = -2 * (X[0] * X[2] / powf(X[1],2)) * expon;
  15. A[3] = A[2] * X[3] / X[2];
  16. return w;
  17. }
  18. void ExtendedKalmanFilter::reset(const VectorN<float,N> &x, const MatrixN<float,N> &p, const MatrixN<float,N> q, float r)
  19. {
  20. P = p;
  21. X = x;
  22. Q = q;
  23. R = r;
  24. }
  25. void ExtendedKalmanFilter::update(float z, float Vx, float Vy)
  26. {
  27. MatrixN<float,N> tempM;
  28. VectorN<float,N> H;
  29. VectorN<float,N> P12;
  30. VectorN<float,N> K;
  31. // LINE 28
  32. // Estimate new state from old.
  33. X[2] -= Vx;
  34. X[3] -= Vy;
  35. // LINE 33
  36. // Update the covariance matrix
  37. // P = A*ekf.P*A'+ekf.Q;
  38. // We know A is identity so
  39. // P = ekf.P+ekf.Q;
  40. P += Q;
  41. // What measurement do we expect to receive in the estimated
  42. // state
  43. // LINE 37
  44. // [z1,H] = ekf.jacobian_h(x1);
  45. float z1 = measurementpredandjacobian(H);
  46. // LINE 40
  47. // P12 = P * H';
  48. P12.mult(P, H); //cross covariance
  49. // LINE 41
  50. // Calculate the KALMAN GAIN
  51. // K = P12 * inv(H*P12 + ekf.R); %Kalman filter gain
  52. K = P12 * 1.0 / (H * P12 + R);
  53. // Correct the state estimate using the measurement residual.
  54. // LINE 44
  55. // X = x1 + K * (z - z1);
  56. X += K * (z - z1);
  57. // Correct the covariance too.
  58. // LINE 46
  59. // NB should be altered to reflect Stengel
  60. // P = P_predict - K * P12';
  61. tempM.mult(K, P12);
  62. P -= tempM;
  63. P.force_symmetry();
  64. }