AP_NavEKF2: initialize stateStruct.quat to unit length
This commit is contained in:
parent
9b74452270
commit
9a274ba565
@ -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));
|
||||
|
Loading…
Reference in New Issue
Block a user