mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF3: Reset states when falling back into non aiding mode.
This commit is contained in:
parent
b92eca7b66
commit
ddadc45854
@ -217,6 +217,9 @@ void NavEKF3_core::setAidingMode()
|
||||
PV_AidingMode = AID_NONE;
|
||||
yawAlignComplete = false;
|
||||
finalInflightYawInit = false;
|
||||
ResetVelocity(resetDataSource::DEFAULT);
|
||||
ResetPosition(resetDataSource::DEFAULT);
|
||||
ResetHeight();
|
||||
}
|
||||
|
||||
// Determine if we should change aiding mode
|
||||
|
Loading…
Reference in New Issue
Block a user