From 2ac9cc94c65bc48143d39901bc1ff79f76c7e084 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 26 Oct 2023 10:05:11 +1100 Subject: [PATCH] GCS_MAVLink: correct compilation if rangefinder disabled --- libraries/GCS_MAVLink/GCS.h | 3 +++ libraries/GCS_MAVLink/GCS_Common.cpp | 17 ++++++++++++++--- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index f695999aff..5941a2e46f 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -23,6 +23,7 @@ #include #include #include +#include #include "ap_message.h" @@ -338,7 +339,9 @@ public: void send_distance_sensor(); // send_rangefinder sends only if a downward-facing instance is // found. Rover overrides this! +#if AP_RANGEFINDER_ENABLED virtual void send_rangefinder() const; +#endif void send_proximity(); virtual void send_nav_controller_output() const = 0; virtual void send_pid_tuning() = 0; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index f45c758db0..697cde517a 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -378,6 +378,7 @@ bool GCS_MAVLINK::send_battery_status() } #endif // AP_BATTERY_ENABLED +#if AP_RANGEFINDER_ENABLED void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor, const uint8_t instance) const { if (!sensor->has_data()) { @@ -408,11 +409,14 @@ void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor, con (const float *)nullptr, // quaternion of sensor orientation for MAV_SENSOR_ROTATION_CUSTOM quality); // Signal quality of the sensor. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal. } +#endif // AP_RANGEFINDER_ENABLED + // send any and all distance_sensor messages. This starts by sending // any distance sensors not used by a Proximity sensor, then sends the // proximity sensor ones. void GCS_MAVLINK::send_distance_sensor() { +#if AP_RANGEFINDER_ENABLED RangeFinder *rangefinder = RangeFinder::get_singleton(); if (rangefinder == nullptr) { return; @@ -450,12 +454,14 @@ void GCS_MAVLINK::send_distance_sensor() send_distance_sensor(sensor, i); } } +#endif // AP_RANGEFINDER_ENABLED #if HAL_PROXIMITY_ENABLED send_proximity(); #endif } +#if AP_RANGEFINDER_ENABLED void GCS_MAVLINK::send_rangefinder() const { RangeFinder *rangefinder = RangeFinder::get_singleton(); @@ -471,6 +477,7 @@ void GCS_MAVLINK::send_rangefinder() const s->distance(), s->voltage_mv() * 0.001f); } +#endif #if HAL_PROXIMITY_ENABLED void GCS_MAVLINK::send_proximity() @@ -3782,10 +3789,12 @@ void GCS_MAVLINK::handle_can_frame(const mavlink_message_t &msg) const void GCS_MAVLINK::handle_distance_sensor(const mavlink_message_t &msg) { +#if AP_RANGEFINDER_ENABLED RangeFinder *rangefinder = AP::rangefinder(); if (rangefinder != nullptr) { rangefinder->handle_msg(msg); } +#endif #if HAL_PROXIMITY_ENABLED AP_Proximity *proximity = AP::proximity(); @@ -5478,7 +5487,7 @@ void GCS_MAVLINK::send_generator_status() const } #endif -#if APM_BUILD_TYPE(APM_BUILD_Rover) +#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover) void GCS_MAVLINK::send_water_depth() const { if (!HAVE_PAYLOAD_SPACE(chan, WATER_DEPTH)) { @@ -5527,7 +5536,7 @@ void GCS_MAVLINK::send_water_depth() const } } -#endif +#endif // AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover) #if HAL_ADSB_ENABLED void GCS_MAVLINK::send_uavionix_adsb_out_status() const @@ -5720,10 +5729,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; #endif +#if AP_RANGEFINDER_ENABLED case MSG_RANGEFINDER: CHECK_PAYLOAD_SIZE(RANGEFINDER); send_rangefinder(); break; +#endif case MSG_DISTANCE_SENSOR: send_distance_sensor(); @@ -5990,7 +6001,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; case MSG_WATER_DEPTH: -#if APM_BUILD_TYPE(APM_BUILD_Rover) +#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover) CHECK_PAYLOAD_SIZE(WATER_DEPTH); send_water_depth(); #endif