AP_NavEKF3: Fix initialisation of state inhibit flags

This commit is contained in:
priseborough 2017-05-10 07:38:45 +10:00 committed by Francisco Ferreira
parent 36e7dfb5f6
commit 0cba133a1e
1 changed files with 2 additions and 0 deletions

View File

@ -233,6 +233,8 @@ void NavEKF3_core::InitialiseVariables()
manoeuvring = false;
inhibitWindStates = true;
inhibitMagStates = true;
inhibitDelVelBiasStates = true;
inhibitDelAngBiasStates = true;
gndOffsetValid = false;
validOrigin = false;
takeoffExpectedSet_ms = 0;