Browse Source

GCS_MAVLink: check for empty replies queue first thing in send_ftp_replies

Will save us a little time on average
zr-v5.1
Peter Barker 5 years ago committed by Peter Barker
parent
commit
668e0d0e65
  1. 2
      libraries/GCS_MAVLink/GCS_FTP.cpp

2
libraries/GCS_MAVLink/GCS_FTP.cpp

@ -85,7 +85,7 @@ void GCS_MAVLINK::handle_file_transfer_protocol(const mavlink_message_t &msg) { @@ -85,7 +85,7 @@ void GCS_MAVLINK::handle_file_transfer_protocol(const mavlink_message_t &msg) {
}
void GCS_MAVLINK::send_ftp_replies(void) {
if (ftp.replies == nullptr) {
if (ftp.replies == nullptr || ftp.replies->empty()) {
return;
}

Loading…
Cancel
Save