Browse Source

GCS_MAVLink: avoid considering no_message_to_send equal to -1

mission-4.1.18
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
8d970c13c0
  1. 9
      libraries/GCS_MAVLink/GCS_Common.cpp

9
libraries/GCS_MAVLink/GCS_Common.cpp

@ -1178,9 +1178,10 @@ void GCS_MAVLINK::update_send() @@ -1178,9 +1178,10 @@ void GCS_MAVLINK::update_send()
}
}
// check for any messages that the code has explicity sent
ap_message next = (ap_message)pushed_ap_message_ids.first_set();
if (next != no_message_to_send) {
// check for any messages that the code has explicitly sent
const int16_t fs = pushed_ap_message_ids.first_set();
if (fs != -1) {
ap_message next = (ap_message)fs;
if (!do_try_send_message(next)) {
break;
}
@ -1196,7 +1197,7 @@ void GCS_MAVLINK::update_send() @@ -1196,7 +1197,7 @@ void GCS_MAVLINK::update_send()
continue;
}
next = next_deferred_bucket_message_to_send();
ap_message next = next_deferred_bucket_message_to_send();
if (next != no_message_to_send) {
if (!do_try_send_message(next)) {
break;

Loading…
Cancel
Save