Browse Source

DataFlash: add O_CLOEXEC in places missing it

By opening with O_CLOEXEC we make sure we don't leak the file descriptor
when we are exec'ing or calling out subprograms. Right now we currently
don't do it so there's no harm, but it's good practice in Linux to have
it.
master
Lucas De Marchi 8 years ago
parent
commit
c9eff28c44
  1. 12
      libraries/DataFlash/DataFlash_File.cpp
  2. 4
      libraries/DataFlash/DataFlash_SITL.cpp

12
libraries/DataFlash/DataFlash_File.cpp

@ -154,7 +154,7 @@ void DataFlash_File::Init()
bool DataFlash_File::file_exists(const char *filename) const bool DataFlash_File::file_exists(const char *filename) const
{ {
#if DATAFLASH_FILE_MINIMAL #if DATAFLASH_FILE_MINIMAL
int fd = open(filename, O_RDONLY); int fd = open(filename, O_RDONLY|O_CLOEXEC);
if (fd == -1) { if (fd == -1) {
return false; return false;
} }
@ -536,7 +536,7 @@ uint16_t DataFlash_File::find_last_log()
if (fname == nullptr) { if (fname == nullptr) {
return ret; return ret;
} }
int fd = open(fname, O_RDONLY); int fd = open(fname, O_RDONLY|O_CLOEXEC);
free(fname); free(fname);
if (fd != -1) { if (fd != -1) {
char buf[10]; char buf[10];
@ -651,7 +651,7 @@ int16_t DataFlash_File::get_log_data(const uint16_t list_entry, const uint16_t p
return -1; return -1;
} }
stop_logging(); stop_logging();
_read_fd = ::open(fname, O_RDONLY); _read_fd = ::open(fname, O_RDONLY|O_CLOEXEC);
if (_read_fd == -1) { if (_read_fd == -1) {
_open_error = true; _open_error = true;
int saved_errno = errno; int saved_errno = errno;
@ -804,7 +804,7 @@ uint16_t DataFlash_File::start_new_log(void)
if (fname == nullptr) { if (fname == nullptr) {
return 0xFFFF; return 0xFFFF;
} }
_write_fd = ::open(fname, O_WRONLY|O_CREAT|O_TRUNC, 0666); _write_fd = ::open(fname, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC, 0666);
_cached_oldest_log = 0; _cached_oldest_log = 0;
if (_write_fd == -1) { if (_write_fd == -1) {
@ -828,7 +828,7 @@ uint16_t DataFlash_File::start_new_log(void)
// we avoid fopen()/fprintf() here as it is not available on as many // we avoid fopen()/fprintf() here as it is not available on as many
// systems as open/write (specifically the QURT RTOS) // systems as open/write (specifically the QURT RTOS)
int fd = open(fname, O_WRONLY|O_CREAT, 0644); int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC, 0644);
free(fname); free(fname);
if (fd == -1) { if (fd == -1) {
return 0xFFFF; return 0xFFFF;
@ -873,7 +873,7 @@ void DataFlash_File::LogReadProcess(const uint16_t list_entry,
if (fname == nullptr) { if (fname == nullptr) {
return; return;
} }
_read_fd = ::open(fname, O_RDONLY); _read_fd = ::open(fname, O_RDONLY|O_CLOEXEC);
free(fname); free(fname);
if (_read_fd == -1) { if (_read_fd == -1) {
return; return;

4
libraries/DataFlash/DataFlash_SITL.cpp

@ -31,11 +31,11 @@ void DataFlash_SITL::Init()
{ {
DataFlash_Backend::Init(); DataFlash_Backend::Init();
if (flash_fd == 0) { if (flash_fd == 0) {
flash_fd = open("dataflash.bin", O_RDWR, 0777); flash_fd = open("dataflash.bin", O_RDWR|O_CLOEXEC, 0777);
if (flash_fd == -1) { if (flash_fd == -1) {
uint8_t *fill; uint8_t *fill;
fill = (uint8_t *)malloc(DF_PAGE_SIZE*DF_NUM_PAGES); fill = (uint8_t *)malloc(DF_PAGE_SIZE*DF_NUM_PAGES);
flash_fd = open("dataflash.bin", O_RDWR | O_CREAT, 0777); flash_fd = open("dataflash.bin", O_RDWR | O_CREAT | O_CLOEXEC, 0777);
memset(fill, 0xFF, DF_PAGE_SIZE*DF_NUM_PAGES); memset(fill, 0xFF, DF_PAGE_SIZE*DF_NUM_PAGES);
write(flash_fd, fill, DF_PAGE_SIZE*DF_NUM_PAGES); write(flash_fd, fill, DF_PAGE_SIZE*DF_NUM_PAGES);
free(fill); free(fill);

Loading…
Cancel
Save