mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF: force healthy false when initialising
this prevents us feeding off our own values when booting Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
This commit is contained in:
parent
be33a9634e
commit
c6b24c521b
@ -315,6 +315,10 @@ void NavEKF::ResetHeight(void)
|
||||
|
||||
void NavEKF::InitialiseFilterDynamic(void)
|
||||
{
|
||||
// this forces healthy() to be false so that when we ask for ahrs
|
||||
// attitude we get the DCM attitude regardless of the state of AHRS_EKF_USE
|
||||
statesInitialised = false;
|
||||
|
||||
// Set re-used variables to zero
|
||||
ZeroVariables();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user