AP_Filesystem: fixed EOF on file read

should return number of bytes read. This fixes an issue with MAVProxy
ftp client
This commit is contained in:
Andrew Tridgell 2020-02-11 13:30:26 +11:00
parent 1cb711d35d
commit b49a76bb20

View File

@ -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;
}