Browse Source

AP_Filesystem: fixed EOF on file read

should return number of bytes read. This fixes an issue with MAVProxy
ftp client
c415-sdk
Andrew Tridgell 5 years ago
parent
commit
b49a76bb20
  1. 5
      libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp

5
libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp

@ -414,7 +414,10 @@ ssize_t AP_Filesystem::read(int fd, void *buf, size_t count) @@ -414,7 +414,10 @@ ssize_t AP_Filesystem::read(int fd, void *buf, size_t count)
errno = fatfs_to_errno((FRESULT)res);
return -1;
}
if (size > n || size == 0) {
if (size == 0) {
break;
}
if (size > n) {
errno = EIO;
return -1;
}

Loading…
Cancel
Save