Browse Source

Merge pull request #2365 from PX4/master_p1

Master p1
sbg
Lorenz Meier 10 years ago
parent
commit
75ef0e1709
  1. 1
      posix-configs/posixtest/init/rc.S
  2. 7
      src/modules/dataman/dataman.c
  3. 3
      src/modules/mavlink/mavlink_ftp.cpp
  4. 2
      src/modules/sdlog2/sdlog2.c
  5. 6
      src/modules/systemlib/mcu_version.c
  6. 2
      src/modules/systemlib/param/param.c
  7. 11
      src/platforms/px4_defines.h
  8. 2
      src/systemcmds/param/param.c
  9. 2
      src/systemcmds/tests/test_file2.c
  10. 2
      src/systemcmds/tests/test_mount.c

1
posix-configs/posixtest/init/rc.S

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
uorb start
param load
mavlink start -u 14556
simulator start -s
param set CAL_GYRO0_ID 2293760

7
src/modules/dataman/dataman.c

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

3
src/modules/mavlink/mavlink_ftp.cpp

@ -455,7 +455,8 @@ MavlinkFTP::_workOpen(PayloadHeader* payload, int oflag) @@ -455,7 +455,8 @@ MavlinkFTP::_workOpen(PayloadHeader* payload, int oflag)
}
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) {
return kErrFailErrno;
}

2
src/modules/sdlog2/sdlog2.c

@ -505,7 +505,7 @@ int open_log_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) {
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] failed opening: %s", log_file_name);

6
src/modules/systemlib/mcu_version.c

@ -62,9 +62,15 @@ @@ -62,9 +62,15 @@
/** Copy the 96bit MCU Unique ID into the provided pointer */
void mcu_unique_id(uint32_t *uid_96_bit)
{
#ifdef __PX4_NUTTX
uid_96_bit[0] = getreg32(UNIQUE_ID);
uid_96_bit[1] = getreg32(UNIQUE_ID+4);
uid_96_bit[2] = getreg32(UNIQUE_ID+8);
#else
uid_96_bit[0] = 0;
uid_96_bit[1] = 1;
uid_96_bit[2] = 2;
#endif
}
int mcu_version(char* rev, char** revstr)

2
src/modules/systemlib/param/param.c

@ -728,7 +728,7 @@ param_save_default(void) @@ -728,7 +728,7 @@ param_save_default(void)
const char *filename = param_get_default_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) {
warn("failed to open param file: %s", filename);

11
src/platforms/px4_defines.h

@ -107,6 +107,11 @@ typedef param_t px4_param_t; @@ -107,6 +107,11 @@ typedef param_t px4_param_t;
#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
#define PRIu64 "llu"
#endif
@ -119,6 +124,12 @@ typedef param_t px4_param_t; @@ -119,6 +124,12 @@ typedef param_t px4_param_t;
// Flag is meaningless on Linux
#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
#define _PX4_IOC(x,y) _IO(x,y)

2
src/systemcmds/param/param.c

@ -202,7 +202,7 @@ static int @@ -202,7 +202,7 @@ static int
do_save(const char *param_file_name)
{
/* 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) {
warn("opening '%s' failed", param_file_name);

2
src/systemcmds/tests/test_file2.c

@ -73,7 +73,7 @@ static void test_corruption(const char *filename, uint32_t write_chunk, uint32_t @@ -73,7 +73,7 @@ static void test_corruption(const char *filename, uint32_t write_chunk, uint32_t
filename, (unsigned)write_chunk, (unsigned)write_size);
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) {
perror(filename);

2
src/systemcmds/tests/test_mount.c

@ -163,7 +163,7 @@ test_mount(int argc, char *argv[]) @@ -163,7 +163,7 @@ test_mount(int argc, char *argv[])
} else {
/* 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");
}

Loading…
Cancel
Save