From a8906ac491914a70987874b61cd3161a224675b3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:26:20 +1100 Subject: [PATCH] GCS_MAVLink: tidy sending of winch messages --- libraries/GCS_MAVLink/GCS.h | 3 +++ libraries/GCS_MAVLink/GCS_Common.cpp | 2 ++ 2 files changed, 5 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index e512ed7312..f12853064f 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -24,6 +24,7 @@ #include #include #include +#include #include "ap_message.h" @@ -385,7 +386,9 @@ public: void send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc); void send_rpm() const; void send_generator_status() const; +#if AP_WINCH_ENABLED virtual void send_winch_status() const {}; +#endif void send_water_depth() const; int8_t battery_remaining_pct(const uint8_t instance) const; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 06a3c0fdb9..0d22beaa91 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -6021,10 +6021,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) } #endif +#if AP_WINCH_ENABLED case MSG_WINCH_STATUS: CHECK_PAYLOAD_SIZE(WINCH_STATUS); send_winch_status(); break; +#endif case MSG_WATER_DEPTH: #if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover)