PredictStates.m 2.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384
  1. function [nextQuat, nextStates, Tbn, correctedDelAng, correctedDelVel] = PredictStates( ...
  2. quat, ... % previous quaternion states 4x1
  3. states, ... % previous states (3x1 rotation error, 3x1 velocity, 3x1 gyro bias)
  4. angRate, ... % IMU rate gyro measurements, 3x1 (rad/sec)
  5. accel, ... % IMU accelerometer measurements 3x1 (m/s/s)
  6. dt) % time since last IMU measurement (sec)
  7. % Define parameters used for previous angular rates and acceleration shwich
  8. % are used for trapezoidal integration
  9. persistent prevAngRate;
  10. if isempty(prevAngRate)
  11. prevAngRate = angRate;
  12. end
  13. persistent prevAccel;
  14. if isempty(prevAccel)
  15. prevAccel = accel;
  16. end
  17. % define persistent variables for previous delta angle and velocity which
  18. % are required for sculling and coning error corrections
  19. persistent prevDelAng;
  20. if isempty(prevDelAng)
  21. prevDelAng = single([0;0;0]);
  22. end
  23. persistent prevDelVel;
  24. if isempty(prevDelVel)
  25. prevDelVel = single([0;0;0]);
  26. end
  27. % Convert IMU data to delta angles and velocities using trapezoidal
  28. % integration
  29. dAng = 0.5*(angRate + prevAngRate)*dt;
  30. dVel = 0.5*(accel + prevAccel )*dt;
  31. prevAngRate = angRate;
  32. prevAccel = accel;
  33. % Remove sensor bias errors
  34. dAng = dAng - states(7:9);
  35. % Apply rotational and skulling corrections
  36. correctedDelVel= dVel + ...
  37. 0.5*cross(prevDelAng + dAng , prevDelVel + dVel) + 1/6*cross(prevDelAng + dAng , cross(prevDelAng + dAng , prevDelVel + dVel)) + ... % rotational correction
  38. 1/12*(cross(prevDelAng , dVel) + cross(prevDelVel , dAng)); % sculling correction
  39. % Apply corrections for coning errors
  40. correctedDelAng = dAng - 1/12*cross(prevDelAng , dAng);
  41. % Save current measurements
  42. prevDelAng = dAng;
  43. prevDelVel = dVel;
  44. % Initialise the updated state vector
  45. nextQuat = quat;
  46. nextStates = states;
  47. % Convert the rotation vector to its equivalent quaternion
  48. rotationMag = sqrt(correctedDelAng(1)^2 + correctedDelAng(2)^2 + correctedDelAng(3)^2);
  49. if rotationMag<1e-12
  50. deltaQuat = single([1;0;0;0]);
  51. else
  52. deltaQuat = [cos(0.5*rotationMag); correctedDelAng/rotationMag*sin(0.5*rotationMag)];
  53. end
  54. % Update the quaternions by rotating from the previous attitude through
  55. % the delta angle rotation quaternion
  56. qUpdated = [quat(1)*deltaQuat(1)-transpose(quat(2:4))*deltaQuat(2:4); quat(1)*deltaQuat(2:4) + deltaQuat(1)*quat(2:4) + cross(quat(2:4),deltaQuat(2:4))];
  57. % Normalise the quaternions and update the quaternion states
  58. quatMag = sqrt(qUpdated(1)^2 + qUpdated(2)^2 + qUpdated(3)^2 + qUpdated(4)^2);
  59. if (quatMag < 1e-16)
  60. nextQuat(1:4) = qUpdated;
  61. else
  62. nextQuat(1:4) = qUpdated / quatMag;
  63. end
  64. % Calculate the body to nav cosine matrix
  65. Tbn = Quat2Tbn(nextQuat);
  66. % transform body delta velocities to delta velocities in the nav frame
  67. delVelNav = Tbn * correctedDelVel + [0;0;9.807]*dt;
  68. % Sum delta velocities to get velocity
  69. nextStates(4:6) = states(4:6) + delVelNav(1:3);
  70. end