mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_Avoidance: allow more libraries to compile with no HAL_GCS_ENABLED
This commit is contained in:
parent
4ce65bb3f7
commit
ee1ce32ead
@ -125,7 +125,7 @@ void AP_OADatabase::init()
|
|||||||
dist_to_radius_scalar = tanf(radians(MAX(_beam_width, 1.0f)));
|
dist_to_radius_scalar = tanf(radians(MAX(_beam_width, 1.0f)));
|
||||||
|
|
||||||
if (!healthy()) {
|
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 _queue.items;
|
||||||
delete[] _database.items;
|
delete[] _database.items;
|
||||||
return;
|
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)));
|
return ((distance_sq < sq(item.radius)) || (distance_sq < sq(_database.items[index].radius)));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
// send ADSB_VEHICLE mavlink messages
|
// send ADSB_VEHICLE mavlink messages
|
||||||
void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms)
|
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++;
|
num_sent++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // HAL_GCS_ENABLED
|
||||||
|
|
||||||
// singleton instance
|
// singleton instance
|
||||||
AP_OADatabase *AP_OADatabase::_singleton;
|
AP_OADatabase *AP_OADatabase::_singleton;
|
||||||
|
@ -247,7 +247,8 @@ void AP_OADijkstra::report_error(AP_OADijkstra_Error error_id)
|
|||||||
if ((error_id != AP_OADijkstra_Error::DIJKSTRA_ERROR_NONE) &&
|
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))) {
|
((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);
|
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_id = error_id;
|
||||||
_error_last_report_ms = now_ms;
|
_error_last_report_ms = now_ms;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user