mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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.
This commit is contained in:
parent
267661d555
commit
744a741b99
@ -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;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user