mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: file descriptor leaking and other issues in "Storage" of Linux.
- Fixed the fd leaking issue in "_storage_create" found by @peterbarker - Remove the unnecessary call of "unlinkat" in "_storage_create" - Simplify the implementation of "init" Signed-off-by: junan <junan76@163.com>
This commit is contained in:
parent
9cb3354ba0
commit
71a69367df
|
@ -101,7 +101,6 @@ int Storage::_storage_create(const char *dpath)
|
|||
return -1;
|
||||
}
|
||||
|
||||
unlinkat(dfd, dpath, 0);
|
||||
int fd = openat(dfd, STORAGE_FILE, O_RDWR|O_CREAT|O_CLOEXEC, 0666);
|
||||
|
||||
if (fd == -1) {
|
||||
|
@ -114,6 +113,7 @@ int Storage::_storage_create(const char *dpath)
|
|||
if (ftruncate(fd, sizeof(_buffer)) == -1) {
|
||||
fprintf(stderr, "Failed to set file size to %u kB (%m)\n",
|
||||
unsigned(sizeof(_buffer) / 1024));
|
||||
close(fd);
|
||||
goto fail;
|
||||
}
|
||||
|
||||
|
@ -145,27 +145,17 @@ void Storage::init()
|
|||
dpath = HAL_BOARD_STORAGE_DIRECTORY;
|
||||
}
|
||||
|
||||
int fd = open(dpath, O_RDWR|O_CLOEXEC);
|
||||
if (fd == -1) {
|
||||
fd = _storage_create(dpath);
|
||||
int fd = _storage_create(dpath);
|
||||
if (fd == -1) {
|
||||
AP_HAL::panic("Cannot create storage %s (%m)", dpath);
|
||||
}
|
||||
}
|
||||
|
||||
ssize_t ret = read(fd, _buffer, sizeof(_buffer));
|
||||
|
||||
if (ret != sizeof(_buffer)) {
|
||||
close(fd);
|
||||
_storage_create(dpath);
|
||||
fd = open(dpath, O_RDONLY|O_CLOEXEC);
|
||||
if (fd == -1) {
|
||||
AP_HAL::panic("Failed to open %s (%m)", dpath);
|
||||
}
|
||||
if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
|
||||
AP_HAL::panic("Failed to read %s (%m)", dpath);
|
||||
}
|
||||
}
|
||||
|
||||
_fd = fd;
|
||||
_initialised = true;
|
||||
|
|
Loading…
Reference in New Issue