GenerateEquations.m 6.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161
  1. % IMPORTANT - This script requires the Matlab symbolic toolbox
  2. % Author: Paul Riseborough
  3. % Last Modified: 16 Feb 2015
  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. % Based on use of a rotation vector for attitude estimation as described
  7. % here:
  8. %
  9. % Mark E. Pittelkau. "Rotation Vector in Attitude Estimation",
  10. % Journal of Guidance, Control, and Dynamics, Vol. 26, No. 6 (2003),
  11. % pp. 855-860.
  12. %
  13. % The benefits for use of rotation error vector over use of a four parameter
  14. % quaternion representation of the estiamted orientation are:
  15. % a) Reduced computational load
  16. % b) Improved stability
  17. % c) The ability to recover faster from large orientation errors. This
  18. % makes this filter particularly suitable where the initial alignment is
  19. % uncertain
  20. % State vector:
  21. % error rotation vector
  22. % Velocity - North, East, Down (m/s)
  23. % Delta Angle bias - X,Y,Z (rad)
  24. % Observations:
  25. % NED velocity - N,E,D (m/s)
  26. % body fixed magnetic field vector - X,Y,Z
  27. % Time varying parameters:
  28. % XYZ delta angle measurements in body axes - rad
  29. % XYZ delta velocity measurements in body axes - m/sec
  30. % magnetic declination
  31. clear all;
  32. %% define symbolic variables and constants
  33. syms dax day daz real % IMU delta angle measurements in body axes - rad
  34. syms dvx dvy dvz real % IMU delta velocity measurements in body axes - m/sec
  35. syms q0 q1 q2 q3 real % quaternions defining attitude of body axes relative to local NED
  36. syms vn ve vd real % NED velocity - m/sec
  37. syms dax_b day_b daz_b real % delta angle bias - rad
  38. syms dvx_b dvy_b dvz_b real % delta velocity bias - m/sec
  39. syms dt real % IMU time step - sec
  40. syms gravity real % gravity - m/sec^2
  41. syms daxNoise dayNoise dazNoise dvxNoise dvyNoise dvzNoise real; % IMU delta angle and delta velocity measurement noise
  42. syms vwn vwe real; % NE wind velocity - m/sec
  43. syms magX magY magZ real; % XYZ body fixed magnetic field measurements - milligauss
  44. syms magN magE magD real; % NED earth fixed magnetic field components - milligauss
  45. syms R_VN R_VE R_VD real % variances for NED velocity measurements - (m/sec)^2
  46. syms R_MAG real % variance for magnetic flux measurements - milligauss^2
  47. syms rotErr1 rotErr2 rotErr3 real; % error rotation vector
  48. %% define the process equations
  49. % define the measured Delta angle and delta velocity vectors
  50. dAngMeas = [dax; day; daz];
  51. dVelMeas = [dvx; dvy; dvz];
  52. % define the delta angle bias errors
  53. dAngBias = [dax_b; day_b; daz_b];
  54. % define the quaternion rotation vector for the state estimate
  55. estQuat = [q0;q1;q2;q3];
  56. % define the attitude error rotation vector, where error = truth - estimate
  57. errRotVec = [rotErr1;rotErr2;rotErr3];
  58. % define the attitude error quaternion using a first order linearisation
  59. errQuat = [1;0.5*errRotVec];
  60. % Define the truth quaternion as the estimate + error
  61. truthQuat = QuatMult(estQuat, errQuat);
  62. % derive the truth body to nav direction cosine matrix
  63. Tbn = Quat2Tbn(truthQuat);
  64. % define the truth delta angle
  65. % ignore coning acompensation as these effects are negligible in terms of
  66. % covariance growth for our application and grade of sensor
  67. dAngTruth = dAngMeas - dAngBias - [daxNoise;dayNoise;dazNoise];
  68. % Define the truth delta velocity
  69. dVelTruth = dVelMeas - [dvxNoise;dvyNoise;dvzNoise];
  70. % define the attitude update equations
  71. % use a first order expansion of rotation to calculate the quaternion increment
  72. % acceptable for propagation of covariances
  73. deltaQuat = [1;
  74. 0.5*dAngTruth(1);
  75. 0.5*dAngTruth(2);
  76. 0.5*dAngTruth(3);
  77. ];
  78. truthQuatNew = QuatMult(truthQuat,deltaQuat);
  79. % calculate the updated attitude error quaternion with respect to the previous estimate
  80. errQuatNew = QuatDivide(truthQuatNew,estQuat);
  81. % change to a rotaton vector - this is the error rotation vector updated state
  82. errRotNew = 2 * [errQuatNew(2);errQuatNew(3);errQuatNew(4)];
  83. % define the velocity update equations
  84. % ignore coriolis terms for linearisation purposes
  85. vNew = [vn;ve;vd] + [0;0;gravity]*dt + Tbn*dVelTruth;
  86. % define the IMU bias error update equations
  87. dabNew = [dax_b; day_b; daz_b];
  88. % Define the state vector & number of states
  89. stateVector = [errRotVec;vn;ve;vd;dAngBias];
  90. nStates=numel(stateVector);
  91. %% derive the covariance prediction equation
  92. % This reduces the number of floating point operations by a factor of 6 or
  93. % more compared to using the standard matrix operations in code
  94. % Define the control (disturbance) vector. Error growth in the inertial
  95. % solution is assumed to be driven by 'noise' in the delta angles and
  96. % velocities, after bias effects have been removed. This is OK because we
  97. % have sensor bias accounted for in the state equations.
  98. distVector = [daxNoise;dayNoise;dazNoise;dvxNoise;dvyNoise;dvzNoise];
  99. % derive the control(disturbance) influence matrix
  100. G = jacobian([errRotNew;vNew;dabNew], distVector);
  101. G = subs(G, {'rotErr1', 'rotErr2', 'rotErr3'}, {0,0,0});
  102. % derive the state error matrix
  103. distMatrix = diag(distVector);
  104. Q = G*distMatrix*transpose(G);
  105. f = matlabFunction(Q,'file','calcQ.m');
  106. % derive the state transition matrix
  107. vNew = subs(vNew,{'daxNoise','dayNoise','dazNoise','dvxNoise','dvyNoise','dvzNoise'}, {0,0,0,0,0,0});
  108. errRotNew = subs(errRotNew,{'daxNoise','dayNoise','dazNoise','dvxNoise','dvyNoise','dvzNoise'}, {0,0,0,0,0,0});
  109. F = jacobian([errRotNew;vNew;dabNew], stateVector);
  110. F = subs(F, {'rotErr1', 'rotErr2', 'rotErr3'}, {0,0,0});
  111. f = matlabFunction(F,'file','calcF.m');
  112. % define a symbolic covariance matrix using strings to represent
  113. % '_l_' to represent '( '
  114. % '_c_' to represent ,
  115. % '_r_' to represent ')'
  116. % these can be substituted later to create executable code
  117. % for rowIndex = 1:nStates
  118. % for colIndex = 1:nStates
  119. % eval(['syms OP_l_',num2str(rowIndex),'_c_',num2str(colIndex), '_r_ real']);
  120. % eval(['P(',num2str(rowIndex),',',num2str(colIndex), ') = OP_l_',num2str(rowIndex),'_c_',num2str(colIndex),'_r_;']);
  121. % end
  122. % end
  123. % Derive the predicted covariance matrix using the standard equation
  124. % nextP = F*P*transpose(F) + Q;
  125. % f = matlabFunction(nextP,'file','calcP.m');
  126. %% derive equations for fusion of magnetic deviation measurement
  127. % rotate body measured field into earth axes
  128. magMeasNED = Tbn*[magX;magY;magZ];
  129. % the predicted measurement is the angle wrt true north of the horizontal
  130. % component of the measured field
  131. angMeas = tan(magMeasNED(2)/magMeasNED(1));
  132. H_MAG = jacobian(angMeas,stateVector); % measurement Jacobian
  133. H_MAG = subs(H_MAG, {'rotErr1', 'rotErr2', 'rotErr3'}, {0,0,0});
  134. f = matlabFunction(H_MAG,'file','calcH_MAG.m');