RunSyntheticData.m 3.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778
  1. %% Set initial conditions
  2. clear all;
  3. dt = 1/100;
  4. duration = 10;
  5. indexLimit = round(duration/dt);
  6. statesLog = zeros(10,indexLimit);
  7. eulLog = zeros(4,indexLimit);
  8. velInnovLog = zeros(4,indexLimit);
  9. decInnovLog = zeros(2,indexLimit);
  10. velInnovVarLog = velInnovLog;
  11. decInnovVarLog = decInnovLog;
  12. angErrLog = zeros(2,indexLimit);
  13. % Use a random initial orientation
  14. quatTruth = [rand;randn;randn;randn];
  15. quatLength = sqrt(quatTruth(1)^2 + quatTruth(2)^2 + quatTruth(3)^2 + quatTruth(4)^2);
  16. quatTruth = quatTruth / quatLength;
  17. TbnTruth = Quat2Tbn(quatTruth);
  18. % initialise the filter to level
  19. quat = [1;0;0;0];
  20. states = zeros(9,1);
  21. Tbn = Quat2Tbn(quat);
  22. % define the earths truth magnetic field
  23. magEarthTruth = [0.3;0.1;-0.5];
  24. % define the assumed declination using th etruth field plus location
  25. % variation
  26. measDec = atan2(magEarthTruth(2),magEarthTruth(1)) + 2*pi/180*randn;
  27. % define the magnetometer bias errors
  28. magMeasBias = 0.02*[randn;randn;randn];
  29. % define the state covariances with the exception of the quaternion covariances
  30. Sigma_velNED = 0.5; % 1 sigma uncertainty in horizontal velocity components
  31. Sigma_dAngBias = 1*pi/180*dt; % 1 Sigma uncertainty in delta angle bias
  32. Sigma_angErr = 1; % 1 Sigma uncertainty in angular misalignment (rad)
  33. covariance = single(diag([Sigma_angErr*[1;1;1];Sigma_velNED*[1;1;1];Sigma_dAngBias*[1;1;1]].^2));
  34. %% Main Loop
  35. headingAligned=0;
  36. time = 0;
  37. for index = 1:indexLimit
  38. time=time+dt;
  39. % synthesise IMU measurements
  40. angRate = 0*[randn;randn;randn];
  41. accel = 0*[randn;randn;randn] + transpose(TbnTruth)*[0;0;-9.81];
  42. % predict states
  43. [quat, states, Tbn, delAng, delVel] = PredictStates(quat,states,angRate,accel,dt);
  44. statesLog(1,index) = time;
  45. statesLog(2:10,index) = states;
  46. eulLog(1,index) = time;
  47. eulLog(2:4,index) = QuatToEul(quat);
  48. % predict covariance matrix
  49. covariance = PredictCovariance(delAng,delVel,quat,states,covariance,dt);
  50. % synthesise velocity measurements
  51. measVel = [0;0;0];
  52. % fuse velocity measurements
  53. [quat,states,angErr,covariance,velInnov,velInnovVar] = FuseVelocity(quat,states,covariance,measVel);
  54. velInnovLog(1,index) = time;
  55. velInnovLog(2:4,index) = velInnov;
  56. velInnovVarLog(1,index) = time;
  57. velInnovVarLog(2:4,index) = velInnovVar;
  58. angErrLog(1,index) = time;
  59. angErrLog(2,index) = angErr;
  60. % synthesise magnetometer measurements adding sensor bias
  61. magBody = transpose(TbnTruth)*magEarthTruth + magMeasBias;
  62. % fuse magnetometer measurements
  63. if (index > 500 && headingAligned==0 && angErr < 1e-4)
  64. quat = AlignHeading(quat,magBody,measDec);
  65. headingAligned = 1;
  66. end
  67. if (headingAligned == 1)
  68. [quat,states,covariance,decInnov,decInnovVar] = FuseMagnetometer(quat,states,covariance,magBody,measDec,Tbn);
  69. decInnovLog(1,index) = time;
  70. decInnovLog(2,index) = decInnov;
  71. decInnovVarLog(1,index) = time;
  72. decInnovVarLog(2,index) = decInnovVar;
  73. end
  74. end
  75. %% Generate Plots
  76. PlotData;