AP_HAL_Linux: 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.
This commit is contained in:
Lucas De Marchi 2016-10-30 11:22:29 -02:00
parent 2e4c1818a3
commit 490841a814
21 changed files with 31 additions and 31 deletions

View File

@ -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);
}
}

View File

@ -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));

View File

@ -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;
}

View File

@ -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);
}

View File

@ -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");
}

View File

@ -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) {

View File

@ -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;

View File

@ -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");
}

View File

@ -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);

View File

@ -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");
}

View File

@ -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) {

View File

@ -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

View File

@ -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));

View File

@ -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");
}

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -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;
}

View File

@ -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;

View File

@ -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",

View File

@ -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;
}