Plane: consider GPS unhealthy if it doesn't have 3D lock

This commit is contained in:
Andrew Tridgell 2014-01-27 09:02:22 +11:00
parent 214a859e97
commit 369c130c2d
1 changed files with 1 additions and 1 deletions

View File

@ -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()) {