From ee1ce32eada33431e65b055c9cf64d9b087627a8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 2 Sep 2023 15:21:33 +1000 Subject: [PATCH] AC_Avoidance: allow more libraries to compile with no HAL_GCS_ENABLED --- libraries/AC_Avoidance/AP_OADatabase.cpp | 4 +++- libraries/AC_Avoidance/AP_OADijkstra.cpp | 3 ++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Avoidance/AP_OADatabase.cpp b/libraries/AC_Avoidance/AP_OADatabase.cpp index cb0153fbbe..cc8dacab1b 100644 --- a/libraries/AC_Avoidance/AP_OADatabase.cpp +++ b/libraries/AC_Avoidance/AP_OADatabase.cpp @@ -125,7 +125,7 @@ void AP_OADatabase::init() dist_to_radius_scalar = tanf(radians(MAX(_beam_width, 1.0f))); if (!healthy()) { - gcs().send_text(MAV_SEVERITY_INFO, "DB init failed . Sizes queue:%u, db:%u", (unsigned int)_queue.size, (unsigned int)_database.size); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "DB init failed . Sizes queue:%u, db:%u", (unsigned int)_queue.size, (unsigned int)_database.size); delete _queue.items; delete[] _database.items; return; @@ -365,6 +365,7 @@ bool AP_OADatabase::is_close_to_item_in_database(const uint16_t index, const OA_ return ((distance_sq < sq(item.radius)) || (distance_sq < sq(_database.items[index].radius))); } +#if HAL_GCS_ENABLED // send ADSB_VEHICLE mavlink messages void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms) { @@ -469,6 +470,7 @@ void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ num_sent++; } } +#endif // HAL_GCS_ENABLED // singleton instance AP_OADatabase *AP_OADatabase::_singleton; diff --git a/libraries/AC_Avoidance/AP_OADijkstra.cpp b/libraries/AC_Avoidance/AP_OADijkstra.cpp index 6ebca1e0fc..a15604c43b 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.cpp +++ b/libraries/AC_Avoidance/AP_OADijkstra.cpp @@ -247,7 +247,8 @@ void AP_OADijkstra::report_error(AP_OADijkstra_Error error_id) if ((error_id != AP_OADijkstra_Error::DIJKSTRA_ERROR_NONE) && ((error_id != _error_last_id) || ((now_ms - _error_last_report_ms) > OA_DIJKSTRA_ERROR_REPORTING_INTERVAL_MS))) { const char* error_msg = get_error_msg(error_id); - gcs().send_text(MAV_SEVERITY_CRITICAL, "Dijkstra: %s", error_msg); + (void)error_msg; // in case !HAL_GCS_ENABLED + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Dijkstra: %s", error_msg); _error_last_id = error_id; _error_last_report_ms = now_ms; }