mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
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:
parent
1cb711d35d
commit
b49a76bb20
@ -414,7 +414,10 @@ ssize_t AP_Filesystem::read(int fd, void *buf, size_t count)
|
|||||||
errno = fatfs_to_errno((FRESULT)res);
|
errno = fatfs_to_errno((FRESULT)res);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
if (size > n || size == 0) {
|
if (size == 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (size > n) {
|
||||||
errno = EIO;
|
errno = EIO;
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user