From bddeac0de6dcfc76ab937cc3ecb9395cbba05ba2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 29 Apr 2025 16:57:23 +1000 Subject: [PATCH] Rover: allow sending of rangefinder mavlink message to be compiled out --- Rover/GCS_MAVLink_Rover.cpp | 4 +++- Rover/GCS_MAVLink_Rover.h | 4 +++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/Rover/GCS_MAVLink_Rover.cpp b/Rover/GCS_MAVLink_Rover.cpp index bd5acfb65b..58294e9e8c 100644 --- a/Rover/GCS_MAVLink_Rover.cpp +++ b/Rover/GCS_MAVLink_Rover.cpp @@ -155,7 +155,7 @@ int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const return rover.g2.motors.get_throttle(); } -#if AP_RANGEFINDER_ENABLED +#if AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED void GCS_MAVLINK_Rover::send_rangefinder() const { float distance = 0; @@ -185,7 +185,9 @@ void GCS_MAVLINK_Rover::send_rangefinder() const distance, voltage); } +#endif // AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED +#if AP_RANGEFINDER_ENABLED void GCS_MAVLINK_Rover::send_water_depth() { if (!HAVE_PAYLOAD_SPACE(chan, WATER_DEPTH)) { diff --git a/Rover/GCS_MAVLink_Rover.h b/Rover/GCS_MAVLink_Rover.h index 24c7a4acf3..61006e1da1 100644 --- a/Rover/GCS_MAVLink_Rover.h +++ b/Rover/GCS_MAVLink_Rover.h @@ -61,9 +61,11 @@ private: int16_t vfr_hud_throttle() const override; -#if AP_RANGEFINDER_ENABLED +#if AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED void send_rangefinder() const override; +#endif // AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED +#if AP_RANGEFINDER_ENABLED // send WATER_DEPTH - metres and temperature void send_water_depth(); // state variable for the last rangefinder we sent a WATER_DEPTH