HAL_QURT: fixed open of new storage file

This commit is contained in:
Andrew Tridgell 2015-12-29 19:20:51 +11:00
parent aae7dd952c
commit 70877ebd50

View File

@ -65,7 +65,7 @@ static void get_storage(void)
if (ardupilot_get_storage(buf, sizeof(buf)) != 0) { if (ardupilot_get_storage(buf, sizeof(buf)) != 0) {
return; return;
} }
int fd = open(STORAGE_FILE ".new", O_WRONLY); int fd = open(STORAGE_FILE ".new", O_WRONLY|O_CREAT|O_TRUNC, 0644);
if (fd == -1) { if (fd == -1) {
printf("Unable to open %s - %s\n", STORAGE_FILE ".new", strerror(errno)); printf("Unable to open %s - %s\n", STORAGE_FILE ".new", strerror(errno));
} }