GenerateEquations.m 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113
  1. % IMPORTANT - This script requires the Matlab symbolic toolbox
  2. % Author: Paul Riseborough
  3. % Last Modified: 16 Feb 2014
  4. % Derivation of a navigation EKF using a local NED earth Tangent Frame for
  5. % the initial alignment and gyro bias estimation from a moving platform
  6. % Uses quaternions for attitude propagation
  7. % State vector:
  8. % quaternions
  9. % Velocity - North, East, Down (m/s)
  10. % Delta Angle bias - X,Y,Z (rad)
  11. % Observations:
  12. % NED velocity - N,E,D (m/s)
  13. % body fixed magnetic field vector - X,Y,Z
  14. % Time varying parameters:
  15. % XYZ delta angle measurements in body axes - rad
  16. % XYZ delta velocity measurements in body axes - m/sec
  17. % magnetic declination
  18. clear all;
  19. %% define symbolic variables and constants
  20. syms dax day daz real % IMU delta angle measurements in body axes - rad
  21. syms dvx dvy dvz real % IMU delta velocity measurements in body axes - m/sec
  22. syms q0 q1 q2 q3 real % quaternions defining attitude of body axes relative to local NED
  23. syms vn ve vd real % NED velocity - m/sec
  24. syms dax_b day_b daz_b real % delta angle bias - rad
  25. syms dvx_b dvy_b dvz_b real % delta velocity bias - m/sec
  26. syms dt real % IMU time step - sec
  27. syms gravity real % gravity - m/sec^2
  28. syms daxNoise dayNoise dazNoise dvxNoise dvyNoise dvzNoise real; % IMU delta angle and delta velocity measurement noise
  29. syms vwn vwe real; % NE wind velocity - m/sec
  30. syms magX magY magZ real; % XYZ body fixed magnetic field measurements - milligauss
  31. syms magN magE magD real; % NED earth fixed magnetic field components - milligauss
  32. syms R_VN R_VE R_VD real % variances for NED velocity measurements - (m/sec)^2
  33. syms R_MAG real % variance for magnetic flux measurements - milligauss^2
  34. %% define the process equations
  35. % define the measured Delta angle and delta velocity vectors
  36. dAngMeas = [dax; day; daz];
  37. dVelMeas = [dvx; dvy; dvz];
  38. % define the delta angle bias errors
  39. dAngBias = [dax_b; day_b; daz_b];
  40. % define the quaternion rotation vector for the state estimate
  41. quat = [q0;q1;q2;q3];
  42. % derive the truth body to nav direction cosine matrix
  43. Tbn = Quat2Tbn(quat);
  44. % define the truth delta angle
  45. % ignore coning acompensation as these effects are negligible in terms of
  46. % covariance growth for our application and grade of sensor
  47. dAngTruth = dAngMeas - dAngBias;
  48. % Define the truth delta velocity
  49. dVelTruth = dVelMeas;
  50. % define the attitude update equations
  51. % use a first order expansion of rotation to calculate the quaternion increment
  52. % acceptable for propagation of covariances
  53. deltaQuat = [1;
  54. 0.5*dAngTruth(1);
  55. 0.5*dAngTruth(2);
  56. 0.5*dAngTruth(3);
  57. ];
  58. quatNew = QuatMult(quat,deltaQuat);
  59. % define the velocity update equations
  60. % ignore coriolis terms for linearisation purposes
  61. vNew = [vn;ve;vd] + [0;0;gravity]*dt + Tbn*dVelTruth;
  62. % define the IMU bias error update equations
  63. dabNew = [dax_b; day_b; daz_b];
  64. % Define the state vector & number of states
  65. stateVector = [quat;vn;ve;vd;dAngBias];
  66. nStates=numel(stateVector);
  67. %% derive the covariance prediction equation
  68. % This reduces the number of floating point operations by a factor of 6 or
  69. % more compared to using the standard matrix operations in code
  70. % Define the control (disturbance) vector. Use the measured delta angles
  71. % and velocities (not truth) to simplify the derivation
  72. distVector = [dAngMeas;dVelMeas];
  73. % derive the control(disturbance) influence matrix
  74. G = jacobian([quatNew;vNew;dabNew], distVector);
  75. f = matlabFunction(G,'file','calcG.m');
  76. % derive the state error matrix
  77. imuNoise = diag([daxNoise dayNoise dazNoise dvxNoise dvyNoise dvzNoise]);
  78. Q = G*imuNoise*transpose(G);
  79. f = matlabFunction(Q,'file','calcQ.m');
  80. % derive the state transition matrix
  81. F = jacobian([quatNew;vNew;dabNew], stateVector);
  82. f = matlabFunction(F,'file','calcF.m');
  83. %% derive equations for fusion of magnetic deviation measurement
  84. % rotate body measured field into earth axes
  85. magMeasNED = Tbn*[magX;magY;magZ];
  86. % the predicted measurement is the angle wrt true north of the horizontal
  87. % component of the measured field
  88. angMeas = tan(magMeasNED(2)/magMeasNED(1));
  89. H_MAG = jacobian(angMeas,stateVector); % measurement Jacobian
  90. f = matlabFunction(H_MAG,'file','calcH_MAG.m');