PlotData.m 1.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465
  1. %% plot gyro bias estimates
  2. figure;
  3. plot(EKFlogs.time,EKFlogs.states(7:9,:)/dtSlow*180/pi);
  4. grid on;
  5. ylabel('Gyro Bias Estimate (deg/sec)');
  6. xlabel('time (sec)');
  7. hold on;
  8. plot([min(time),max(time)],[gyroBias,gyroBias]*180/pi);
  9. hold off;
  10. %% plot velocity
  11. figure;
  12. plot(EKFlogs.time,EKFlogs.states(4:6,:));
  13. grid on;
  14. ylabel('Velocity (m/sec)');
  15. xlabel('time (sec)');
  16. %% calculate and plot tilt correction magnitude
  17. figure;
  18. plot(EKFlogs.time,EKFlogs.tiltCorr);
  19. grid on;
  20. ylabel('Tilt Correction Magnitude (rad)');
  21. xlabel('time (sec)');
  22. %% plot velocity innovations
  23. figure;
  24. subplot(3,1,1);plot(EKFlogs.time,[EKFlogs.velInnov(1,:);sqrt(EKFlogs.velInnovVar(1,:));-sqrt(EKFlogs.velInnovVar(1,:))]');
  25. grid on;
  26. ylabel('VelN Innovations (m)');
  27. subplot(3,1,2);plot(EKFlogs.time,[EKFlogs.velInnov(2,:);sqrt(EKFlogs.velInnovVar(2,:));-sqrt(EKFlogs.velInnovVar(2,:))]');
  28. grid on;
  29. ylabel('VelE Innovations (m)');
  30. subplot(3,1,3);plot(EKFlogs.time,[EKFlogs.velInnov(3,:);sqrt(EKFlogs.velInnovVar(3,:));-sqrt(EKFlogs.velInnovVar(3,:))]');
  31. grid on;
  32. ylabel('VelD Innovations (m)');
  33. xlabel('time (sec)');
  34. %% plot compass innovations
  35. figure;
  36. plot(EKFlogs.time,[EKFlogs.decInnov;sqrt(EKFlogs.decInnovVar);-sqrt(EKFlogs.decInnovVar)]');
  37. grid on;
  38. ylabel('Compass Innovations (rad)');
  39. xlabel('time (sec)');
  40. %% plot Euler angle estimates
  41. figure;
  42. subplot(3,1,1);plot(gimbal.time,gimbal.euler(1,:)*180/pi);
  43. ylabel('Roll (deg)');grid on;
  44. subplot(3,1,2);plot(gimbal.time,gimbal.euler(2,:)*180/pi);
  45. ylabel('Pitch (deg)');grid on;
  46. subplot(3,1,3);plot(gimbal.time,gimbal.euler(3,:)*180/pi);
  47. ylabel('Yaw (deg)');
  48. grid on;
  49. xlabel('time (sec)');
  50. %% plot Euler angle error estimates
  51. figure;
  52. subplot(3,1,1);plot(gimbal.time,gimbal.eulerError(1,:)*180/pi);
  53. ylabel('Roll Error (deg)');grid on;
  54. subplot(3,1,2);plot(gimbal.time,gimbal.eulerError(2,:)*180/pi);
  55. ylabel('Pitch Error (deg)');grid on;
  56. subplot(3,1,3);plot(gimbal.time,gimbal.eulerError(3,:)*180/pi);
  57. ylabel('Yaw Error (deg)');
  58. grid on;
  59. xlabel('time (sec)');