Browse Source

AP_NavEKF3: initialize stateStruct.quat to unit length

gps-1.3.1
Josh Henderson 4 years ago committed by Peter Barker
parent
commit
67eb6d17eb
  1. 1
      libraries/AP_NavEKF3/AP_NavEKF3_core.cpp

1
libraries/AP_NavEKF3/AP_NavEKF3_core.cpp

@ -465,6 +465,7 @@ void NavEKF3_core::InitialiseVariablesMag() @@ -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…
Cancel
Save