FuseVelocity.m 2.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172
  1. function [...
  2. quat, ... % quaternion state vector after fusion of measurements
  3. states, ... % state vector after fusion of measurements
  4. tiltErr, ... % angle error
  5. P, ... % state covariance matrix after fusion of corrections
  6. innovation,... % NED velocity innovations (m/s)
  7. varInnov] ... % NED velocity innovation variance ((m/s)^2)
  8. = FuseVelocity( ...
  9. quat, ... % predicted quaternion states from the INS
  10. states, ... % predicted states from the INS
  11. P, ... % predicted covariance
  12. measVel) % NED velocity measurements (m/s)
  13. R_OBS = 0.5^2;
  14. innovation = zeros(1,3);
  15. varInnov = zeros(1,3);
  16. % Fuse measurements sequentially
  17. angErrVec = [0;0;0];
  18. for obsIndex = 1:3
  19. stateIndex = 3 + obsIndex;
  20. % Calculate the velocity measurement innovation
  21. innovation(obsIndex) = states(stateIndex) - measVel(obsIndex);
  22. % Calculate the Kalman Gain taking advantage of direct state observation
  23. H = zeros(1,9);
  24. H(1,stateIndex) = 1;
  25. varInnov(obsIndex) = P(stateIndex,stateIndex) + R_OBS;
  26. K = P(:,stateIndex)/varInnov(obsIndex);
  27. % Calculate state corrections
  28. xk = K * innovation(obsIndex);
  29. % Apply the state corrections
  30. states(1:3) = 0;
  31. states = states - xk;
  32. % Store tilt error estimate for external monitoring
  33. angErrVec = angErrVec + states(1:3);
  34. % the first 3 states represent the angular misalignment vector. This is
  35. % is used to correct the estimated quaternion
  36. % Convert the error rotation vector to its equivalent quaternion
  37. % truth = estimate + error
  38. rotationMag = sqrt(states(1)^2 + states(2)^2 + states(3)^2);
  39. if rotationMag > 1e-12
  40. deltaQuat = [cos(0.5*rotationMag); [states(1);states(2);states(3)]/rotationMag*sin(0.5*rotationMag)];
  41. % Update the quaternion states by rotating from the previous attitude through
  42. % the error quaternion
  43. quat = QuatMult(quat,deltaQuat);
  44. % re-normalise the quaternion
  45. quatMag = sqrt(quat(1)^2 + quat(2)^2 + quat(3)^2 + quat(4)^2);
  46. quat = quat / quatMag;
  47. end
  48. % Update the covariance
  49. P = P - K*P(stateIndex,:);
  50. % Force symmetry on the covariance matrix to prevent ill-conditioning
  51. P = 0.5*(P + transpose(P));
  52. % ensure diagonals are positive
  53. for i=1:9
  54. if P(i,i) < 0
  55. P(i,i) = 0;
  56. end
  57. end
  58. end
  59. tiltErr = sqrt(dot(angErrVec(1:2),angErrVec(1:2)));
  60. end