forked from Archive/PX4-Autopilot
parameters use bitset for mark_unsaved
This commit is contained in:
parent
0e0639a5bf
commit
38731662c6
|
@ -80,6 +80,14 @@ public:
|
|||
}
|
||||
}
|
||||
|
||||
void reset()
|
||||
{
|
||||
// set bits to false
|
||||
for (auto &d : _data) {
|
||||
d.store(0);
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
static constexpr uint8_t BITS_PER_ELEMENT = 32;
|
||||
static constexpr size_t ARRAY_SIZE = ((N % BITS_PER_ELEMENT) == 0) ? (N / BITS_PER_ELEMENT) :
|
||||
|
|
|
@ -76,6 +76,14 @@ public:
|
|||
}
|
||||
}
|
||||
|
||||
void reset()
|
||||
{
|
||||
// set bits to false
|
||||
for (auto &d : _data) {
|
||||
d = 0;
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
static constexpr uint8_t BITS_PER_ELEMENT = 8;
|
||||
static constexpr size_t ARRAY_SIZE = (N % BITS_PER_ELEMENT == 0) ? N / BITS_PER_ELEMENT : N / BITS_PER_ELEMENT + 1;
|
||||
|
|
|
@ -72,11 +72,10 @@
|
|||
struct param_wbuf_s {
|
||||
union param_value_u val;
|
||||
param_t param;
|
||||
bool unsaved;
|
||||
};
|
||||
|
||||
static int
|
||||
param_export_internal(bool only_unsaved, param_filter_func filter)
|
||||
param_export_internal(param_filter_func filter)
|
||||
{
|
||||
struct param_wbuf_s *s = nullptr;
|
||||
bson_encoder_s encoder{};
|
||||
|
@ -97,20 +96,10 @@ param_export_internal(bool only_unsaved, param_filter_func filter)
|
|||
int32_t i;
|
||||
float f;
|
||||
|
||||
/*
|
||||
* If we are only saving values changed since last save, and this
|
||||
* one hasn't, then skip it
|
||||
*/
|
||||
if (only_unsaved && !s->unsaved) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (filter && !filter(s->param)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
s->unsaved = false;
|
||||
|
||||
/* append the appropriate BSON type object */
|
||||
|
||||
switch (param_type(s->param)) {
|
||||
|
@ -310,9 +299,9 @@ out:
|
|||
return result;
|
||||
}
|
||||
|
||||
int flash_param_save(bool only_unsaved, param_filter_func filter)
|
||||
int flash_param_save(param_filter_func filter)
|
||||
{
|
||||
return param_export_internal(only_unsaved, filter);
|
||||
return param_export_internal(filter);
|
||||
}
|
||||
|
||||
int flash_param_load()
|
||||
|
|
|
@ -62,7 +62,7 @@ __EXPORT int param_set_external(param_t param, const void *val, bool mark_saved,
|
|||
__EXPORT const void *param_get_value_ptr_external(param_t param);
|
||||
|
||||
/* The interface hooks to the Flash based storage. The caller is responsible for locking */
|
||||
__EXPORT int flash_param_save(bool only_unsaved, param_filter_func filter);
|
||||
__EXPORT int flash_param_save(param_filter_func filter);
|
||||
__EXPORT int flash_param_load();
|
||||
__EXPORT int flash_param_import();
|
||||
|
||||
|
|
|
@ -318,12 +318,11 @@ __EXPORT void param_reset_specific(const char *resets[], int num_resets);
|
|||
* Note: this method requires a large amount of stack size!
|
||||
*
|
||||
* @param fd File descriptor to export to (-1 selects the FLASH storage).
|
||||
* @param only_unsaved Only export changed parameters that have not yet been exported.
|
||||
* @param filter Filter parameters to be exported. The method should return true if
|
||||
* the parameter should be exported. No filtering if nullptr is passed.
|
||||
* @return Zero on success, nonzero on failure.
|
||||
*/
|
||||
__EXPORT int param_export(int fd, bool only_unsaved, param_filter_func filter);
|
||||
__EXPORT int param_export(int fd, param_filter_func filter);
|
||||
|
||||
/**
|
||||
* Import parameters from a file, discarding any unrecognized parameters.
|
||||
|
|
|
@ -72,7 +72,7 @@ using namespace time_literals;
|
|||
#if defined(FLASH_BASED_PARAMS)
|
||||
#include "flashparams/flashparams.h"
|
||||
#else
|
||||
inline static int flash_param_save(bool only_unsaved, param_filter_func filter) { return -1; }
|
||||
inline static int flash_param_save(param_filter_func filter) { return -1; }
|
||||
inline static int flash_param_load() { return -1; }
|
||||
inline static int flash_param_import() { return -1; }
|
||||
#endif
|
||||
|
@ -91,12 +91,12 @@ static constexpr uint16_t param_info_count = sizeof(px4::parameters) / sizeof(pa
|
|||
static px4::AtomicBitset<param_info_count> params_active; // params found
|
||||
static px4::AtomicBitset<param_info_count> params_changed; // params non-default
|
||||
static px4::Bitset<param_info_count> params_custom_default; // params with runtime default value
|
||||
static px4::AtomicBitset<param_info_count> params_unsaved;
|
||||
|
||||
// Storage for modified parameters.
|
||||
struct param_wbuf_s {
|
||||
union param_value_u val;
|
||||
param_t param;
|
||||
bool unsaved;
|
||||
};
|
||||
|
||||
/** flexible array holding modified parameter values */
|
||||
|
@ -413,12 +413,7 @@ bool param_is_volatile(param_t param)
|
|||
bool
|
||||
param_value_unsaved(param_t param)
|
||||
{
|
||||
struct param_wbuf_s *s;
|
||||
param_lock_reader();
|
||||
s = param_find_changed(param);
|
||||
bool ret = s && s->unsaved;
|
||||
param_unlock_reader();
|
||||
return ret;
|
||||
return handle_in_range(param) ? params_unsaved[param] : false;
|
||||
}
|
||||
|
||||
size_t param_size(param_t param)
|
||||
|
@ -740,9 +735,8 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_
|
|||
utarray_new(param_values, ¶m_icd);
|
||||
|
||||
// mark all parameters unchanged (default)
|
||||
for (int i = 0; i < params_changed.size(); i++) {
|
||||
params_changed.set(i, false);
|
||||
}
|
||||
params_changed.reset();
|
||||
params_unsaved.reset();
|
||||
}
|
||||
|
||||
if (param_values == nullptr) {
|
||||
|
@ -768,31 +762,41 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_
|
|||
s = param_find_changed(param);
|
||||
}
|
||||
|
||||
if (s != nullptr) {
|
||||
if (s == nullptr) {
|
||||
PX4_ERR("error param_values storage slot invalid");
|
||||
|
||||
} else {
|
||||
/* update the changed value */
|
||||
switch (param_type(param)) {
|
||||
case PARAM_TYPE_INT32:
|
||||
param_changed = param_changed || s->val.i != *(int32_t *)val;
|
||||
s->val.i = *(int32_t *)val;
|
||||
s->unsaved = !mark_saved;
|
||||
if (s->val.i != *(int32_t *)val) {
|
||||
s->val.i = *(int32_t *)val;
|
||||
param_changed = true;
|
||||
}
|
||||
|
||||
params_changed.set(param, true);
|
||||
params_unsaved.set(param, !mark_saved);
|
||||
result = PX4_OK;
|
||||
break;
|
||||
|
||||
case PARAM_TYPE_FLOAT:
|
||||
param_changed = param_changed || fabsf(s->val.f - * (float *)val) > FLT_EPSILON;
|
||||
s->val.f = *(float *)val;
|
||||
s->unsaved = !mark_saved;
|
||||
if (fabsf(s->val.f - * (float *)val) > FLT_EPSILON) {
|
||||
s->val.f = *(float *)val;
|
||||
param_changed = true;
|
||||
}
|
||||
|
||||
params_changed.set(param, true);
|
||||
params_unsaved.set(param, !mark_saved);
|
||||
result = PX4_OK;
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_ERR("param_set invalid param type for %s", param_name(param));
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if ((result == PX4_OK) && !mark_saved) { // this is false when importing parameters
|
||||
if ((result == PX4_OK) && param_changed && !mark_saved) { // this is false when importing parameters
|
||||
param_autosave();
|
||||
}
|
||||
}
|
||||
|
@ -870,15 +874,13 @@ int param_set_default_value(param_t param, const void *val)
|
|||
utarray_new(param_custom_default_values, ¶m_icd);
|
||||
|
||||
// mark all parameters unchanged (default)
|
||||
for (int i = 0; i < params_custom_default.size(); i++) {
|
||||
params_custom_default.set(i, false);
|
||||
}
|
||||
}
|
||||
params_custom_default.reset();
|
||||
|
||||
if (param_custom_default_values == nullptr) {
|
||||
PX4_ERR("failed to allocate custom default values array");
|
||||
param_unlock_writer();
|
||||
return PX4_ERROR;
|
||||
if (param_custom_default_values == nullptr) {
|
||||
PX4_ERR("failed to allocate custom default values array");
|
||||
param_unlock_writer();
|
||||
return PX4_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
// check if param being set to default value
|
||||
|
@ -890,7 +892,7 @@ int param_set_default_value(param_t param, const void *val)
|
|||
break;
|
||||
|
||||
case PARAM_TYPE_FLOAT:
|
||||
setting_to_static_default = (fabsf(px4::parameters[param].val.f - * (float *)val) < FLT_EPSILON);
|
||||
setting_to_static_default = (fabsf(px4::parameters[param].val.f - * (float *)val) <= FLT_EPSILON);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -977,6 +979,7 @@ static int param_reset_internal(param_t param, bool notify = true)
|
|||
}
|
||||
|
||||
params_changed.set(param, false);
|
||||
params_unsaved.set(param, true);
|
||||
|
||||
param_found = true;
|
||||
}
|
||||
|
@ -1003,9 +1006,7 @@ param_reset_all_internal(bool auto_save)
|
|||
if (param_values != nullptr) {
|
||||
utarray_free(param_values);
|
||||
|
||||
for (int i = 0; i < params_changed.size(); i++) {
|
||||
params_changed.set(i, false);
|
||||
}
|
||||
params_changed.reset();
|
||||
}
|
||||
|
||||
/* mark as reset / deleted */
|
||||
|
@ -1147,7 +1148,7 @@ static int param_save_file_internal(const char *filename)
|
|||
int fd = ::open(filename, O_WRONLY | O_CREAT, PX4_O_MODE_666);
|
||||
|
||||
if (fd > -1) {
|
||||
res = param_export(fd, false, nullptr);
|
||||
res = param_export(fd, nullptr);
|
||||
::close(fd);
|
||||
|
||||
if (res == PX4_OK) {
|
||||
|
@ -1184,6 +1185,7 @@ int param_save_default()
|
|||
param_lock_writer();
|
||||
perf_begin(param_export_perf);
|
||||
res = flash_param_save(false, nullptr);
|
||||
params_unsaved.reset();
|
||||
perf_end(param_export_perf);
|
||||
param_unlock_writer();
|
||||
}
|
||||
|
@ -1233,7 +1235,7 @@ param_load_default()
|
|||
}
|
||||
|
||||
int
|
||||
param_export(int fd, bool only_unsaved, param_filter_func filter)
|
||||
param_export(int fd, param_filter_func filter)
|
||||
{
|
||||
int result = -1;
|
||||
perf_begin(param_export_perf);
|
||||
|
@ -1241,7 +1243,8 @@ param_export(int fd, bool only_unsaved, param_filter_func filter)
|
|||
if (fd < 0) {
|
||||
param_lock_writer();
|
||||
// flash_param_save() will take the shutdown lock
|
||||
result = flash_param_save(only_unsaved, filter);
|
||||
result = flash_param_save(filter);
|
||||
params_unsaved.reset();
|
||||
param_unlock_writer();
|
||||
perf_end(param_export_perf);
|
||||
return result;
|
||||
|
@ -1271,14 +1274,6 @@ param_export(int fd, bool only_unsaved, param_filter_func filter)
|
|||
}
|
||||
|
||||
while ((s = (struct param_wbuf_s *)utarray_next(param_values, s)) != nullptr) {
|
||||
/*
|
||||
* If we are only saving values changed since last save, and this
|
||||
* one hasn't, then skip it
|
||||
*/
|
||||
if (only_unsaved && !s->unsaved) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (filter && !filter(s->param)) {
|
||||
continue;
|
||||
}
|
||||
|
@ -1308,8 +1303,6 @@ param_export(int fd, bool only_unsaved, param_filter_func filter)
|
|||
break;
|
||||
}
|
||||
|
||||
s->unsaved = false;
|
||||
|
||||
const char *name = param_name(s->param);
|
||||
const size_t size = param_size(s->param);
|
||||
|
||||
|
@ -1347,7 +1340,12 @@ param_export(int fd, bool only_unsaved, param_filter_func filter)
|
|||
out:
|
||||
|
||||
if (result == 0) {
|
||||
if (bson_encoder_fini(&encoder) != PX4_OK) {
|
||||
if (bson_encoder_fini(&encoder) == PX4_OK) {
|
||||
if (!filter) {
|
||||
params_unsaved.reset();
|
||||
}
|
||||
|
||||
} else {
|
||||
PX4_ERR("BSON encoder finialize failed");
|
||||
result = -1;
|
||||
}
|
||||
|
|
|
@ -84,7 +84,7 @@ int FactoryCalibrationStorage::store()
|
|||
return 0;
|
||||
}
|
||||
|
||||
int ret = param_export(_fd, false, filter_calibration_params);
|
||||
int ret = param_export(_fd, filter_calibration_params);
|
||||
|
||||
if (ret != 0) {
|
||||
PX4_ERR("param export failed (%i)", ret);
|
||||
|
|
|
@ -441,7 +441,7 @@ do_save(const char *param_file_name)
|
|||
return 1;
|
||||
}
|
||||
|
||||
int result = param_export(fd, false, nullptr);
|
||||
int result = param_export(fd, nullptr);
|
||||
close(fd);
|
||||
|
||||
if (result < 0) {
|
||||
|
|
|
@ -408,7 +408,7 @@ bool ParameterTest::exportImportAll()
|
|||
return false;
|
||||
}
|
||||
|
||||
int result = param_export(fd, false, nullptr);
|
||||
int result = param_export(fd, nullptr);
|
||||
|
||||
if (result != PX4_OK) {
|
||||
PX4_ERR("param_export failed");
|
||||
|
|
Loading…
Reference in New Issue