Browse Source

AP_NavEKF3: fixed bug in external yaw for fixed wing

when we are on the ground we should not chang to AID_NONE if we have
an external yaw source

this fixes an EKF3 error loop on the ground found by Michael
c415-sdk
Andrew Tridgell 4 years ago
parent
commit
fcccdcc936
  1. 2
      libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp

2
libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp

@ -289,7 +289,7 @@ void NavEKF3_core::setAidingMode() @@ -289,7 +289,7 @@ void NavEKF3_core::setAidingMode()
// This is a special case for when we are a fixed wing aircraft vehicle that has landed and
// has no yaw measurement that works when static. Declare the yaw as unaligned (unknown)
// and declare attitude aiding loss so that we fall back into a non-aiding mode
if (assume_zero_sideslip() && onGround && !use_compass()){
if (assume_zero_sideslip() && onGround && !use_compass() && !using_external_yaw()) {
yawAlignComplete = false;
finalInflightYawInit = false;
attAidLossCritical = true;

Loading…
Cancel
Save