AP_NavEKF3: initialize stateStruct.quat to unit length

This commit is contained in:
Josh Henderson 2021-07-09 00:02:13 -04:00 committed by Peter Barker
parent 9a274ba565
commit 67eb6d17eb

View File

@ -465,6 +465,7 @@ void NavEKF3_core::InitialiseVariablesMag()
magYawResetRequest = false; magYawResetRequest = false;
posDownAtLastMagReset = stateStruct.position.z; posDownAtLastMagReset = stateStruct.position.z;
yawInnovAtLastMagReset = 0.0f; yawInnovAtLastMagReset = 0.0f;
stateStruct.quat.initialise();
quatAtLastMagReset = stateStruct.quat; quatAtLastMagReset = stateStruct.quat;
magFieldLearned = false; magFieldLearned = false;
storedMag.reset(); storedMag.reset();