mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_NavEKF3: initialize stateStruct.quat to unit length
This commit is contained in:
parent
9a274ba565
commit
67eb6d17eb
@ -465,6 +465,7 @@ void NavEKF3_core::InitialiseVariablesMag()
|
||||
magYawResetRequest = false;
|
||||
posDownAtLastMagReset = stateStruct.position.z;
|
||||
yawInnovAtLastMagReset = 0.0f;
|
||||
stateStruct.quat.initialise();
|
||||
quatAtLastMagReset = stateStruct.quat;
|
||||
magFieldLearned = false;
|
||||
storedMag.reset();
|
||||
|
Loading…
Reference in New Issue
Block a user