diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 3a69c4eb3d..b1b345dea3 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -499,7 +499,7 @@ void NavEKF::UpdateFilter() OnGroundCheck(); // Define rules used to set staticMode - if (onGround && !_ahrs->get_correct_centrifugal()) { + if (onGround && static_mode_demanded()) { staticMode = true; } else { staticMode = false; @@ -2231,7 +2231,7 @@ void NavEKF::getGyroBias(Vector3f &gyroBias) const void NavEKF::getAccelBias(Vector3f &accelBias) const { accelBias.x = staticMode? 1.0f : 0.0f; - accelBias.y = _ahrs->get_correct_centrifugal()? 0.0f : 1.0f; + accelBias.y = static_mode_demanded()? 1.0f : 0.0f; accelBias.z = states[13] / dtIMU; } @@ -2659,4 +2659,12 @@ bool NavEKF::useAirspeed(void) const return _ahrs->get_airspeed()->use(); } +/* + see if the vehicle code has demanded static mode + */ +bool NavEKF::static_mode_demanded(void) const +{ + return !_ahrs->get_armed() || !_ahrs->get_correct_centrifugal(); +} + #endif // HAL_CPU_CLASS diff --git a/libraries/AP_NavEKF/AP_NavEKF.h b/libraries/AP_NavEKF/AP_NavEKF.h index 63721b13e7..7ecb419369 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.h +++ b/libraries/AP_NavEKF/AP_NavEKF.h @@ -255,6 +255,9 @@ private: // return true if we should use the airspeed sensor bool useAirspeed(void) const; + // check if static mode has been demanded by vehicle code + bool static_mode_demanded(void) const; + private: // EKF Mavlink Tuneable Parameters AP_Float _gpsHorizVelNoise; // GPS horizontal velocity measurement noise : m/s