Browse Source

GCS_MAVLink: return early from log send if no log data to send

master
Andrew Tridgell 11 years ago
parent
commit
0aebc18b3f
  1. 3
      libraries/GCS_MAVLink/GCS_Logs.cpp

3
libraries/GCS_MAVLink/GCS_Logs.cpp

@ -132,6 +132,9 @@ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash) @@ -132,6 +132,9 @@ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash)
if (_log_listing) {
handle_log_send_listing(dataflash);
}
if (!_log_sending) {
return;
}
uint8_t num_sends = 1;
if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
// when on USB we can send a lot more data

Loading…
Cancel
Save