From c32d323cd681f3fcbce378329555079be9a96724 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Tue, 3 Nov 2015 11:46:46 -0200 Subject: [PATCH] GCS_MAVLink: remove check for GPS_RTK_AVAILABLE --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index c5365c4330..3fb0d8e723 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -914,14 +914,12 @@ bool GCS_MAVLINK::send_gps_raw(AP_GPS &gps) return false; } -#if GPS_RTK_AVAILABLE if (gps.highest_supported_status(0) > AP_GPS::GPS_OK_FIX_3D) { if (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_GPS_RTK_LEN) { gps.send_mavlink_gps_rtk(chan); } } -#endif if (gps.num_sensors() > 1 && gps.status(1) > AP_GPS::NO_GPS) { @@ -929,14 +927,12 @@ bool GCS_MAVLINK::send_gps_raw(AP_GPS &gps) gps.send_mavlink_gps2_raw(chan); } -#if GPS_RTK_AVAILABLE if (gps.highest_supported_status(1) > AP_GPS::GPS_OK_FIX_3D) { if (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_GPS2_RTK_LEN) { gps.send_mavlink_gps2_rtk(chan); } } -#endif } //TODO: Should check what else managed to get through...