mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: GCS_FTP: remove redundant more_pending variable
This is taken care of by the "break" statements
This commit is contained in:
parent
a09ac895e9
commit
7028f1adba
|
@ -456,14 +456,12 @@ void GCS_MAVLINK::ftp_worker(void) {
|
|||
break;
|
||||
}
|
||||
|
||||
bool more_pending = true;
|
||||
const uint32_t transfer_size = 100;
|
||||
for (uint32_t i = 0; (i < transfer_size) && more_pending; i++) {
|
||||
for (uint32_t i = 0; (i < transfer_size); i++) {
|
||||
// fill the buffer
|
||||
const ssize_t read_bytes = AP::FS().read(ftp.fd, reply.data, max_read);
|
||||
if (read_bytes == -1) {
|
||||
ftp_error(reply, FTP_ERROR::FailErrno);
|
||||
more_pending = false;
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -474,7 +472,6 @@ void GCS_MAVLINK::ftp_worker(void) {
|
|||
|
||||
if (read_bytes == 0) {
|
||||
ftp_error(reply, FTP_ERROR::EndOfFile);
|
||||
more_pending = false;
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue