PredictCovariance.m 1.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960
  1. function P = PredictCovariance(deltaAngle, ...
  2. deltaVelocity, ...
  3. quat, ...
  4. states,...
  5. P, ... % Previous state covariance matrix
  6. dt) ... % IMU and prediction time step
  7. % Set the filter state process noise (IMU errors are already built into the
  8. % equations). It includes the process noise required for evolution of the
  9. % IMU bias errors
  10. dAngBiasSigma = dt*1E-6;
  11. processNoise = [0*ones(1,7), dAngBiasSigma*[1 1 1]];
  12. % Specify the estimated errors on the delta angles and delta velocities
  13. daxNoise = (dt*25.0/60*pi/180)^2;
  14. dayNoise = (dt*25.0/60*pi/180)^2;
  15. dazNoise = (dt*25.0/60*pi/180)^2;
  16. dvxNoise = (dt*0.5)^2;
  17. dvyNoise = (dt*0.5)^2;
  18. dvzNoise = (dt*0.5)^2;
  19. dvx = deltaVelocity(1);
  20. dvy = deltaVelocity(2);
  21. dvz = deltaVelocity(3);
  22. dax = deltaAngle(1);
  23. day = deltaAngle(2);
  24. daz = deltaAngle(3);
  25. q0 = quat(1);
  26. q1 = quat(2);
  27. q2 = quat(3);
  28. q3 = quat(4);
  29. dax_b = states(8);
  30. day_b = states(9);
  31. daz_b = states(10);
  32. % Predicted covariance
  33. F = calcF(dax,dax_b,day,day_b,daz,daz_b,dvx,dvy,dvz,q0,q1,q2,q3);
  34. Q = calcQ(daxNoise,dayNoise,dazNoise,dvxNoise,dvyNoise,dvzNoise,q0,q1,q2,q3);
  35. P = F*P*transpose(F) + Q;
  36. % Add the general process noise
  37. for i = 1:10
  38. P(i,i) = P(i,i) + processNoise(i)^2;
  39. end
  40. % Force symmetry on the covariance matrix to prevent ill-conditioning
  41. % of the matrix which would cause the filter to blow-up
  42. P = 0.5*(P + transpose(P));
  43. % ensure diagonals are positive
  44. for i=1:9
  45. if P(i,i) < 0
  46. P(i,i) = 0;
  47. end
  48. end
  49. end