param: grab the shutdown lock while writing params to the file

This commit is contained in:
Beat Küng 2017-07-24 13:10:04 +02:00 committed by Lorenz Meier
parent 898a8dcd57
commit 931ef189b5
3 changed files with 38 additions and 8 deletions

View File

@ -44,6 +44,7 @@
#include <px4_defines.h>
#include <px4_posix.h>
#include <px4_shutdown.h>
#include <string.h>
#include <stdbool.h>
#include <stdint.h>
@ -158,6 +159,12 @@ out:
size_t buf_size = bson_encoder_buf_size(&encoder);
int shutdown_lock_ret = px4_shutdown_lock();
if (shutdown_lock_ret) {
PX4_ERR("px4_shutdown_lock() failed (%i)", shutdown_lock_ret);
}
/* Get a buffer from the flash driver with enough space */
uint8_t *buffer;
@ -186,6 +193,11 @@ out:
free(enc_buff);
parameter_flashfs_free();
}
if (shutdown_lock_ret == 0) {
px4_shutdown_unlock();
}
}
return result;

View File

@ -45,6 +45,7 @@
#include <px4_defines.h>
#include <px4_posix.h>
#include <px4_config.h>
#include <px4_shutdown.h>
#include <string.h>
#include <stdbool.h>
#include <float.h>
@ -1003,6 +1004,12 @@ param_export(int fd, bool only_unsaved)
struct bson_encoder_s encoder;
int result = -1;
int shutdown_lock_ret = px4_shutdown_lock();
if (shutdown_lock_ret) {
PX4_ERR("px4_shutdown_lock() failed (%i)", shutdown_lock_ret);
}
param_lock_writer();
bson_encoder_init_file(&encoder, fd);
@ -1090,6 +1097,12 @@ param_export(int fd, bool only_unsaved)
out:
param_unlock_writer();
fsync(fd); // make sure the data is flushed before releasing the shutdown lock
if (shutdown_lock_ret == 0) {
px4_shutdown_unlock();
}
if (result == 0) {
result = bson_encoder_fini(&encoder);
}

View File

@ -44,6 +44,7 @@
//#include <debug.h>
#include <px4_defines.h>
#include <px4_posix.h>
#include <px4_shutdown.h>
#include <string.h>
#include <stdbool.h>
#include <stdlib.h>
@ -945,14 +946,6 @@ param_save_default(void)
goto exit;
}
// After writing the file, also do a fsync to prevent loosing params if power is cut.
res = fsync(fd);
if (res != 0) {
PX4_ERR("failed to do fsync: %s", strerror(errno));
goto exit;
}
PARAM_CLOSE(fd);
@ -1044,6 +1037,12 @@ param_export(int fd, bool only_unsaved)
struct bson_encoder_s encoder;
int result = -1;
int shutdown_lock_ret = px4_shutdown_lock();
if (shutdown_lock_ret) {
PX4_ERR("px4_shutdown_lock() failed (%i)", shutdown_lock_ret);
}
param_lock();
bson_encoder_init_file(&encoder, fd);
@ -1123,6 +1122,12 @@ param_export(int fd, bool only_unsaved)
out:
param_unlock();
fsync(fd); // make sure the data is flushed before releasing the shutdown lock
if (shutdown_lock_ret == 0) {
px4_shutdown_unlock();
}
if (result == 0) {
result = bson_encoder_fini(&encoder);
}