AP_Filesystem: fixed a read past EOF bug in @PARAM

this could cause mavproxy FTP param download to fail
This commit is contained in:
Andrew Tridgell 2021-04-14 10:07:37 +10:00
parent 5fd46c02ad
commit 3e138aa98a
2 changed files with 16 additions and 1 deletions

View File

@ -254,6 +254,14 @@ int32_t AP_Filesystem_Param::read(int fd, void *buf, uint32_t count)
return -1; return -1;
} }
if (r.file_size != 0) {
// ensure we don't try to read past EOF
if (r.file_ofs > r.file_size) {
count = 0;
} else {
count = MIN(count, r.file_size - r.file_ofs);
}
}
if (r.file_ofs < sizeof(struct header)) { if (r.file_ofs < sizeof(struct header)) {
struct header hdr; struct header hdr;
@ -321,7 +329,13 @@ int32_t AP_Filesystem_Param::read(int fd, void *buf, uint32_t count)
uint8_t tbuf[max_pack_len]; uint8_t tbuf[max_pack_len];
uint8_t len = pack_param(r, c, tbuf); uint8_t len = pack_param(r, c, tbuf);
if (len == 0) { if (len == 0) {
// no more params // no more params, use this to trigger EOF in later reads
const uint32_t size = r.file_ofs + total;
if (r.file_size == 0) {
r.file_size = size;
} else {
r.file_size = MIN(size, r.file_size);
}
break; break;
} }
uint8_t n = MIN(len, count); uint8_t n = MIN(len, count);

View File

@ -62,6 +62,7 @@ private:
uint16_t start; uint16_t start;
uint16_t count; uint16_t count;
uint32_t file_ofs; uint32_t file_ofs;
uint32_t file_size;
struct cursor *cursors; struct cursor *cursors;
} file[max_open_file]; } file[max_open_file];