AlignHeading.m 1.7 KB

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