mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Filesystem: fixed a param ftp bug
if param count changes we need to zero the file size
This commit is contained in:
parent
7242b6e3e5
commit
b449e45ed6
@ -56,6 +56,7 @@ int AP_Filesystem_Param::open(const char *fname, int flags)
|
|||||||
r.start = 0;
|
r.start = 0;
|
||||||
r.count = 0;
|
r.count = 0;
|
||||||
r.read_size = 0;
|
r.read_size = 0;
|
||||||
|
r.file_size = 0;
|
||||||
r.writebuf = nullptr;
|
r.writebuf = nullptr;
|
||||||
if (!read_only) {
|
if (!read_only) {
|
||||||
// setup for upload
|
// setup for upload
|
||||||
|
Loading…
Reference in New Issue
Block a user