AP_HAL_Linux: keep "dfd" open util fsync is done.

Since we want to do a fsync on "dfd", it can not be closed before that.

Signed-off-by: junan <junan76@163.com>
This commit is contained in:
junan 2024-09-08 09:50:35 +08:00 committed by Peter Barker
parent 1e8e250459
commit 4ee5b0ea12

View File

@ -104,8 +104,6 @@ int Storage::_storage_create(const char *dpath)
unlinkat(dfd, dpath, 0);
int fd = openat(dfd, STORAGE_FILE, O_RDWR|O_CREAT|O_CLOEXEC, 0666);
close(dfd);
if (fd == -1) {
fprintf(stderr, "Failed to create storage file %s/%s\n", dpath,
STORAGE_FILE);