RunRealData.m 3.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586
  1. %% Set initial conditions
  2. clear all;
  3. load('fltTest.mat');
  4. startDelayTime = 100; % number of seconds to delay filter start (used to simulate in-flight restart)
  5. dt = 1/50;
  6. indexLimit = length(IMU);
  7. magIndexlimit = length(MAG);
  8. statesLog = zeros(10,indexLimit);
  9. eulLog = zeros(4,indexLimit);
  10. velInnovLog = zeros(4,indexLimit);
  11. angErrLog = zeros(2,indexLimit);
  12. decInnovLog = zeros(2,magIndexlimit);
  13. velInnovVarLog = velInnovLog;
  14. decInnovVarLog = decInnovLog;
  15. % initialise the state vector and quaternion
  16. states = zeros(9,1);
  17. quat = [1;0;0;0];
  18. Tbn = Quat2Tbn(quat);
  19. % average last 10 accel readings to reduce effect of noise
  20. initAccel(1) = mean(IMU(1:10,6));
  21. initAccel(2) = mean(IMU(1:10,7));
  22. initAccel(3) = mean(IMU(1:10,8));
  23. % Use averaged accel readings to align tilt
  24. quat = AlignTilt(quat,initAccel);
  25. % Set the expected declination
  26. measDec = 0.18;
  27. % define the state covariances
  28. Sigma_velNED = 0.5; % 1 sigma uncertainty in horizontal velocity components
  29. Sigma_dAngBias = 5*pi/180*dt; % 1 Sigma uncertainty in delta angle bias
  30. Sigma_angErr = 1; % 1 Sigma uncertainty in angular misalignment (rad)
  31. covariance = single(diag([Sigma_angErr*[1;1;1];Sigma_velNED*[1;1;1];Sigma_dAngBias*[1;1;1]].^2));
  32. %% Main Loop
  33. magIndex = 1;
  34. time = 0;
  35. angErr = 0;
  36. headingAligned = 0;
  37. % delay start by a minimum of 10 IMU samples to allow for initial tilt
  38. % alignment delay
  39. startIndex = max(11,ceil(startDelayTime/dt));
  40. for index = startIndex:indexLimit
  41. time=time+dt + startIndex*dt;
  42. % read IMU measurements
  43. angRate = IMU(index,3:5)';
  44. % switch in a bias offset to test the filter
  45. if (time > +inf)
  46. angRate = angRate + [1;-1;1]*pi/180;
  47. end
  48. accel = IMU(index,6:8)';
  49. % predict states
  50. [quat, states, Tbn, delAng, delVel] = PredictStates(quat,states,angRate,accel,dt);
  51. statesLog(1,index) = time;
  52. statesLog(2:10,index) = states;
  53. eulLog(1,index) = time;
  54. eulLog(2:4,index) = QuatToEul(quat);
  55. % predict covariance matrix
  56. covariance = PredictCovariance(delAng,delVel,quat,states,covariance,dt);
  57. % fuse velocity measurements - use synthetic measurements
  58. measVel = [0;0;0];
  59. [quat,states,angErr,covariance,velInnov,velInnovVar] = FuseVelocity(quat,states,covariance,measVel);
  60. velInnovLog(1,index) = time;
  61. velInnovLog(2:4,index) = velInnov;
  62. velInnovVarLog(1,index) = time;
  63. velInnovVarLog(2:4,index) = velInnovVar;
  64. angErrLog(1,index) = time;
  65. angErrLog(2,index) = angErr;
  66. % read magnetometer measurements
  67. while ((MAG(magIndex,1) < IMU(index,1)) && (magIndex < magIndexlimit))
  68. magIndex = magIndex + 1;
  69. magBody = 0.001*MAG(magIndex,3:5)';
  70. if (time >= 1.0 && headingAligned==0 && angErr < 1e-3)
  71. quat = AlignHeading(quat,magBody,measDec);
  72. headingAligned = 1;
  73. end
  74. % fuse magnetometer measurements if new data available and when tilt has settled
  75. if (headingAligned == 1)
  76. [quat,states,covariance,decInnov,decInnovVar] = FuseMagnetometer(quat,states,covariance,magBody,measDec,Tbn);
  77. decInnovLog(1,magIndex) = time;
  78. decInnovLog(2,magIndex) = decInnov;
  79. decInnovVarLog(1,magIndex) = time;
  80. decInnovVarLog(2,magIndex) = decInnovVar;
  81. end
  82. end
  83. end
  84. %% Generate plots
  85. PlotData;