diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp index 59145351b7..e03947b2b5 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp @@ -409,6 +409,9 @@ bool NavEKF3_core::InitialiseFilterBootstrap(void) { // If we are a plane and don't have GPS lock then don't initialise if (assume_zero_sideslip() && AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) { + hal.util->snprintf(prearm_fail_string, + sizeof(prearm_fail_string), + "EKF3 init failure: No GPS lock"); statesInitialised = false; return false; }