AP_NavEKF2: initialize stateStruct.quat to unit length

This commit is contained in:
Josh Henderson 2021-07-09 00:01:32 -04:00 committed by Peter Barker
parent 9b74452270
commit 9a274ba565

View File

@ -238,6 +238,7 @@ void NavEKF2_core::InitialiseVariables()
runUpdates = false;
framesSincePredict = 0;
gpsYawResetRequest = false;
stateStruct.quat.initialise();
quatAtLastMagReset = stateStruct.quat;
delAngBiasLearned = false;
memset(&filterStatus, 0, sizeof(filterStatus));