AP_NavEKF: Do not perform start-up yaw alignment if no compass

Yaw cannot be aligned until in-flight when there is sufficient GPS velocity.
This commit is contained in:
Paul Riseborough 2016-05-21 11:18:29 +10:00 committed by Andrew Tridgell
parent d2694fe5dc
commit 08de4e6d95

View File

@ -172,7 +172,7 @@ void NavEKF2_core::checkAttitudeAlignmentStatus()
}
// Once tilt has converged, align yaw using magnetic field measurements
if (tiltAlignComplete && !yawAlignComplete) {
if (tiltAlignComplete && !yawAlignComplete && use_compass()) {
Vector3f eulerAngles;
stateStruct.quat.to_euler(eulerAngles.x, eulerAngles.y, eulerAngles.z);
stateStruct.quat = calcQuatAndFieldStates(eulerAngles.x, eulerAngles.y);