mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
GCS_MAVLink: rename confusingly-named method
This commit is contained in:
parent
b696986de6
commit
e91ee3e54a
@ -503,7 +503,7 @@ private:
|
|||||||
uint8_t sending_bucket_id = no_bucket_to_send;
|
uint8_t sending_bucket_id = no_bucket_to_send;
|
||||||
Bitmask bucket_message_ids_to_send{MSG_LAST};
|
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 find_next_bucket_to_send();
|
||||||
void remove_message_from_bucket(int8_t bucket, ap_message id);
|
void remove_message_from_bucket(int8_t bucket, ap_message id);
|
||||||
|
|
||||||
|
@ -1024,7 +1024,7 @@ void GCS_MAVLINK::find_next_bucket_to_send()
|
|||||||
#endif
|
#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) {
|
if (sending_bucket_id == no_bucket_to_send) {
|
||||||
// could happen if all streamrates are zero?
|
// could happen if all streamrates are zero?
|
||||||
@ -1042,7 +1042,7 @@ ap_message GCS_MAVLINK::next_deferred_message_to_send()
|
|||||||
if (next == -1) {
|
if (next == -1) {
|
||||||
// should not happen
|
// should not happen
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#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
|
#endif
|
||||||
find_next_bucket_to_send();
|
find_next_bucket_to_send();
|
||||||
return no_message_to_send;
|
return no_message_to_send;
|
||||||
@ -1197,7 +1197,7 @@ void GCS_MAVLINK::update_send()
|
|||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
next = next_deferred_message_to_send();
|
next = next_deferred_bucket_message_to_send();
|
||||||
if (next != no_message_to_send) {
|
if (next != no_message_to_send) {
|
||||||
if (!do_try_send_message(next)) {
|
if (!do_try_send_message(next)) {
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user