From 369c130c2d0569d12132a4893be6066eec4d3c9f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Jan 2014 09:02:22 +1100 Subject: [PATCH] Plane: consider GPS unhealthy if it doesn't have 3D lock --- 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 4eb42d2d21..93b201fdd8 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -209,7 +209,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) if (g.compass_enabled && compass.healthy() && ahrs.use_compass()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG; } - if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) { + if (g_gps != NULL && g_gps->status() >= GPS::GPS_OK_FIX_3D) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS; } if (!ins.healthy()) {