From 103da0c88940fde062353add24ff43cf5a46d3ba Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 11 Dec 2013 15:22:35 +1100 Subject: [PATCH] Plane: when no GPS lock always send GPS messages --- ArduPlane/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 3eb1b12d27..72f9a6c034 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -293,7 +293,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) static void NOINLINE send_gps_raw(mavlink_channel_t chan) { static uint32_t last_send_time; - if (last_send_time != 0 && last_send_time == g_gps->last_fix_time) { + if (last_send_time != 0 && last_send_time == g_gps->last_fix_time && g_gps->status() >= GPS::GPS_OK_FIX_3D) { return; } last_send_time = g_gps->last_fix_time;