GenerateEquations.m 8.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241
  1. % IMPORTANT - This script requires the Matlab symbolic toolbox
  2. % Author: Paul Riseborough
  3. % Last Modified: 16 Feb 2015
  4. % Derivation of a 3-axis gimbal attitude estimator using a local NED earth Tangent
  5. % Frame. Based on use of a rotation vector for attitude estimation as described
  6. % here:
  7. % Mark E. Pittelkau. "Rotation Vector in Attitude Estimation",
  8. % Journal of Guidance, Control, and Dynamics, Vol. 26, No. 6 (2003),
  9. % pp. 855-860.
  10. % The gimbal is assumed to have the following characteristics:
  11. % A three axis gimbal having a fixed top plate mounted to the vehicle body with a magnetometer
  12. % Yaw, roll and pitch degrees of freedom (yaw, roll, pitch Euler sequence)
  13. % with angle measurements on each gimbal axis
  14. % IMU measuring delta angles and delta velocites mounted on the
  15. % camera/sensor assembly
  16. % When the gimbal joints are all at zero degrees, the sensor assembly X,Y,Z
  17. % axis is aligned with the top plate X,Y,Z axis
  18. % State vector:
  19. % error rotation vector - X,Y,Z (rad)
  20. % Velocity - North, East, Down (m/s)
  21. % Delta Angle bias - X,Y,Z (rad)
  22. % Delta Velocity Bias - X,Y,Z (m/s)
  23. % Observations:
  24. % NED velocity - N,E,D (m/s)
  25. % sensor fixed magnetic field vector of base - X,Y,Z
  26. % Time varying parameters:
  27. % XYZ delta angle measurements in sensor axes - rad
  28. % XYZ delta velocity measurements in sensor axes - m/sec
  29. % yaw, roll, pitch gimbal rotation angles
  30. %% define symbolic variables and constants
  31. clear all;
  32. % specify if we want to incorporate accerometer bias estimation into the
  33. % filter, 0 = no, 1 = yes
  34. f_accBiasEst = 0;
  35. syms dax day daz real % IMU delta angle measurements in sensor axes - rad
  36. syms dvx dvy dvz real % IMU delta velocity measurements in sensor axes - m/sec
  37. syms q0 q1 q2 q3 real % quaternions defining attitude of sensor axes relative to local NED
  38. syms vn ve vd real % NED velocity - m/sec
  39. syms dax_b day_b daz_b real % delta angle bias - rad
  40. syms dvx_b dvy_b dvz_b real % delta velocity bias - m/sec
  41. syms dt real % IMU time step - sec
  42. syms gravity real % gravity - m/sec^2
  43. syms daxNoise dayNoise dazNoise dvxNoise dvyNoise dvzNoise real; % IMU delta angle and delta velocity measurement noise
  44. syms vwn vwe real; % NE wind velocity - m/sec
  45. syms magX magY magZ real; % XYZ top plate magnetic field measurements - milligauss
  46. syms magN magE magD real; % NED earth fixed magnetic field components - milligauss
  47. syms R_VN R_VE R_VD real % variances for NED velocity measurements - (m/sec)^2
  48. syms R_MAG real % variance for magnetic flux measurements - milligauss^2
  49. syms rotErr1 rotErr2 rotErr3 real; % error rotation vector
  50. syms decl real; % earth magnetic field declination from true north
  51. syms gPsi gPhi gTheta real; % gimbal joint angles yaw, roll, pitch (rad)
  52. %% define the process equations
  53. % define the measured Delta angle and delta velocity vectors
  54. dAngMeas = [dax; day; daz];
  55. dVelMeas = [dvx; dvy; dvz];
  56. % define the delta angle bias errors
  57. dAngBias = [dax_b; day_b; daz_b];
  58. % define the delta velocity bias errors
  59. if (f_accBiasEst > 0)
  60. dVelBias = [dvx_b; dvy_b; dvz_b];
  61. else
  62. dVelBias = [0; 0; 0];
  63. end
  64. % define the quaternion rotation vector for the state estimate
  65. estQuat = [q0;q1;q2;q3];
  66. % define the attitude error rotation vector, where error = truth - estimate
  67. errRotVec = [rotErr1;rotErr2;rotErr3];
  68. % define the attitude error quaternion using a first order linearisation
  69. errQuat = [1;0.5*errRotVec];
  70. % Define the truth quaternion as the estimate + error
  71. truthQuat = QuatMult(estQuat, errQuat);
  72. % derive the truth sensor to nav direction cosine matrix
  73. Tsn = Quat2Tbn(truthQuat);
  74. % define the truth delta angle
  75. % ignore coning acompensation as these effects are negligible in terms of
  76. % covariance growth for our application and grade of sensor
  77. dAngTruth = dAngMeas - dAngBias - [daxNoise;dayNoise;dazNoise];
  78. % Define the truth delta velocity
  79. dVelTruth = dVelMeas - dVelBias - [dvxNoise;dvyNoise;dvzNoise];
  80. % define the attitude update equations
  81. % use a first order expansion of rotation to calculate the quaternion increment
  82. % acceptable for propagation of covariances
  83. deltaQuat = [1;
  84. 0.5*dAngTruth(1);
  85. 0.5*dAngTruth(2);
  86. 0.5*dAngTruth(3);
  87. ];
  88. truthQuatNew = QuatMult(truthQuat,deltaQuat);
  89. % calculate the updated attitude error quaternion with respect to the previous estimate
  90. errQuatNew = QuatDivide(truthQuatNew,estQuat);
  91. % change to a rotaton vector - this is the error rotation vector updated state
  92. errRotNew = 2 * [errQuatNew(2);errQuatNew(3);errQuatNew(4)];
  93. % define the velocity update equations
  94. % ignore coriolis terms for linearisation purposes
  95. vNew = [vn;ve;vd] + [0;0;gravity]*dt + Tsn*dVelTruth;
  96. % define the IMU bias error update equations
  97. dabNew = dAngBias;
  98. dvbNew = dVelBias;
  99. % Define the state vector & number of states
  100. if (f_accBiasEst > 0)
  101. stateVector = [errRotVec;vn;ve;vd;dAngBias;dVelBias];
  102. else
  103. stateVector = [errRotVec;vn;ve;vd;dAngBias];
  104. end
  105. nStates=numel(stateVector);
  106. save 'symeqns.mat';
  107. %% derive the filter Jacobians
  108. % Define the control (disturbance) vector. Error growth in the inertial
  109. % solution is assumed to be driven by 'noise' in the delta angles and
  110. % velocities, after bias effects have been removed. This is OK because we
  111. % have sensor bias accounted for in the state equations.
  112. distVector = [daxNoise;dayNoise;dazNoise;dvxNoise;dvyNoise;dvzNoise];
  113. % derive the control(disturbance) influence matrix
  114. if (f_accBiasEst > 0)
  115. predictedState = [errRotNew;vNew;dabNew;dvbNew];
  116. else
  117. predictedState = [errRotNew;vNew;dabNew];
  118. end
  119. G = jacobian(predictedState, distVector);
  120. G = subs(G, {'rotErr1', 'rotErr2', 'rotErr3'}, {0,0,0});
  121. % derive the state error matrix
  122. distMatrix = diag(distVector);
  123. Q = G*distMatrix*transpose(G);
  124. %matlabFunction(Q,'file','calcQ.m');
  125. % derive the state transition matrix
  126. vNew = subs(vNew,{'daxNoise','dayNoise','dazNoise','dvxNoise','dvyNoise','dvzNoise'}, {0,0,0,0,0,0});
  127. errRotNew = subs(errRotNew,{'daxNoise','dayNoise','dazNoise','dvxNoise','dvyNoise','dvzNoise'}, {0,0,0,0,0,0});
  128. % Define the state vector & number of states
  129. if (f_accBiasEst)
  130. predictedState = [errRotNew;vNew;dabNew;dvbNew];
  131. else
  132. predictedState = [errRotNew;vNew;dabNew];
  133. end
  134. F = jacobian(predictedState, stateVector);
  135. F = subs(F, {'rotErr1', 'rotErr2', 'rotErr3'}, {0,0,0});
  136. %matlabFunction(F,'file','calcF.m');
  137. %% Derive the predicted covariance
  138. % This reduces the number of floating point operations by a factor of 4 or
  139. % more compared to using the standard matrix operations in code
  140. % define a symbolic covariance matrix using strings to represent
  141. % '_l_' to represent '( '
  142. % '_c_' to represent ,
  143. % '_r_' to represent ')'
  144. % these can be substituted later to create executable code
  145. for rowIndex = 1:nStates
  146. for colIndex = 1:nStates
  147. eval(['syms OP_l_',num2str(rowIndex),'_c_',num2str(colIndex), '_r_ real']);
  148. eval(['P(',num2str(rowIndex),',',num2str(colIndex), ') = OP_l_',num2str(rowIndex),'_c_',num2str(colIndex),'_r_;']);
  149. end
  150. end
  151. % Derive the predicted covariance matrix using the standard equation
  152. PP = F*P*transpose(F) + Q;
  153. %matlabFunction(PP,'file','calcP.m');
  154. ccode(PP,'file','calcP.c');
  155. FixCode('calcP');
  156. % free up memory
  157. clear all;
  158. reset(symengine);
  159. %% derive equations for fusion of magnetic deviation measurement
  160. load('symeqns.mat');
  161. % Define rotation from magnetometer to yaw gimbal
  162. T3 = [ cos(gPsi) sin(gPsi) 0; ...
  163. -sin(gPsi) cos(gPsi) 0; ...
  164. 0 0 1];
  165. % Define rotation from yaw gimbal to roll gimbal
  166. T1 = [ 1 0 0; ...
  167. 0 cos(gPhi) sin(gPhi); ...
  168. 0 -sin(gPhi) cos(gPhi)];
  169. % Define rotation from roll gimbal to pitch gimbal
  170. T2 = [ cos(gTheta) 0 -sin(gTheta); ...
  171. 0 1 0; ...
  172. sin(gTheta) 0 cos(gTheta)];
  173. % Define rotation from magnetometer to sensor using a 312 rotation sequence
  174. Tms = T2*T1*T3;
  175. % Define rotation from magnetometer to nav axes
  176. Tmn = Tsn*Tms;
  177. save 'symeqns.mat';
  178. % rotate magentic field measured at top plate into nav axes
  179. magMeasNED = Tmn*[magX;magY;magZ];
  180. % the predicted measurement is the angle wrt magnetic north of the horizontal
  181. % component of the measured field
  182. angMeas = tan(magMeasNED(2)/magMeasNED(1)) - decl;
  183. H_MAG = jacobian(angMeas,stateVector); % measurement Jacobian
  184. H_MAG = subs(H_MAG, {'rotErr1', 'rotErr2', 'rotErr3'}, {0,0,0});
  185. H_MAG = H_MAG(1:3);
  186. H_MAG = simplify(H_MAG);
  187. % matlabFunction(H_MAG,'file','calcH_MAG.m');
  188. ccode(H_MAG,'file','calcH_MAG.c');
  189. FixCode('calcH_MAG');
  190. % free up memory
  191. clear all;
  192. reset(symengine);
  193. %% generate helper functions
  194. load 'symeqns.mat';
  195. matlabFunction(Tms,'file','calcTms.m');
  196. Tmn = subs(Tmn, {'rotErr1', 'rotErr2', 'rotErr3'}, {0,0,0});
  197. matlabFunction(Tmn,'file','calcTmn.m');