diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 51b32b0eec..7ea1171339 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -503,7 +503,7 @@ private: uint8_t sending_bucket_id = no_bucket_to_send; Bitmask bucket_message_ids_to_send{MSG_LAST}; - ap_message next_deferred_message_to_send(); + ap_message next_deferred_bucket_message_to_send(); void find_next_bucket_to_send(); void remove_message_from_bucket(int8_t bucket, ap_message id); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 9e1bb2a2ef..50aacc67d0 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1024,7 +1024,7 @@ void GCS_MAVLINK::find_next_bucket_to_send() #endif } -ap_message GCS_MAVLINK::next_deferred_message_to_send() +ap_message GCS_MAVLINK::next_deferred_bucket_message_to_send() { if (sending_bucket_id == no_bucket_to_send) { // could happen if all streamrates are zero? @@ -1042,7 +1042,7 @@ ap_message GCS_MAVLINK::next_deferred_message_to_send() if (next == -1) { // should not happen #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - AP_HAL::panic("next_deferred_message_to_send called on empty bucket"); + AP_HAL::panic("next_deferred_bucket_message_to_send called on empty bucket"); #endif find_next_bucket_to_send(); return no_message_to_send; @@ -1197,7 +1197,7 @@ void GCS_MAVLINK::update_send() continue; } - next = next_deferred_message_to_send(); + next = next_deferred_bucket_message_to_send(); if (next != no_message_to_send) { if (!do_try_send_message(next)) { break;