mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 07:09:48 +08:00
param save: Add a blocking API for param saves to be used from shell.
This commit is contained in:
committed by
Beat Küng
parent
18f0311161
commit
fd267fb9a5
@@ -110,10 +110,22 @@ void ParamAutosave::Run()
|
||||
}
|
||||
|
||||
PX4_DEBUG("Autosaving params");
|
||||
int ret = param_save_default();
|
||||
int ret = param_save_default(false);
|
||||
|
||||
if (ret != 0) {
|
||||
PX4_ERR("param auto save failed (%i)", ret);
|
||||
if (ret != PX4_OK) {
|
||||
// re-request to be saved in the future, try 3 times at most
|
||||
if (_retry_count < 3) {
|
||||
_retry_count++;
|
||||
PX4_INFO("param auto save unavailable (%i), retrying..", ret);
|
||||
request();
|
||||
|
||||
} else {
|
||||
PX4_ERR("param auto save failed (%i)", ret);
|
||||
_retry_count = 0;
|
||||
}
|
||||
|
||||
} else {
|
||||
_retry_count = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -59,5 +59,6 @@ public:
|
||||
private:
|
||||
hrt_abstime _last_timestamp{0};
|
||||
px4::atomic_bool _scheduled{false};
|
||||
int _retry_count{0};
|
||||
bool _disabled{false};
|
||||
};
|
||||
|
||||
@@ -400,13 +400,17 @@ __EXPORT const char *param_get_backup_file(void);
|
||||
|
||||
/**
|
||||
* Save parameters to the default file.
|
||||
*
|
||||
* Note: this method requires a large amount of stack size!
|
||||
*
|
||||
* This function saves all parameters with non-default values.
|
||||
*
|
||||
* @return Zero on success.
|
||||
* @param blocking If true, in case the default file is busy, the function blocks
|
||||
* until the file is available for writing.
|
||||
*
|
||||
* @return Zero on success, -EWOULDBLOCK if the file is busy and blocking is false.
|
||||
*/
|
||||
__EXPORT int param_save_default(void);
|
||||
__EXPORT int param_save_default(bool blocking);
|
||||
|
||||
/**
|
||||
* Load parameters from the default parameter file.
|
||||
|
||||
@@ -698,14 +698,19 @@ const char *param_get_backup_file()
|
||||
static int param_export_internal(int fd, param_filter_func filter);
|
||||
static int param_verify(int fd);
|
||||
|
||||
int param_save_default()
|
||||
int param_save_default(bool blocking)
|
||||
{
|
||||
PX4_DEBUG("param_save_default");
|
||||
|
||||
// take the file lock
|
||||
if (pthread_mutex_trylock(&file_mutex) != 0) {
|
||||
PX4_ERR("param_save_default: file lock failed (already locked)");
|
||||
return PX4_ERROR;
|
||||
if (blocking) {
|
||||
pthread_mutex_lock(&file_mutex);
|
||||
|
||||
} else {
|
||||
if (pthread_mutex_trylock(&file_mutex) != 0) {
|
||||
PX4_DEBUG("param_save_default: file lock failed (already locked)");
|
||||
return -EWOULDBLOCK;
|
||||
}
|
||||
}
|
||||
|
||||
int shutdown_lock_ret = px4_shutdown_lock();
|
||||
|
||||
@@ -168,7 +168,7 @@ int param_ioctl(unsigned int cmd, unsigned long arg)
|
||||
|
||||
case PARAMIOCSAVEDEFAULT: {
|
||||
paramiocsavedefault_t *data = (paramiocsavedefault_t *)arg;
|
||||
data->ret = param_save_default();
|
||||
data->ret = param_save_default(data->blocking);
|
||||
}
|
||||
break;
|
||||
|
||||
|
||||
@@ -140,6 +140,7 @@ typedef struct paramiocresetgroup {
|
||||
|
||||
#define PARAMIOCSAVEDEFAULT _PARAMIOC(15)
|
||||
typedef struct paramiocsavedefault {
|
||||
bool blocking;
|
||||
int ret;
|
||||
} paramiocsavedefault_t;
|
||||
|
||||
|
||||
@@ -187,9 +187,9 @@ param_reset_specific(const char *resets[], int num_resets)
|
||||
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
|
||||
}
|
||||
|
||||
int param_save_default()
|
||||
int param_save_default(bool blocking)
|
||||
{
|
||||
paramiocsavedefault_t data = {PX4_ERROR};
|
||||
paramiocsavedefault_t data = {blocking, PX4_ERROR};
|
||||
boardctl(PARAMIOCSAVEDEFAULT, reinterpret_cast<unsigned long>(&data));
|
||||
return data.ret;
|
||||
}
|
||||
|
||||
@@ -180,7 +180,7 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub)
|
||||
|
||||
/* save */
|
||||
calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG, 0);
|
||||
param_save_default();
|
||||
param_save_default(true);
|
||||
|
||||
feedback_calibration_failed(mavlink_log_pub);
|
||||
return PX4_ERROR;
|
||||
|
||||
@@ -158,7 +158,7 @@ void WorkerThread::threadEntry()
|
||||
break;
|
||||
|
||||
case Request::ParamSaveDefault:
|
||||
_ret_value = param_save_default();
|
||||
_ret_value = param_save_default(true);
|
||||
|
||||
if (_ret_value != 0) {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Error saving settings\t");
|
||||
@@ -175,7 +175,7 @@ void WorkerThread::threadEntry()
|
||||
case Request::ParamResetSensorFactory: {
|
||||
const char *reset_cal[] = { "CAL_ACC*", "CAL_GYRO*", "CAL_MAG*" };
|
||||
param_reset_specific(reset_cal, sizeof(reset_cal) / sizeof(reset_cal[0]));
|
||||
_ret_value = param_save_default();
|
||||
_ret_value = param_save_default(true);
|
||||
#if defined(CONFIG_BOARDCTL_RESET)
|
||||
px4_reboot_request(false, 400_ms);
|
||||
#endif // CONFIG_BOARDCTL_RESET
|
||||
|
||||
@@ -284,7 +284,7 @@ void TemperatureCalibration::task_main()
|
||||
}
|
||||
|
||||
param_notify_changes();
|
||||
int ret = param_save_default();
|
||||
int ret = param_save_default(true);
|
||||
|
||||
if (ret != 0) {
|
||||
PX4_ERR("Failed to save params (%i)", ret);
|
||||
|
||||
@@ -509,7 +509,7 @@ do_import(const char *param_file_name)
|
||||
static int
|
||||
do_save_default()
|
||||
{
|
||||
return param_save_default();
|
||||
return param_save_default(true);
|
||||
}
|
||||
|
||||
static int
|
||||
|
||||
@@ -316,7 +316,7 @@ bool ParameterTest::exportImport()
|
||||
}
|
||||
|
||||
// save
|
||||
if (param_save_default() != PX4_OK) {
|
||||
if (param_save_default(true) != PX4_OK) {
|
||||
PX4_ERR("param_save_default failed");
|
||||
return false;
|
||||
}
|
||||
@@ -461,7 +461,7 @@ bool ParameterTest::exportImportAll()
|
||||
}
|
||||
|
||||
// save
|
||||
if (param_save_default() != PX4_OK) {
|
||||
if (param_save_default(true) != PX4_OK) {
|
||||
PX4_ERR("param_save_default failed");
|
||||
return false;
|
||||
}
|
||||
@@ -561,7 +561,7 @@ bool ParameterTest::exportImportAll()
|
||||
}
|
||||
|
||||
// save
|
||||
if (param_save_default() != PX4_OK) {
|
||||
if (param_save_default(true) != PX4_OK) {
|
||||
PX4_ERR("param_save_default failed");
|
||||
return false;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user