From 031e5b1dabdc2b6cd3ebaf598f9370fbb2a0b1c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:28:08 +1100 Subject: [PATCH] GCS_MAVLink: tidy sending of WATER_DEPTH messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 0d22beaa91..9956d53370 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1045,7 +1045,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #if HAL_WITH_ESC_TELEM { MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, MSG_ESC_TELEMETRY}, #endif -#if APM_BUILD_TYPE(APM_BUILD_Rover) +#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover) { MAVLINK_MSG_ID_WATER_DEPTH, MSG_WATER_DEPTH}, #endif #if HAL_HIGH_LATENCY2_ENABLED @@ -6028,12 +6028,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; #endif - case MSG_WATER_DEPTH: #if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover) + case MSG_WATER_DEPTH: CHECK_PAYLOAD_SIZE(WATER_DEPTH); send_water_depth(); -#endif break; +#endif case MSG_HIGH_LATENCY2: #if HAL_HIGH_LATENCY2_ENABLED