Fixed passed ot open() for O_CREAT

In nuttx the mode parameter to open is not required but in Linux,
and per the POSIX spec, mode is required if the O_CREAT flag is
passed.

The mode flags are different for NuttX and Linux so a new set of
PX4 defines was added:

PX4_O_MODE_777 - read, write, execute for user, group and other
PX4_O_MODE_666 - read, and write for user, group and other
PX4_O_MODE_600 - read, and write for user

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois 2015-06-13 22:06:38 -07:00 committed by Lorenz Meier
parent c6b36073fe
commit 872a26e6da
8 changed files with 19 additions and 12 deletions

View File

@ -672,12 +672,7 @@ task_main(int argc, char *argv[])
} }
/* Open or create the data manager file */ /* Open or create the data manager file */
g_task_fd = open(k_data_manager_device_path, O_RDWR | O_CREAT | O_BINARY g_task_fd = open(k_data_manager_device_path, O_RDWR | O_CREAT | O_BINARY, PX4_O_MODE_666);
#ifdef __PX4_LINUX
// Open with read/write permission for user
, S_IRUSR | S_IWUSR
#endif
);
if (g_task_fd < 0) { if (g_task_fd < 0) {
warnx("Could not open data manager file %s", k_data_manager_device_path); warnx("Could not open data manager file %s", k_data_manager_device_path);

View File

@ -455,7 +455,8 @@ MavlinkFTP::_workOpen(PayloadHeader* payload, int oflag)
} }
fileSize = st.st_size; fileSize = st.st_size;
int fd = ::open(filename, oflag); // Set mode to 666 incase oflag has O_CREAT
int fd = ::open(filename, oflag, PX4_O_MODE_666);
if (fd < 0) { if (fd < 0) {
return kErrFailErrno; return kErrFailErrno;
} }

View File

@ -505,7 +505,7 @@ int open_log_file()
} }
} }
int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC, 0x0777); int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC, PX4_O_MODE_666);
if (fd < 0) { if (fd < 0) {
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] failed opening: %s", log_file_name); mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] failed opening: %s", log_file_name);

View File

@ -728,7 +728,7 @@ param_save_default(void)
const char *filename = param_get_default_file(); const char *filename = param_get_default_file();
/* write parameters to temp file */ /* write parameters to temp file */
fd = PARAM_OPEN(filename, O_WRONLY | O_CREAT, 0x777); fd = PARAM_OPEN(filename, O_WRONLY | O_CREAT, PX4_O_MODE_666);
if (fd < 0) { if (fd < 0) {
warn("failed to open param file: %s", filename); warn("failed to open param file: %s", filename);

View File

@ -107,6 +107,11 @@ typedef param_t px4_param_t;
#define PX4_ISFINITE(x) isfinite(x) #define PX4_ISFINITE(x) isfinite(x)
// mode for open with O_CREAT
#define PX4_O_MODE_777 0777
#define PX4_O_MODE_666 0666
#define PX4_O_MODE_600 0600
#ifndef PRIu64 #ifndef PRIu64
#define PRIu64 "llu" #define PRIu64 "llu"
#endif #endif
@ -119,6 +124,12 @@ typedef param_t px4_param_t;
// Flag is meaningless on Linux // Flag is meaningless on Linux
#define O_BINARY 0 #define O_BINARY 0
// mode for open with O_CREAT
#define PX4_O_MODE_777 (S_IRWXU | S_IRWXG | S_IRWXO)
#define PX4_O_MODE_666 (S_IRUSR | S_IWUSR | S_IRGRP | S_IWGRP | S_IROTH | S_IWOTH )
#define PX4_O_MODE_600 (S_IRUSR | S_IWUSR)
// NuttX _IOC is equivalent to Linux _IO // NuttX _IOC is equivalent to Linux _IO
#define _PX4_IOC(x,y) _IO(x,y) #define _PX4_IOC(x,y) _IO(x,y)

View File

@ -202,7 +202,7 @@ static int
do_save(const char *param_file_name) do_save(const char *param_file_name)
{ {
/* create the file */ /* create the file */
int fd = open(param_file_name, O_WRONLY | O_CREAT, 0x777); int fd = open(param_file_name, O_WRONLY | O_CREAT, PX4_O_MODE_666);
if (fd < 0) { if (fd < 0) {
warn("opening '%s' failed", param_file_name); warn("opening '%s' failed", param_file_name);

View File

@ -73,7 +73,7 @@ static void test_corruption(const char *filename, uint32_t write_chunk, uint32_t
filename, (unsigned)write_chunk, (unsigned)write_size); filename, (unsigned)write_chunk, (unsigned)write_size);
uint32_t ofs = 0; uint32_t ofs = 0;
int fd = open(filename, O_CREAT | O_RDWR | O_TRUNC); int fd = open(filename, O_CREAT | O_RDWR | O_TRUNC, PX4_O_MODE_666);
if (fd == -1) { if (fd == -1) {
perror(filename); perror(filename);

View File

@ -163,7 +163,7 @@ test_mount(int argc, char *argv[])
} else { } else {
/* this must be the first iteration, do something */ /* this must be the first iteration, do something */
cmd_fd = open(cmd_filename, O_TRUNC | O_WRONLY | O_CREAT); cmd_fd = open(cmd_filename, O_TRUNC | O_WRONLY | O_CREAT, PX4_O_MODE_666);
warnx("First iteration of file test\n"); warnx("First iteration of file test\n");
} }