From 3e138aa98a8556a43f742cfe5c65ec591846fe2e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 14 Apr 2021 10:07:37 +1000 Subject: [PATCH] AP_Filesystem: fixed a read past EOF bug in @PARAM this could cause mavproxy FTP param download to fail --- libraries/AP_Filesystem/AP_Filesystem_Param.cpp | 16 +++++++++++++++- libraries/AP_Filesystem/AP_Filesystem_Param.h | 1 + 2 files changed, 16 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem_Param.cpp b/libraries/AP_Filesystem/AP_Filesystem_Param.cpp index 3f18aa88dc..1455b1f4eb 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Param.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_Param.cpp @@ -254,6 +254,14 @@ int32_t AP_Filesystem_Param::read(int fd, void *buf, uint32_t count) 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)) { 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 len = pack_param(r, c, tbuf); 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; } uint8_t n = MIN(len, count); diff --git a/libraries/AP_Filesystem/AP_Filesystem_Param.h b/libraries/AP_Filesystem/AP_Filesystem_Param.h index d3eb58c17d..6476cfdb39 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Param.h +++ b/libraries/AP_Filesystem/AP_Filesystem_Param.h @@ -62,6 +62,7 @@ private: uint16_t start; uint16_t count; uint32_t file_ofs; + uint32_t file_size; struct cursor *cursors; } file[max_open_file];