diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 97e03468be..87ec744660 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -301,7 +301,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan) g_gps->ground_course_cd, // 1/100 degrees, g_gps->num_sats); #if GPS2_ENABLE - if (g_gps2 != NULL) { + if (g_gps2 != NULL && g_gps2->status() != GPS::NO_GPS) { int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES; if (payload_space >= MAVLINK_MSG_ID_GPS2_RAW_LEN) { mavlink_msg_gps2_raw_send(