From fbbadecfe3d5dfef2f15df0a7f07e622039a41e0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 25 Oct 2023 15:23:59 +1100 Subject: [PATCH] GCS_MAVLink: tidy use of GPS mavlink defines --- libraries/GCS_MAVLink/GCS_Common.cpp | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index c0bb9a442f..f45c758db0 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3069,10 +3069,14 @@ float GCS_MAVLINK::vfr_hud_airspeed() const } #endif +#if AP_GPS_ENABLED // because most vehicles don't have airspeed sensors, we return a // different sort of speed estimate in the relevant field for // comparison's sake. return AP::gps().ground_speed(); +#endif + + return 0.0; } float GCS_MAVLINK::vfr_hud_climbrate() const @@ -3977,12 +3981,14 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) break; #endif +#if AP_GPS_ENABLED case MAVLINK_MSG_ID_GPS_RTCM_DATA: case MAVLINK_MSG_ID_GPS_INPUT: case MAVLINK_MSG_ID_HIL_GPS: case MAVLINK_MSG_ID_GPS_INJECT_DATA: AP::gps().handle_msg(msg); break; +#endif case MAVLINK_MSG_ID_STATUSTEXT: handle_statustext(msg); @@ -5760,6 +5766,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) CHECK_PAYLOAD_SIZE(SYSTEM_TIME); send_system_time(); break; +#if AP_GPS_ENABLED case MSG_GPS_RAW: CHECK_PAYLOAD_SIZE(GPS_RAW_INT); AP::gps().send_mavlink_gps_raw(chan); @@ -5768,18 +5775,19 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) CHECK_PAYLOAD_SIZE(GPS_RTK); AP::gps().send_mavlink_gps_rtk(chan, 0); break; - case MSG_GPS2_RAW: #if GPS_MAX_RECEIVERS > 1 + case MSG_GPS2_RAW: CHECK_PAYLOAD_SIZE(GPS2_RAW); AP::gps().send_mavlink_gps2_raw(chan); -#endif break; - case MSG_GPS2_RTK: +#endif #if GPS_MAX_RECEIVERS > 1 + case MSG_GPS2_RTK: CHECK_PAYLOAD_SIZE(GPS2_RTK); AP::gps().send_mavlink_gps_rtk(chan, 1); -#endif break; +#endif +#endif // AP_GPS_ENABLED case MSG_LOCAL_POSITION: CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED); send_local_position();