diff --git a/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp b/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp index 7326046400..8d27d78a0f 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp @@ -35,7 +35,7 @@ void AnalogSource_IIO::init_pins(void) strncpy(buf, IIO_ANALOG_IN_DIR, sizeof(buf)); strncat(buf, AnalogSource_IIO::analog_sources[i], sizeof(buf) - strlen(buf) - 1); - fd_analog_sources[i] = open(buf, O_RDONLY | O_NONBLOCK); + fd_analog_sources[i] = open(buf, O_RDONLY | O_NONBLOCK | O_CLOEXEC); } } diff --git a/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp b/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp index 789e852c06..44373f8f5d 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp @@ -27,7 +27,7 @@ void AnalogSource_Navio2::set_channel(uint8_t pin) ::close(_fd); } - _fd = ::open(channel_path, O_RDONLY); + _fd = ::open(channel_path, O_RDONLY|O_CLOEXEC); if (_fd < 0) { hal.console->printf("%s not opened: %s\n", channel_path, strerror(errno)); diff --git a/libraries/AP_HAL_Linux/CameraSensor.cpp b/libraries/AP_HAL_Linux/CameraSensor.cpp index 568b0dfee8..63f45397a0 100644 --- a/libraries/AP_HAL_Linux/CameraSensor.cpp +++ b/libraries/AP_HAL_Linux/CameraSensor.cpp @@ -30,7 +30,7 @@ bool CameraSensor::set_format(uint32_t width, uint32_t height, uint32_t format) struct v4l2_subdev_format fmt; int ret, fd; - fd = open(_device_path, O_RDWR); + fd = open(_device_path, O_RDWR | O_CLOEXEC); if (fd < 0) { return false; } diff --git a/libraries/AP_HAL_Linux/GPIO_BBB.cpp b/libraries/AP_HAL_Linux/GPIO_BBB.cpp index 7936287665..b757b242bb 100644 --- a/libraries/AP_HAL_Linux/GPIO_BBB.cpp +++ b/libraries/AP_HAL_Linux/GPIO_BBB.cpp @@ -29,7 +29,7 @@ void GPIO_BBB::init() // Idea taken from https://groups.google.com/forum/#!msg/beagleboard/OYFp4EXawiI/Mq6s3sg14HoJ uint8_t bank_enable[3] = { 5, 65, 105 }; - int export_fd = open("/sys/class/gpio/export", O_WRONLY); + int export_fd = open("/sys/class/gpio/export", O_WRONLY | O_CLOEXEC); if (export_fd == -1) { AP_HAL::panic("unable to open /sys/class/gpio/export"); } @@ -40,7 +40,7 @@ void GPIO_BBB::init() /* open /dev/mem */ - if ((mem_fd = open("/dev/mem", O_RDWR|O_SYNC) ) < 0) { + if ((mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC)) < 0) { printf("can't open /dev/mem \n"); exit (-1); } diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.cpp b/libraries/AP_HAL_Linux/GPIO_RPI.cpp index 3e6cea1901..8937949b69 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.cpp +++ b/libraries/AP_HAL_Linux/GPIO_RPI.cpp @@ -48,7 +48,7 @@ void GPIO_RPI::init() int rpi_version = UtilRPI::from(hal.util)->get_rpi_version(); uint32_t gpio_address = rpi_version == 1 ? GPIO_BASE(BCM2708_PERI_BASE) : GPIO_BASE(BCM2709_PERI_BASE); - int mem_fd = open("/dev/mem", O_RDWR|O_SYNC); + int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC); if (mem_fd < 0) { AP_HAL::panic("Can't open /dev/mem"); } diff --git a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp index a069a240d1..2137b64c3d 100644 --- a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp +++ b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp @@ -342,7 +342,7 @@ void OpticalFlow_Onboard::_run_optflow() gyro_rate.z = rate_z; #ifdef OPTICALFLOW_ONBOARD_RECORD_VIDEO - int fd = open(OPTICALFLOW_ONBOARD_VIDEO_FILE, O_CREAT | O_WRONLY + int fd = open(OPTICALFLOW_ONBOARD_VIDEO_FILE, O_CLOEXEC | O_CREAT | O_WRONLY | O_APPEND, S_IRUSR | S_IWUSR | S_IRGRP | S_IWGRP | S_IROTH | S_IWOTH); if (fd != -1) { diff --git a/libraries/AP_HAL_Linux/RCInput_115200.cpp b/libraries/AP_HAL_Linux/RCInput_115200.cpp index 47140996ae..7fb225023d 100644 --- a/libraries/AP_HAL_Linux/RCInput_115200.cpp +++ b/libraries/AP_HAL_Linux/RCInput_115200.cpp @@ -37,7 +37,7 @@ using namespace Linux; void RCInput_115200::init() { - fd = open(device_path, O_RDWR | O_NONBLOCK); + fd = open(device_path, O_RDWR | O_NONBLOCK | O_CLOEXEC); if (fd != -1) { struct termios options; diff --git a/libraries/AP_HAL_Linux/RCInput_AioPRU.cpp b/libraries/AP_HAL_Linux/RCInput_AioPRU.cpp index c4ce642f10..69f4e3221f 100644 --- a/libraries/AP_HAL_Linux/RCInput_AioPRU.cpp +++ b/libraries/AP_HAL_Linux/RCInput_AioPRU.cpp @@ -35,7 +35,7 @@ using namespace Linux; void RCInput_AioPRU::init() { - int mem_fd = open("/dev/mem", O_RDWR|O_SYNC); + int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC); if (mem_fd == -1) { AP_HAL::panic("Unable to open /dev/mem"); } diff --git a/libraries/AP_HAL_Linux/RCInput_Navio2.cpp b/libraries/AP_HAL_Linux/RCInput_Navio2.cpp index c32adaf2f0..edd7eee78c 100644 --- a/libraries/AP_HAL_Linux/RCInput_Navio2.cpp +++ b/libraries/AP_HAL_Linux/RCInput_Navio2.cpp @@ -65,7 +65,7 @@ int RCInput_Navio2::open_channel(int channel) AP_HAL::panic("[RCInput_Navio2]: not enough memory\n"); } - int fd = ::open(channel_path, O_RDONLY); + int fd = ::open(channel_path, O_RDONLY|O_CLOEXEC); free(channel_path); diff --git a/libraries/AP_HAL_Linux/RCInput_PRU.cpp b/libraries/AP_HAL_Linux/RCInput_PRU.cpp index aa14cdeeb9..804072d9e5 100644 --- a/libraries/AP_HAL_Linux/RCInput_PRU.cpp +++ b/libraries/AP_HAL_Linux/RCInput_PRU.cpp @@ -27,7 +27,7 @@ using namespace Linux; void RCInput_PRU::init() { - int mem_fd = open("/dev/mem", O_RDWR|O_SYNC); + int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC); if (mem_fd == -1) { AP_HAL::panic("Unable to open /dev/mem"); } diff --git a/libraries/AP_HAL_Linux/RCInput_RPI.cpp b/libraries/AP_HAL_Linux/RCInput_RPI.cpp index 339c34d7d2..096c1ff2c5 100644 --- a/libraries/AP_HAL_Linux/RCInput_RPI.cpp +++ b/libraries/AP_HAL_Linux/RCInput_RPI.cpp @@ -109,12 +109,12 @@ Memory_table::Memory_table(uint32_t page_count, int version) _phys_pages = (void**)malloc(page_count * sizeof(void*)); _page_count = page_count; - if ((fdMem = open("/dev/mem", O_RDWR | O_SYNC)) < 0) { + if ((fdMem = open("/dev/mem", O_RDWR | O_SYNC | O_CLOEXEC)) < 0) { fprintf(stderr,"Failed to open /dev/mem\n"); exit(-1); } - if ((file = open("/proc/self/pagemap", O_RDWR | O_SYNC)) < 0) { + if ((file = open("/proc/self/pagemap", O_RDWR | O_SYNC | O_CLOEXEC)) < 0) { fprintf(stderr,"Failed to open /proc/self/pagemap\n"); exit(-1); } @@ -216,7 +216,7 @@ void RCInput_RPI::set_physical_addresses(int version) //Map peripheral to virtual memory void* RCInput_RPI::map_peripheral(uint32_t base, uint32_t len) { - int fd = open("/dev/mem", O_RDWR); + int fd = open("/dev/mem", O_RDWR | O_CLOEXEC); void * vaddr; if (fd < 0) { diff --git a/libraries/AP_HAL_Linux/RCInput_SBUS.cpp b/libraries/AP_HAL_Linux/RCInput_SBUS.cpp index 312e3a1193..167ccd9310 100644 --- a/libraries/AP_HAL_Linux/RCInput_SBUS.cpp +++ b/libraries/AP_HAL_Linux/RCInput_SBUS.cpp @@ -38,7 +38,7 @@ using namespace Linux; void RCInput_SBUS::init() { - fd = open(device_path, O_RDWR | O_NONBLOCK); + fd = open(device_path, O_RDWR | O_NONBLOCK | O_CLOEXEC); if (fd != -1) { printf("Opened SBUS input %s fd=%d\n", device_path, (int)fd); fflush(stdout); @@ -107,7 +107,7 @@ void RCInput_SBUS::_timer_tick(void) #if SBUS_DEBUG_LOG static int logfd = -1; if (logfd == -1) { - logfd = open("sbus.log", O_WRONLY|O_CREAT|O_TRUNC, 0644); + logfd = open("sbus.log", O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC, 0644); } #endif diff --git a/libraries/AP_HAL_Linux/RCInput_UART.cpp b/libraries/AP_HAL_Linux/RCInput_UART.cpp index 994aa6ff90..ae58c906e4 100644 --- a/libraries/AP_HAL_Linux/RCInput_UART.cpp +++ b/libraries/AP_HAL_Linux/RCInput_UART.cpp @@ -17,7 +17,7 @@ using namespace Linux; RCInput_UART::RCInput_UART(const char *path) { - _fd = open(path, O_RDONLY|O_NOCTTY|O_NONBLOCK|O_NDELAY); + _fd = open(path, O_RDONLY|O_NOCTTY|O_NONBLOCK|O_NDELAY|O_CLOEXEC); if (_fd < 0) { AP_HAL::panic("RCInput_UART: Error opening '%s': %s", path, strerror(errno)); diff --git a/libraries/AP_HAL_Linux/RCInput_ZYNQ.cpp b/libraries/AP_HAL_Linux/RCInput_ZYNQ.cpp index 65e4f397bc..675235ba96 100644 --- a/libraries/AP_HAL_Linux/RCInput_ZYNQ.cpp +++ b/libraries/AP_HAL_Linux/RCInput_ZYNQ.cpp @@ -24,7 +24,7 @@ using namespace Linux; void RCInput_ZYNQ::init() { - int mem_fd = open("/dev/mem", O_RDWR|O_SYNC); + int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC); if (mem_fd == -1) { AP_HAL::panic("Unable to open /dev/mem"); } diff --git a/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp b/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp index fdd6cff9a2..e77409481b 100644 --- a/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp @@ -36,7 +36,7 @@ void RCOutput_AioPRU::init() signal(SIGBUS,catch_sigbus); - mem_fd = open("/dev/mem", O_RDWR|O_SYNC); + mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC); pwm = (struct pwm*) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_RAM_BASE); iram = (uint32_t*)mmap(0, 0x2000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_IRAM_BASE); diff --git a/libraries/AP_HAL_Linux/RCOutput_PRU.cpp b/libraries/AP_HAL_Linux/RCOutput_PRU.cpp index 30f476a302..6e5f9c6b38 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PRU.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_PRU.cpp @@ -29,7 +29,7 @@ void RCOutput_PRU::init() { uint32_t mem_fd; signal(SIGBUS,catch_sigbus); - mem_fd = open("/dev/mem", O_RDWR|O_SYNC); + mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC); sharedMem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_SHAREDRAM_BASE); close(mem_fd); diff --git a/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp b/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp index f68e7d3ee9..f67790f725 100644 --- a/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp @@ -37,7 +37,7 @@ void RCOutput_ZYNQ::init() { uint32_t mem_fd; signal(SIGBUS,catch_sigbus); - mem_fd = open("/dev/mem", O_RDWR|O_SYNC); + mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC); sharedMem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_ZYNQ_PWM_BASE); close(mem_fd); diff --git a/libraries/AP_HAL_Linux/Storage.cpp b/libraries/AP_HAL_Linux/Storage.cpp index 04060e2669..e111ed88dd 100644 --- a/libraries/AP_HAL_Linux/Storage.cpp +++ b/libraries/AP_HAL_Linux/Storage.cpp @@ -35,7 +35,7 @@ void Storage::_storage_create(void) { mkdir(STORAGE_DIR, 0777); unlink(STORAGE_FILE); - int fd = open(STORAGE_FILE, O_RDWR|O_CREAT, 0666); + int fd = open(STORAGE_FILE, O_RDWR|O_CREAT|O_CLOEXEC, 0666); if (fd == -1) { AP_HAL::panic("Failed to create " STORAGE_FILE); } @@ -57,10 +57,10 @@ void Storage::_storage_open(void) } _dirty_mask = 0; - int fd = open(STORAGE_FILE, O_RDWR); + int fd = open(STORAGE_FILE, O_RDWR|O_CLOEXEC); if (fd == -1) { _storage_create(); - fd = open(STORAGE_FILE, O_RDWR); + fd = open(STORAGE_FILE, O_RDWR|O_CLOEXEC); if (fd == -1) { AP_HAL::panic("Failed to open " STORAGE_FILE); } @@ -80,7 +80,7 @@ void Storage::_storage_open(void) if (ret != sizeof(_buffer)) { close(fd); _storage_create(); - fd = open(STORAGE_FILE, O_RDONLY); + fd = open(STORAGE_FILE, O_RDONLY|O_CLOEXEC); if (fd == -1) { AP_HAL::panic("Failed to open " STORAGE_FILE); } @@ -137,7 +137,7 @@ void Storage::_timer_tick(void) } if (_fd == -1) { - _fd = open(STORAGE_FILE, O_WRONLY); + _fd = open(STORAGE_FILE, O_WRONLY|O_CLOEXEC); if (_fd == -1) { return; } diff --git a/libraries/AP_HAL_Linux/ToneAlarm.cpp b/libraries/AP_HAL_Linux/ToneAlarm.cpp index e3f3e49cad..8a692c2b41 100644 --- a/libraries/AP_HAL_Linux/ToneAlarm.cpp +++ b/libraries/AP_HAL_Linux/ToneAlarm.cpp @@ -38,9 +38,9 @@ bool ToneAlarm::tune_repeat[TONE_NUMBER_OF_TUNES] = {false,true,false,false,fals ToneAlarm::ToneAlarm() { - period_fd = open("/sys/devices/ocp.3/pwm_test_P8_36.12/period",O_WRONLY); - duty_fd = open("/sys/devices/ocp.3/pwm_test_P8_36.12/duty",O_WRONLY); - run_fd = open("/sys/devices/ocp.3/pwm_test_P8_36.12/run",O_WRONLY); + period_fd = open("/sys/devices/ocp.3/pwm_test_P8_36.12/period",O_WRONLY|O_CLOEXEC); + duty_fd = open("/sys/devices/ocp.3/pwm_test_P8_36.12/duty",O_WRONLY|O_CLOEXEC); + run_fd = open("/sys/devices/ocp.3/pwm_test_P8_36.12/run",O_WRONLY|O_CLOEXEC); tune_num = -1; //initialy no tune to play tune_pos = 0; diff --git a/libraries/AP_HAL_Linux/VideoIn.cpp b/libraries/AP_HAL_Linux/VideoIn.cpp index cf7378b962..dc7e574d81 100644 --- a/libraries/AP_HAL_Linux/VideoIn.cpp +++ b/libraries/AP_HAL_Linux/VideoIn.cpp @@ -68,7 +68,7 @@ bool VideoIn::open_device(const char *device_path, uint32_t memtype) _fd = -1; _buffers = nullptr; - _fd = open(device_path, O_RDWR); + _fd = open(device_path, O_RDWR|O_CLOEXEC); _memtype = memtype; if (_fd < 0) { hal.console->printf("Error opening device %s: %s (%d).\n", diff --git a/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp b/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp index a6176572eb..e829d6227f 100644 --- a/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp +++ b/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp @@ -275,7 +275,7 @@ int qflight_UART_open(const char *device, int32_t *_fd) return -1; } struct uartbuf &b = uarts[num_open_uarts]; - int fd = open(device, O_RDWR | O_NONBLOCK); + int fd = open(device, O_RDWR | O_NONBLOCK|O_CLOEXEC); if (fd == -1) { return -1; }