AlignHeading.m 1.5 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647
  1. function quat = AlignHeading( ...
  2. quat, ... % quaternion state vector
  3. magMea, ... % body frame magnetic flux measurements
  4. declination) % Estimated magnetic field delination at current location
  5. % Calculate the predicted magnetic declination
  6. Tbn = Quat2Tbn(quat);
  7. magMeasNED = Tbn*magMea;
  8. predDec = atan2(magMeasNED(2),magMeasNED(1));
  9. % Calculate the measurement innovation
  10. innovation = predDec - declination;
  11. if (innovation > pi)
  12. innovation = innovation - 2*pi;
  13. elseif (innovation < -pi)
  14. innovation = innovation + 2*pi;
  15. end
  16. % form the NED rotation vector
  17. deltaRotNED = -[0;0;innovation];
  18. % rotate into body axes
  19. % Calculate the body to nav cosine matrix
  20. Tbn = Quat2Tbn(quat);
  21. deltaRotBody = transpose(Tbn)*deltaRotNED;
  22. % Convert the error rotation vector to its equivalent quaternion
  23. % error = truth - estimate
  24. rotationMag = abs(innovation);
  25. if rotationMag<1e-6
  26. deltaQuat = single([1;0;0;0]);
  27. else
  28. deltaQuat = [cos(0.5*rotationMag); [deltaRotBody(1);deltaRotBody(2);deltaRotBody(3)]/rotationMag*sin(0.5*rotationMag)];
  29. end
  30. % Update the quaternion states by rotating from the previous attitude through
  31. % the delta angle rotation quaternion
  32. quat = [quat(1)*deltaQuat(1)-transpose(quat(2:4))*deltaQuat(2:4); quat(1)*deltaQuat(2:4) + deltaQuat(1)*quat(2:4) + cross(quat(2:4),deltaQuat(2:4))];
  33. % normalise the updated quaternion states
  34. quatMag = sqrt(quat(1)^2 + quat(2)^2 + quat(3)^2 + quat(4)^2);
  35. if (quatMag > 1e-12)
  36. quat = quat / quatMag;
  37. end
  38. end