RunSimulation.m 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203
  1. %% Set initial conditions
  2. clear all;
  3. dtSlow = 1/50;
  4. dtFast = 1/1000;
  5. rateMult = round(dtSlow/dtFast);
  6. duration = 60;
  7. indexLimitSlow = round(duration/dtSlow);
  8. indexLimitFast = indexLimitSlow*rateMult;
  9. % create data logging variables
  10. gimbal.time = zeros(1,indexLimitFast);
  11. gimbal.euler = zeros(3,indexLimitFast);
  12. gimbal.eulerTruth = zeros(3,indexLimitFast);
  13. gimbal.eulerError = zeros(3,indexLimitFast);
  14. % Use a random initial truth orientation
  15. phiInit = 0.1*randn;
  16. thetaInit = 0.1*randn;
  17. psiInit = 2*pi*rand - pi;
  18. quatTruth = EulToQuat([phiInit,thetaInit,psiInit]);% [1;0.05*randn;0.05*randn;2*(rand-0.5)];
  19. quatLength = sqrt(quatTruth(1)^2 + quatTruth(2)^2 + quatTruth(3)^2 + quatTruth(4)^2);
  20. quatTruth = quatTruth / quatLength;
  21. TsnTruth = Quat2Tbn(quatTruth);
  22. % define the earths truth magnetic field
  23. declTruth = 10*pi/180;
  24. magEarthTruth = [0.25*cos(declTruth);0.25*sin(declTruth);-0.5];
  25. % define the declination parameter assuming 2deg RMS error - this would be
  26. % obtained from the main EKF to take advantage of in-flight learning
  27. declParam = declTruth + 2*pi/180*randn;
  28. % define the magnetometer bias errors
  29. magMeasBias = 0.02*[randn;randn;randn];
  30. % Define IMU bias errors and noise
  31. gyroBias = 1*pi/180*[randn;randn;randn];
  32. accBias = 0.05*[randn;randn;randn];
  33. gyroNoise = 0.01;
  34. accNoise = 0.05;
  35. % define the state covariances with the exception of the quaternion covariances
  36. Sigma_velNED = 0.5; % 1 sigma uncertainty in horizontal velocity components
  37. Sigma_dAngBias = 1*pi/180*dtSlow; % 1 Sigma uncertainty in delta angle bias
  38. Sigma_angErr = 1; % 1 Sigma uncertainty in angular misalignment (rad)
  39. covariance = single(diag([Sigma_angErr*[1;1;1];Sigma_velNED*[1;1;1];Sigma_dAngBias*[1;1;1]]).^2);
  40. % Initialise truth trajectory variables
  41. % fly a CCW circle with constant gimbal angles
  42. gPsiInit = 20*pi/180; % gimbal yaw
  43. gThetaInit = 0; % gimbal pitch
  44. gPhiInit = 0; % gimbal roll
  45. psiTruth = psiInit;
  46. radius = 20;
  47. gndSpd = 5;
  48. trackAngTruth = -pi;
  49. centripAccelMag = gndSpd/radius*gndSpd;
  50. gravAccel = [0;0;-9.81];
  51. %% Main Loop
  52. hdgAlignedEKF=0;
  53. hdgAlignedGimbal=0;
  54. slowIndex = 0;
  55. delAngFast = [0;0;0];
  56. delVelFast = [0;0;0];
  57. delAngSlow = [0;0;0];
  58. delVelSlow = [0;0;0];
  59. prevAngRateMeas = [0;0;0];
  60. prevAccelMeas = [0;0;0];
  61. quatFast = [1;0;0;0];
  62. quatFastSaved = quatFast;
  63. angRateBiasEKF = [0;0;0];
  64. quatEKF = [1;0;0;0];
  65. for fastIndex = 1:indexLimitFast % 1000 Hz gimbal prediction loop
  66. time = dtFast*fastIndex;
  67. % Calculate Truth Data
  68. % Need to replace this with a full kinematic model or test data
  69. % calculate truth angular rates - we don't start manoeuvring until
  70. % heading alignment is complete
  71. psiRateTruth = gndSpd/radius*hdgAlignedEKF;
  72. angRateTruth = [0;0;psiRateTruth]; % constant yaw rate
  73. % calculate yaw and track angles
  74. psiTruth = psiTruth + psiRateTruth*dtFast;
  75. trackAngTruth = trackAngTruth + psiRateTruth*dtFast;
  76. % Cacluate truth quternion
  77. quatTruth = EulToQuat([phiInit,thetaInit,psiTruth]);
  78. % Calculate truth rotaton from sensor to NED
  79. TsnTruth = Quat2Tbn(quatTruth);
  80. % calculate truth accel vector
  81. centripAccel = centripAccelMag*[-sin(trackAngTruth);cos(trackAngTruth);0];
  82. accelTruth = transpose(TsnTruth)*(gravAccel + centripAccel);
  83. % calculate truth velocity vector
  84. truthVel = gndSpd*[cos(trackAngTruth);sin(trackAngTruth);0];
  85. % synthesise sensor measurements
  86. % Synthesise IMU measurements, adding bias and noise
  87. angRateMeas = angRateTruth + gyroBias + gyroNoise*[randn;randn;randn];
  88. accelMeas = accelTruth + accBias + accNoise*[randn;randn;randn];
  89. % synthesise velocity measurements
  90. measVel = truthVel;
  91. % synthesise gimbal angles
  92. gPhi = 0;
  93. gTheta = 0;
  94. gPsi = gPsiInit;
  95. % Define rotation from magnetometer to sensor using a 312 rotation sequence
  96. TmsTruth = calcTms(gPhi,gPsi,gTheta);
  97. % calculate rotation from NED to magnetometer axes Tnm = Tsm * Tns
  98. TnmTruth = transpose(TmsTruth) * transpose(TsnTruth);
  99. % synthesise magnetometer measurements adding sensor bias
  100. magMeas = TnmTruth*magEarthTruth + magMeasBias;
  101. % integrate the IMU measurements to produce delta angles and velocities
  102. % using a trapezoidal integrator
  103. if isempty(prevAngRateMeas)
  104. prevAngRateMeas = angRateMeas;
  105. end
  106. if isempty(prevAccelMeas)
  107. prevAccelMeas = accelMeas;
  108. end
  109. delAngFast = delAngFast + 0.5*(angRateMeas + prevAngRateMeas)*dtFast;
  110. delVelFast = delVelFast + 0.5*(accelMeas + prevAccelMeas)*dtFast;
  111. prevAngRateMeas = angRateMeas;
  112. prevAccelMeas = accelMeas;
  113. % Run an attitude prediction calculation at 1000Hz
  114. % Convert the rotation vector to its equivalent quaternion
  115. % using a first order approximation after applying the correction for
  116. % gyro bias using bias estimates from the EKF
  117. deltaQuat = [1;0.5*(angRateMeas - angRateBiasEKF)*dtFast];
  118. % Update the quaternions by rotating from the previous attitude through
  119. % the delta angle rotation quaternion
  120. quatFast = QuatMult(quatFast,deltaQuat);
  121. % Normalise the quaternions
  122. quatFast = NormQuat(quatFast);
  123. % log the high rate data
  124. eulLogFast(:,fastIndex) = QuatToEul(quatFast);
  125. % every 20msec we send them to the EKF computer and reset
  126. % the total
  127. % we also save a copy of the quaternion from our high rate prediction
  128. if (rem(fastIndex,rateMult) == 0)
  129. delAngSlow = delAngFast;
  130. delVelSlow = delVelFast;
  131. delAngFast = [0;0;0];
  132. delVelFast = [0;0;0];
  133. quatFastSaved = quatFast;
  134. end
  135. % run the 50Hz EKF loop but do so 5 msec behind the
  136. % data transmission to simulate the effect of transmission and
  137. % computational delays
  138. if (rem(fastIndex,rateMult) == 5)
  139. slowIndex = slowIndex + 1;
  140. [quatEKF,angRateBiasEKF,EKFlogs,hdgAlignedEKF] = calcEKF(delAngSlow,delVelSlow,measVel,gPhi,gPsi,gTheta,magMeas,declParam,time,dtSlow,slowIndex,indexLimitSlow);
  141. end
  142. % Correct Gimbal attitude usng EKF data
  143. % Assume the gimbal controller receive the EKF solution 10 msec after
  144. % it sent the sensor data
  145. if (rem(fastIndex,rateMult) == 10)
  146. % calculate the quaternion from the EKF corrected attitude to the
  147. % attitude calculated using the local fast prediction algorithm
  148. deltaQuatFast = QuatDivide(quatEKF,quatFastSaved);
  149. % apply this correction to the fast solution at the current time
  150. % step (this can be applied across several steps to smooth the
  151. % output if required)
  152. quatFast = QuatMult(quatFast,deltaQuatFast);
  153. % normalise the resultant quaternion
  154. quatFast = NormQuat(quatFast);
  155. % flag when the gimbals own heading is aligned
  156. hdgAlignedGimbal = hdgAlignedEKF;
  157. end
  158. % Log gimbal data
  159. gimbal.time(fastIndex) = time;
  160. gimbal.euler(:,fastIndex) = QuatToEul(quatFast);
  161. gimbal.eulerTruth(:,fastIndex) = QuatToEul(quatTruth);
  162. if (hdgAlignedGimbal)
  163. gimbal.eulerError(:,fastIndex) = gimbal.euler(:,fastIndex) - gimbal.eulerTruth(:,fastIndex);
  164. if (gimbal.eulerError(3,fastIndex) > pi)
  165. gimbal.eulerError(3,fastIndex) = gimbal.eulerError(3,fastIndex) - 2*pi;
  166. elseif (gimbal.eulerError(3,fastIndex) < -pi)
  167. gimbal.eulerError(3,fastIndex) = gimbal.eulerError(3,fastIndex) + 2*pi;
  168. end
  169. else
  170. gimbal.eulerError(:,fastIndex) = [NaN;NaN;NaN];
  171. end
  172. end
  173. %% Generate Plots
  174. close all;
  175. PlotData;