orien.m 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124
  1. % This is an Extended Kalman Filter which fuses
  2. % accelerometer & gyroscope readings
  3. % to get the orientation.
  4. % Written by @TanTanTan
  5. % Note that we assume the biases of IMU do not change in the whole
  6. % process. This is approximately true when the sensors operate in a steady
  7. % state.
  8. clear; close all; clc;
  9. %--- Dataset parameters
  10. deltat = 1/200; % Sampling period
  11. noise_gyro = 2.4e-3; % Gyroscope noise(discrete), rad/s
  12. noise_accel = 2.83e-2; % Accelerometer noise, m/s^2
  13. gravity = 9.81007; % Gravity magnitude, m/s^2
  14. %--- Load data
  15. % Each row of IMU data :
  16. % (timestamp, wx, wy, wz, ax, ay, az)
  17. % Each row of Ground truth data :
  18. % (time, position, quaternion, velocity, gyroscope bias, accelerometer bias)
  19. data = load('data/attitude_data.mat');
  20. imu_data = data.imu_data; % IMU readings
  21. grt_data = data.grt_data; % Ground truth (GT)
  22. grt_q = grt_data(:, 5:8); % GT quaternions
  23. bias_w = grt_data(1, 12:14); % gyroscope bias
  24. bias_a = grt_data(1, 15:17); % accelerometer bias
  25. %--- Container of the results
  26. N = length(imu_data);
  27. allX = zeros(N, 4);
  28. %--- Initialization
  29. x = grt_q(1,:)'; % Initial state (quaternion)
  30. P = 1e-10 * eye(4); % Initial covariance
  31. allX(1,:) = x';
  32. % ---Here we go !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
  33. for k = 2 : N
  34. %--- 1. Propagation --------------------------
  35. % Gyroscope measurements
  36. w = (imu_data(k-1, 2:4) + imu_data(k, 2:4))/2;
  37. w = w - bias_w;
  38. % Compute the F matrix
  39. Omega =[0 -w(1) -w(2) -w(3);...
  40. w(1) 0 w(3) -w(2); ...
  41. w(2) -w(3) 0 w(1); ...
  42. w(3) w(2) -w(1) 0 ];
  43. F = eye(4) + deltat * Omega / 2;
  44. % Compute the process noise Q
  45. G = [-x(2) -x(3) -x(4); ...
  46. x(1) -x(4) x(3); ...
  47. x(4) x(1) -x(2); ...
  48. -x(3) x(2) x(1)] / 2;
  49. Q = (noise_gyro * deltat)^2 * (G * G');
  50. % Propagate the state and covariance
  51. x = F * x;
  52. x = x / norm(x); % Normalize the quaternion
  53. P = F * P * F' + Q;
  54. %--- 2. Update----------------------------------
  55. % Accelerometer measurements
  56. a = imu_data(k, 5:7);
  57. a = a - bias_a;
  58. % We use the unit vector of acceleration as observation
  59. ea = a' / norm(a);
  60. ea_prediction = [2*(x(2)*x(4)-x(1)*x(3)); ...
  61. 2*(x(3)*x(4)+x(1)*x(2)); ...
  62. x(1)^2-x(2)^2-x(3)^2+x(4)^2];
  63. % Residual
  64. y = ea - ea_prediction;
  65. % Compute the measurement matrix H
  66. H = 2*[-x(3) x(4) -x(1) x(2); ...
  67. x(2) x(1) x(4) x(3); ...
  68. x(1) -x(2) -x(3) x(4)];
  69. % Measurement noise R
  70. R_internal = (noise_accel / norm(a))^2 * eye(3);
  71. R_external = (1-gravity/norm(a))^2 * eye(3);
  72. R = R_internal + R_external;
  73. % Update
  74. S = H * P * H' + R;
  75. K = P * H' / S;
  76. x = x + K * y;
  77. P = (eye(4) - K * H) * P;
  78. % 3. Ending
  79. x = x / norm(x); % Normalize the quaternion
  80. P = (P + P') / 2; % Make sure that covariance matrix is symmetric
  81. allX(k,:) = x'; % Save the result
  82. end
  83. %--- Compare the results with ground truth
  84. q_Ws0 = quatinv(grt_q(1,:));
  85. for i=1:N
  86. grt_q(i,:) = quatmultiply(q_Ws0, grt_q(i,:));
  87. allX(i,:) = quatmultiply(q_Ws0, allX(i,:));
  88. end
  89. [psi, theta, phi] = quat2angle(allX);
  90. [grt_psi, grt_theta, grt_phi] = quat2angle(grt_q);
  91. figure, hold on
  92. plot(1:N, psi, 'r-.', 1:N, grt_psi, 'r');
  93. plot(1:N, theta, 'g-.', 1:N, grt_theta, 'g');
  94. plot(1:N, phi, 'b-.', 1:N, grt_phi, 'b');