From 744a741b99ce849e371eddecc475cb9b001a3c33 Mon Sep 17 00:00:00 2001 From: Friedrich Beckmann Date: Sun, 18 Sep 2022 18:35:41 +0200 Subject: [PATCH] AP_Filesystem: Better estimation of filesize for parameter file The actual filesize of the parameter downloadfile is around 15200 bytes. The indicated filesize is used in QGC for the progressbar. This patch does not try to compute the exact filesize but I try a better estimate. Only the full download off all parameters is considered to avoid more complexity. --- libraries/AP_Filesystem/AP_Filesystem_Param.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem_Param.cpp b/libraries/AP_Filesystem/AP_Filesystem_Param.cpp index e8ec6a4854..c7fa3177de 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Param.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_Param.cpp @@ -469,8 +469,8 @@ int AP_Filesystem_Param::stat(const char *name, struct stat *stbuf) return -1; } memset(stbuf, 0, sizeof(*stbuf)); - // give fixed size to avoid needing to scan entire file - stbuf->st_size = 1024*1024; + // give size estimation to avoid needing to scan entire file + stbuf->st_size = AP_Param::count_parameters() * 12; return 0; }