AP_NavEKF3: Reset states when falling back into non aiding mode.

This commit is contained in:
Paul Riseborough 2020-12-12 10:52:01 +11:00 committed by Andrew Tridgell
parent b92eca7b66
commit ddadc45854

View File

@ -217,6 +217,9 @@ void NavEKF3_core::setAidingMode()
PV_AidingMode = AID_NONE;
yawAlignComplete = false;
finalInflightYawInit = false;
ResetVelocity(resetDataSource::DEFAULT);
ResetPosition(resetDataSource::DEFAULT);
ResetHeight();
}
// Determine if we should change aiding mode