Browse Source

AP_NavEKF3: simplify logic when updating yawAngDataStatic

zr-v5.1
Randy Mackay 4 years ago committed by Peter Barker
parent
commit
c2edae905f
  1. 5
      libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp

5
libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp

@ -208,13 +208,10 @@ void NavEKF3_core::SelectMagFusion() @@ -208,13 +208,10 @@ void NavEKF3_core::SelectMagFusion()
if (fabsf(prevTnb[0][2]) < fabsf(prevTnb[1][2])) {
// A 321 rotation order is best conditioned because the X axis is closer to horizontal than the Y axis
yawAngDataStatic.order = rotationOrder::TAIT_BRYAN_321;
yawAngDataStatic.yawAng = atan2f(prevTnb[0][1], prevTnb[0][0]);
} else {
// A 312 rotation order is best conditioned because the Y axis is closer to horizontal than the X axis
yawAngDataStatic.order = rotationOrder::TAIT_BRYAN_312;
}
if (yawAngDataStatic.order == rotationOrder::TAIT_BRYAN_321) {
yawAngDataStatic.yawAng = atan2f(prevTnb[0][1], prevTnb[0][0]);
} else if (yawAngDataStatic.order == rotationOrder::TAIT_BRYAN_312) {
yawAngDataStatic.yawAng = atan2f(-prevTnb[1][0], prevTnb[1][1]);
}
yawAngDataStatic.yawAngErr = MAX(frontend->_yawNoise, 0.05f);

Loading…
Cancel
Save