mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Logger: use load_file()
save a bit of flash
This commit is contained in:
parent
3a0e494085
commit
6bf7f9e864
@ -549,15 +549,10 @@ uint16_t AP_Logger_File::find_last_log()
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
EXPECT_DELAY_MS(3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
int fd = AP::FS().open(fname, O_RDONLY);
|
FileData *fd = AP::FS().load_file(fname);
|
||||||
free(fname);
|
if (fd != nullptr) {
|
||||||
if (fd != -1) {
|
ret = strtol((const char *)fd->data, NULL, 10);
|
||||||
char buf[10];
|
delete fd;
|
||||||
memset(buf, 0, sizeof(buf));
|
|
||||||
if (AP::FS().read(fd, buf, sizeof(buf)-1) > 0) {
|
|
||||||
ret = strtol(buf, NULL, 10);
|
|
||||||
}
|
|
||||||
AP::FS().close(fd);
|
|
||||||
}
|
}
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user