mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
parameters: add simple backup and restore mechanism
This commit is contained in:
parent
e692f4ca01
commit
1f6acd0171
@ -176,6 +176,16 @@ else
|
||||
cp $PARAM_FILE /fs/microsd/param_import_fail.bson &
|
||||
fi
|
||||
|
||||
# try importing from backup file
|
||||
if [ -f "/fs/microsd/parameters_backup.bson" ]
|
||||
then
|
||||
param import /fs/microsd/parameters_backup.bson
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $SDCARD_AVAILABLE = yes ]
|
||||
then
|
||||
param select-backup /fs/microsd/parameters_backup.bson
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X
|
||||
|
||||
@ -3,6 +3,8 @@
|
||||
# (px4-alias.sh is expected to be in the PATH)
|
||||
. px4-alias.sh
|
||||
|
||||
param select eeprom/parameters
|
||||
|
||||
dataman start
|
||||
|
||||
simulator start
|
||||
|
||||
@ -395,6 +395,22 @@ __EXPORT int param_set_default_file(const char *filename);
|
||||
*/
|
||||
__EXPORT const char *param_get_default_file(void);
|
||||
|
||||
/**
|
||||
* Set the backup parameter file name.
|
||||
*
|
||||
* @param filename Path to the backup parameter file. The file is not required to
|
||||
* exist.
|
||||
* @return Zero on success.
|
||||
*/
|
||||
__EXPORT int param_set_backup_file(const char *filename);
|
||||
|
||||
/**
|
||||
* Get the backup parameter file name.
|
||||
*
|
||||
* @return The path to the backup parameter file
|
||||
*/
|
||||
__EXPORT const char *param_get_backup_file(void);
|
||||
|
||||
/**
|
||||
* Save parameters to the default file.
|
||||
* Note: this method requires a large amount of stack size!
|
||||
|
||||
@ -71,15 +71,14 @@ using namespace time_literals;
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
#include "flashparams/flashparams.h"
|
||||
static const char *param_default_file = nullptr; // nullptr means to store to FLASH
|
||||
#else
|
||||
inline static int flash_param_save(bool only_unsaved, param_filter_func filter) { return -1; }
|
||||
inline static int flash_param_load() { return -1; }
|
||||
inline static int flash_param_import() { return -1; }
|
||||
static const char *param_default_file = PX4_ROOTFSDIR"/eeprom/parameters";
|
||||
#endif
|
||||
|
||||
static char *param_user_file = nullptr;
|
||||
static char *param_default_file = nullptr;
|
||||
static char *param_backup_file = nullptr;
|
||||
|
||||
#include <px4_platform_common/workqueue.h>
|
||||
/* autosaving variables */
|
||||
@ -1080,19 +1079,24 @@ param_reset_specific(const char *resets[], int num_resets)
|
||||
int
|
||||
param_set_default_file(const char *filename)
|
||||
{
|
||||
if ((param_backup_file && strcmp(filename, param_backup_file) == 0)) {
|
||||
PX4_ERR("default file can't be the same as the backup file %s", filename);
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
#ifdef FLASH_BASED_PARAMS
|
||||
// the default for flash-based params is always the FLASH
|
||||
(void)filename;
|
||||
#else
|
||||
|
||||
if (param_user_file != nullptr) {
|
||||
if (param_default_file != nullptr) {
|
||||
// we assume this is not in use by some other thread
|
||||
free(param_user_file);
|
||||
param_user_file = nullptr;
|
||||
free(param_default_file);
|
||||
param_default_file = nullptr;
|
||||
}
|
||||
|
||||
if (filename) {
|
||||
param_user_file = strdup(filename);
|
||||
param_default_file = strdup(filename);
|
||||
}
|
||||
|
||||
#endif /* FLASH_BASED_PARAMS */
|
||||
@ -1100,27 +1104,42 @@ param_set_default_file(const char *filename)
|
||||
return 0;
|
||||
}
|
||||
|
||||
const char *
|
||||
param_get_default_file()
|
||||
const char *param_get_default_file()
|
||||
{
|
||||
return (param_user_file != nullptr) ? param_user_file : param_default_file;
|
||||
return param_default_file;
|
||||
}
|
||||
|
||||
int param_save_default()
|
||||
int param_set_backup_file(const char *filename)
|
||||
{
|
||||
int res = PX4_ERROR;
|
||||
|
||||
const char *filename = param_get_default_file();
|
||||
|
||||
if (!filename) {
|
||||
param_lock_writer();
|
||||
perf_begin(param_export_perf);
|
||||
res = flash_param_save(false, nullptr);
|
||||
perf_end(param_export_perf);
|
||||
param_unlock_writer();
|
||||
return res;
|
||||
if (param_default_file && strcmp(filename, param_default_file) == 0) {
|
||||
PX4_ERR("backup file can't be the same as the default file %s", filename);
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (param_backup_file != nullptr) {
|
||||
// we assume this is not in use by some other thread
|
||||
free(param_backup_file);
|
||||
param_backup_file = nullptr;
|
||||
}
|
||||
|
||||
if (filename) {
|
||||
param_backup_file = strdup(filename);
|
||||
|
||||
} else {
|
||||
param_backup_file = nullptr; // backup disabled
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
const char *param_get_backup_file()
|
||||
{
|
||||
return param_backup_file;
|
||||
}
|
||||
|
||||
static int param_save_file_internal(const char *filename)
|
||||
{
|
||||
int res = PX4_ERROR;
|
||||
int attempts = 5;
|
||||
|
||||
while (res != OK && attempts > 0) {
|
||||
@ -1131,7 +1150,10 @@ int param_save_default()
|
||||
res = param_export(fd, false, nullptr);
|
||||
::close(fd);
|
||||
|
||||
if (res != PX4_OK) {
|
||||
if (res == PX4_OK) {
|
||||
return PX4_OK;
|
||||
|
||||
} else {
|
||||
PX4_ERR("param_export failed, retrying %d", attempts);
|
||||
px4_usleep(10000); // wait at least 10 milliseconds before trying again
|
||||
}
|
||||
@ -1147,6 +1169,30 @@ int param_save_default()
|
||||
PX4_ERR("failed to write parameters to file: %s", filename);
|
||||
}
|
||||
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
int param_save_default()
|
||||
{
|
||||
int res = PX4_ERROR;
|
||||
const char *filename = param_get_default_file();
|
||||
|
||||
if (filename) {
|
||||
res = param_save_file_internal(filename);
|
||||
|
||||
} else {
|
||||
param_lock_writer();
|
||||
perf_begin(param_export_perf);
|
||||
res = flash_param_save(false, nullptr);
|
||||
perf_end(param_export_perf);
|
||||
param_unlock_writer();
|
||||
}
|
||||
|
||||
// backup file
|
||||
if (param_backup_file) {
|
||||
param_save_file_internal(param_backup_file);
|
||||
}
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
@ -1593,6 +1639,10 @@ void param_print_status()
|
||||
PX4_INFO("file: %s", param_get_default_file());
|
||||
}
|
||||
|
||||
if (param_backup_file) {
|
||||
PX4_INFO("backup file: %s", param_backup_file);
|
||||
}
|
||||
|
||||
#endif /* FLASH_BASED_PARAMS */
|
||||
|
||||
if (param_values != nullptr) {
|
||||
|
||||
@ -140,7 +140,10 @@ $ reboot
|
||||
PRINT_MODULE_USAGE_ARG("<file>", "File name (use default if not given)", true);
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("select", "Select default file");
|
||||
PRINT_MODULE_USAGE_ARG("<file>", "File name (use <root>/eeprom/parameters if not given)", true);
|
||||
PRINT_MODULE_USAGE_ARG("<file>", "File name", true);
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("select-backup", "Select default file");
|
||||
PRINT_MODULE_USAGE_ARG("<file>", "File name", true);
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("show", "Show parameter values");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('a', "Show all parameters (not just used)", true);
|
||||
@ -253,6 +256,23 @@ param_main(int argc, char *argv[])
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "select-backup")) {
|
||||
if (argc >= 3) {
|
||||
param_set_backup_file(argv[2]);
|
||||
|
||||
} else {
|
||||
param_set_backup_file(nullptr);
|
||||
}
|
||||
|
||||
const char *backup_file = param_get_backup_file();
|
||||
|
||||
if (backup_file) {
|
||||
PX4_INFO("selected parameter backup file %s", backup_file);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "show")) {
|
||||
if (argc >= 3) {
|
||||
// optional argument -c to show only non-default params
|
||||
@ -525,6 +545,8 @@ do_import(const char *param_file_name)
|
||||
PX4_ERR("open '%s' failed (%i)", param_file_name, errno);
|
||||
return 1;
|
||||
}
|
||||
|
||||
PX4_INFO("importing from '%s'", param_file_name);
|
||||
}
|
||||
|
||||
int result = param_import(fd, mark_saved);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user