parameter server continued

This commit is contained in:
Daniel Agar 2022-12-10 22:07:04 -05:00
parent 481addbcac
commit 6fd19df64e
No known key found for this signature in database
GPG Key ID: FD3CBA98017A69DE
11 changed files with 290 additions and 860 deletions

View File

@ -181,10 +181,10 @@ int px4_platform_init()
px4::WorkQueueManagerStart();
param_init();
uorb_start();
param_init();
px4_log_initialize();
#if defined(CONFIG_SYSTEM_CDCACM) && defined(CONFIG_BUILD_FLAT)

View File

@ -46,10 +46,10 @@ int px4_platform_init(void)
px4::WorkQueueManagerStart();
param_init();
uorb_start();
param_init();
px4_log_initialize();
return PX4_OK;

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2017 - 2020 PX4 Development Team. All rights reserved.
# Copyright (c) 2017 - 2022 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -159,18 +159,6 @@ else()
list(APPEND SRCS param_translation.cpp)
endif()
if(${PX4_PLATFORM} STREQUAL "nuttx")
# add_subdirectory(flashparams)
# # build user-side interface for protected build
# if(NOT CONFIG_BUILD_FLAT)
# list(APPEND SRCS parameters_ioctl.cpp)
# add_library(usr_parameters usr_parameters_if.cpp px4_parameters.hpp)
# add_dependencies(usr_parameters prebuild_targets)
# target_compile_definitions(usr_parameters PRIVATE -DMODULE_NAME="usr_parameters")
# endif()
endif()
# TODO: find a better way to do this
if(NOT "${PX4_BOARD}" MATCHES "px4_io")
add_library(parameters STATIC EXCLUDE_FROM_ALL
@ -182,10 +170,11 @@ if(NOT "${PX4_BOARD}" MATCHES "px4_io")
target_link_libraries(parameters PRIVATE perf tinybson px4_platform)
target_compile_definitions(parameters PRIVATE -DMODULE_NAME="parameters" -D__KERNEL__)
target_compile_definitions(parameters PRIVATE -DMODULE_NAME="parameters")
target_compile_options(parameters
PRIVATE
#-DDEBUG_BUILD
#${MAX_CUSTOM_OPT_LEVEL}
-Wno-cast-align # TODO: fix and enable
-Wno-sign-compare # TODO: fix and enable
)

View File

@ -50,72 +50,63 @@
// #endif
ParameterServer::ParameterServer() :
ScheduledWorkItem("parameter_server", px4::wq_configurations::lp_default)
ScheduledWorkItem("parameter_server", px4::wq_configurations::hp_default)
{
px4_sem_init(&param_sem, 0, 1);
px4_sem_init(&param_sem_save, 0, 1);
px4_sem_init(&reader_lock_holders_lock, 0, 1);
px4_sem_init(&_param_sem, 0, 1);
px4_sem_init(&_param_sem_save, 0, 1);
px4_sem_init(&_reader_lock_holders_lock, 0, 1);
param_export_perf = perf_alloc(PC_ELAPSED, "param: export");
param_find_perf = perf_alloc(PC_COUNT, "param: find");
param_get_perf = perf_alloc(PC_COUNT, "param: get");
param_set_perf = perf_alloc(PC_ELAPSED, "param: set");
#if defined(__PX4_NUTTX) && !defined(CONFIG_BUILD_FLAT)
px4_register_boardct_ioctl(_PARAMIOCBASE, param_ioctl);
#endif
ScheduleOnInterval(1_s);
_param_request_sub.registerCallback();
}
ParameterServer::~ParameterServer()
{
px4_sem_destroy(&param_sem);
px4_sem_destroy(&param_sem_save);
px4_sem_destroy(&reader_lock_holders_lock);
px4_sem_destroy(&_param_sem);
px4_sem_destroy(&_param_sem_save);
px4_sem_destroy(&_reader_lock_holders_lock);
perf_free(param_export_perf);
perf_free(param_find_perf);
perf_free(param_get_perf);
perf_free(param_set_perf);
perf_free(_export_perf);
perf_free(_find_count_perf);
perf_free(_get_count_perf);
perf_free(_set_perf);
}
void ParameterServer::lockReader()
{
do {} while (px4_sem_wait(&reader_lock_holders_lock) != 0);
do {} while (px4_sem_wait(&_reader_lock_holders_lock) != 0);
++reader_lock_holders;
++_reader_lock_holders;
if (reader_lock_holders == 1) {
if (_reader_lock_holders == 1) {
// the first reader takes the lock, the next ones are allowed to just continue
do {} while (px4_sem_wait(&param_sem) != 0);
do {} while (px4_sem_wait(&_param_sem) != 0);
}
px4_sem_post(&reader_lock_holders_lock);
px4_sem_post(&_reader_lock_holders_lock);
}
void ParameterServer::lockWriter()
{
do {} while (px4_sem_wait(&param_sem) != 0);
do {} while (px4_sem_wait(&_param_sem) != 0);
}
void ParameterServer::unlockReader()
{
do {} while (px4_sem_wait(&reader_lock_holders_lock) != 0);
do {} while (px4_sem_wait(&_reader_lock_holders_lock) != 0);
--reader_lock_holders;
--_reader_lock_holders;
if (reader_lock_holders == 0) {
if (_reader_lock_holders == 0) {
// the last reader releases the lock
px4_sem_post(&param_sem);
px4_sem_post(&_param_sem);
}
px4_sem_post(&reader_lock_holders_lock);
px4_sem_post(&_reader_lock_holders_lock);
}
void ParameterServer::unlockWriter()
{
px4_sem_post(&param_sem);
px4_sem_post(&_param_sem);
}
int ParameterServer::compareValues(const void *a, const void *b)
@ -136,10 +127,10 @@ int ParameterServer::compareValues(const void *a, const void *b)
ParameterServer::param_wbuf_s *ParameterServer::findChanged(param_t param)
{
if (params_changed[param] && (param_values != nullptr)) {
if (_params_changed[param] && (_param_values != nullptr)) {
param_wbuf_s key{};
key.param = param;
return (param_wbuf_s *)utarray_find(param_values, &key, ParameterServer::compareValues);
return (param_wbuf_s *)utarray_find(_param_values, &key, ParameterServer::compareValues);
}
return nullptr;
@ -155,11 +146,11 @@ const void *ParameterServer::getParameterValuePointer(param_t param)
return &s->val;
} else {
if (params_custom_default[param] && param_custom_default_values) {
if (_params_custom_default[param] && _param_custom_default_values) {
// get default from custom default storage
param_wbuf_s key{};
key.param = param;
param_wbuf_s *pbuf = (param_wbuf_s *)utarray_find(param_custom_default_values, &key, ParameterServer::compareValues);
param_wbuf_s *pbuf = (param_wbuf_s *)utarray_find(_param_custom_default_values, &key, ParameterServer::compareValues);
if (pbuf != nullptr) {
return &pbuf->val;
@ -188,11 +179,11 @@ int ParameterServer::getParameterDefaultValueInternal(param_t param, void *defau
}
if (default_val) {
if (params_custom_default[param] && param_custom_default_values) {
if (_params_custom_default[param] && _param_custom_default_values) {
// get default from custom default storage
param_wbuf_s key{};
key.param = param;
param_wbuf_s *pbuf = (param_wbuf_s *)utarray_find(param_custom_default_values, &key, ParameterServer::compareValues);
param_wbuf_s *pbuf = (param_wbuf_s *)utarray_find(_param_custom_default_values, &key, ParameterServer::compareValues);
if (pbuf != nullptr) {
memcpy(default_val, &pbuf->val, getParameterSize(param));
@ -217,7 +208,7 @@ int ParameterServer::getParameterDefaultValueInternal(param_t param, void *defau
param_t ParameterServer::findParameter(const char *name, bool notification)
{
perf_count(param_find_perf);
perf_count(_find_count_perf);
param_t middle;
param_t front = 0;
@ -254,7 +245,7 @@ param_t ParameterServer::findParameter(const char *name, bool notification)
bool ParameterServer::isParameterUsed(param_t param) const
{
if (handle_in_range(param)) {
return params_active[param];
return _params_active[param];
}
return false;
@ -275,8 +266,8 @@ param_t ParameterServer::forUsedIndex(unsigned index) const
if (index < param_info_count) {
unsigned used_count = 0;
for (int i = 0; i < params_active.size(); i++) {
if (params_active[i]) {
for (int i = 0; i < _params_active.size(); i++) {
if (_params_active[i]) {
// we found the right used count,
// return the param value
if (index == used_count) {
@ -310,8 +301,8 @@ int ParameterServer::getParameterUsedIndex(param_t param) const
// walk all params and count, now knowing that it has a valid index
int used_count = 0;
for (int i = 0; i < params_active.size(); i++) {
if (params_active[i]) {
for (int i = 0; i < _params_active.size(); i++) {
if (_params_active[i]) {
if (param == i) {
return used_count;
@ -352,13 +343,13 @@ bool ParameterServer::isParameterValueDefault(param_t param)
return true;
}
if (!params_changed[param] && !params_custom_default[param]) {
if (!_params_changed[param] && !_params_custom_default[param]) {
// no value saved and no custom default
return true;
} else {
// the param_values dynamic array might carry things that have been set
// back to default, so we don't rely on the params_changed bitset here
// the _param_values dynamic array might carry things that have been set
// back to default, so we don't rely on the _params_changed bitset here
switch (getParameterType(param)) {
case PARAM_TYPE_INT32: {
lockReader();
@ -403,7 +394,7 @@ bool ParameterServer::isParameterValueDefault(param_t param)
bool ParameterServer::isParameterValueUnsaved(param_t param)
{
return handle_in_range(param) ? params_unsaved[param] : false;
return handle_in_range(param) ? _params_unsaved[param] : false;
}
param_type_t ParameterServer::getParameterType(param_t param) const
@ -429,21 +420,21 @@ size_t ParameterServer::getParameterSize(param_t param) const
int ParameterServer::getParameterValue(param_t param, void *val)
{
perf_count(param_get_perf);
perf_count(_get_count_perf);
if (!handle_in_range(param)) {
PX4_ERR("get: param %" PRId16 " invalid", param);
return PX4_ERROR;
}
if (!params_active[param]) {
if (!_params_active[param]) {
PX4_DEBUG("get: param %" PRId16 " (%s) not active", param, getParameterName(param));
}
int result = PX4_ERROR;
if (val) {
if (!params_changed[param] && !params_custom_default[param]) {
if (!_params_changed[param] && !_params_custom_default[param]) {
// if parameter is unchanged (static default value) copy immediately and avoid locking
switch (getParameterType(param)) {
case PARAM_TYPE_INT32:
@ -478,7 +469,7 @@ int ParameterServer::getParameterDefaultValue(param_t param, void *default_val)
int ret = 0;
if (!params_custom_default[param]) {
if (!_params_custom_default[param]) {
// return static default value
switch (getParameterType(param)) {
case PARAM_TYPE_INT32:
@ -540,18 +531,18 @@ int ParameterServer::setParameter(param_t param, const void *val, bool mark_save
bool param_changed = false;
lockWriter();
perf_begin(param_set_perf);
perf_begin(_set_perf);
// create the parameter store if it doesn't exist
if (param_values == nullptr) {
utarray_new(param_values, &param_icd);
if (_param_values == nullptr) {
utarray_new(_param_values, &param_icd);
// mark all parameters unchanged (default)
params_changed.reset();
params_unsaved.reset();
_params_changed.reset();
_params_unsaved.reset();
}
if (param_values == nullptr) {
if (_param_values == nullptr) {
PX4_ERR("failed to allocate modified values array");
goto out;
@ -566,16 +557,16 @@ int ParameterServer::setParameter(param_t param, const void *val, bool mark_save
param_changed = true;
/* add it to the array and sort */
utarray_push_back(param_values, &buf);
utarray_sort(param_values, ParameterServer::compareValues);
params_changed.set(param, true);
utarray_push_back(_param_values, &buf);
utarray_sort(_param_values, ParameterServer::compareValues);
_params_changed.set(param, true);
/* find it after sorting */
s = findChanged(param);
}
if (s == nullptr) {
PX4_ERR("error param_values storage slot invalid");
PX4_ERR("error _param_values storage slot invalid");
} else {
/* update the changed value */
@ -586,8 +577,8 @@ int ParameterServer::setParameter(param_t param, const void *val, bool mark_save
param_changed = true;
}
params_changed.set(param, true);
params_unsaved.set(param, !mark_saved);
_params_changed.set(param, true);
_params_unsaved.set(param, !mark_saved);
result = PX4_OK;
break;
@ -597,8 +588,8 @@ int ParameterServer::setParameter(param_t param, const void *val, bool mark_save
param_changed = true;
}
params_changed.set(param, true);
params_unsaved.set(param, !mark_saved);
_params_changed.set(param, true);
_params_unsaved.set(param, !mark_saved);
result = PX4_OK;
break;
@ -614,7 +605,7 @@ int ParameterServer::setParameter(param_t param, const void *val, bool mark_save
}
out:
perf_end(param_set_perf);
perf_end(_set_perf);
unlockWriter();
/*
@ -644,13 +635,13 @@ int ParameterServer::setParameterDefaultValue(param_t param, const void *val)
lockWriter();
if (param_custom_default_values == nullptr) {
utarray_new(param_custom_default_values, &param_icd);
if (_param_custom_default_values == nullptr) {
utarray_new(_param_custom_default_values, &param_icd);
// mark all parameters unchanged (default)
params_custom_default.reset();
_params_custom_default.reset();
if (param_custom_default_values == nullptr) {
if (_param_custom_default_values == nullptr) {
PX4_ERR("failed to allocate custom default values array");
unlockWriter();
return PX4_ERROR;
@ -676,18 +667,18 @@ int ParameterServer::setParameterDefaultValue(param_t param, const void *val)
{
param_wbuf_s key{};
key.param = param;
s = (param_wbuf_s *)utarray_find(param_custom_default_values, &key, ParameterServer::compareValues);
s = (param_wbuf_s *)utarray_find(_param_custom_default_values, &key, ParameterServer::compareValues);
}
if (setting_to_static_default) {
if (s != nullptr) {
// param in memory and set to non-default value, clear
int pos = utarray_eltidx(param_custom_default_values, s);
utarray_erase(param_custom_default_values, pos, 1);
int pos = utarray_eltidx(_param_custom_default_values, s);
utarray_erase(_param_custom_default_values, pos, 1);
}
// do nothing if param not already set and being set to default
params_custom_default.set(param, false);
_params_custom_default.set(param, false);
result = PX4_OK;
} else {
@ -697,11 +688,11 @@ int ParameterServer::setParameterDefaultValue(param_t param, const void *val)
buf.param = param;
// add it to the array and sort
utarray_push_back(param_custom_default_values, &buf);
utarray_sort(param_custom_default_values, ParameterServer::compareValues);
utarray_push_back(_param_custom_default_values, &buf);
utarray_sort(_param_custom_default_values, ParameterServer::compareValues);
// find it after sorting
s = (param_wbuf_s *)utarray_find(param_custom_default_values, &buf, ParameterServer::compareValues);
s = (param_wbuf_s *)utarray_find(_param_custom_default_values, &buf, ParameterServer::compareValues);
}
if (s != nullptr) {
@ -709,13 +700,13 @@ int ParameterServer::setParameterDefaultValue(param_t param, const void *val)
switch (getParameterType(param)) {
case PARAM_TYPE_INT32:
s->val.i = *(int32_t *)val;
params_custom_default.set(param, true);
_params_custom_default.set(param, true);
result = PX4_OK;
break;
case PARAM_TYPE_FLOAT:
s->val.f = *(float *)val;
params_custom_default.set(param, true);
_params_custom_default.set(param, true);
result = PX4_OK;
break;
@ -738,29 +729,15 @@ int ParameterServer::setParameterDefaultValue(param_t param, const void *val)
void ParameterServer::setParameterUsed(param_t param)
{
if (handle_in_range(param)) {
params_active.set(param, true);
_params_active.set(param, true);
}
}
void ParameterServer::notifyChanges()
{
parameter_update_s pup{};
pup.instance = param_instance++;
pup.get_count = perf_event_count(param_get_perf);
pup.set_count = perf_event_count(param_set_perf);
pup.find_count = perf_event_count(param_find_perf);
pup.export_count = perf_event_count(param_export_perf);
pup.active = params_active.count();
pup.changed = params_changed.count();
pup.custom_default = params_custom_default.count();
pup.timestamp = hrt_absolute_time();
if (param_topic == nullptr) {
param_topic = orb_advertise(ORB_ID(parameter_update), &pup);
} else {
orb_publish(ORB_ID(parameter_update), param_topic, &pup);
}
_notify_scheduled.store(true);
ScheduleDelayed(10_ms);
// TODO: delay back to back notifications
}
int ParameterServer::resetParameter(param_t param, bool notify)
@ -776,12 +753,12 @@ int ParameterServer::resetParameter(param_t param, bool notify)
/* if we found one, erase it */
if (s != nullptr) {
int pos = utarray_eltidx(param_values, s);
utarray_erase(param_values, pos, 1);
int pos = utarray_eltidx(_param_values, s);
utarray_erase(_param_values, pos, 1);
}
params_changed.set(param, false);
params_unsaved.set(param, true);
_params_changed.set(param, false);
_params_unsaved.set(param, true);
param_found = true;
}
@ -801,14 +778,14 @@ void ParameterServer::resetAllParameters(bool auto_save)
{
lockWriter();
if (param_values != nullptr) {
utarray_free(param_values);
if (_param_values != nullptr) {
utarray_free(_param_values);
params_changed.reset();
_params_changed.reset();
}
/* mark as reset / deleted */
param_values = nullptr;
_param_values = nullptr;
if (auto_save) {
autoSave();
@ -878,14 +855,14 @@ int ParameterServer::exportToFile(const char *filename, param_filter_func filter
}
// take the file lock
do {} while (px4_sem_wait(&param_sem_save) != 0);
do {} while (px4_sem_wait(&_param_sem_save) != 0);
lockReader();
int fd = ::open(filename, O_RDWR | O_CREAT, PX4_O_MODE_666);
int result = PX4_ERROR;
perf_begin(param_export_perf);
perf_begin(_export_perf);
if (fd > -1) {
result = exportInternal(fd, filter);
@ -895,10 +872,10 @@ int ParameterServer::exportToFile(const char *filename, param_filter_func filter
// result = flash_param_save(filter);
}
perf_end(param_export_perf);
perf_end(_export_perf);
unlockReader();
px4_sem_post(&param_sem_save);
px4_sem_post(&_param_sem_save);
if (shutdown_lock_ret == 0) {
px4_shutdown_unlock();
@ -1258,7 +1235,7 @@ void ParameterServer::forEachParameter(void (*func)(void *arg, param_t param), v
int ParameterServer::setDefaultFile(const char *filename)
{
if ((param_backup_file && strcmp(filename, param_backup_file) == 0)) {
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;
}
@ -1268,14 +1245,14 @@ int ParameterServer::setDefaultFile(const char *filename)
(void)filename;
#else
if (param_default_file != nullptr) {
if (_param_default_file != nullptr) {
// we assume this is not in use by some other thread
free(param_default_file);
param_default_file = nullptr;
free(_param_default_file);
_param_default_file = nullptr;
}
if (filename) {
param_default_file = strdup(filename);
_param_default_file = strdup(filename);
}
#endif /* FLASH_BASED_PARAMS */
@ -1285,22 +1262,22 @@ int ParameterServer::setDefaultFile(const char *filename)
int ParameterServer::setBackupFile(const char *filename)
{
if (param_default_file && strcmp(filename, param_default_file) == 0) {
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) {
if (_param_backup_file != nullptr) {
// we assume this is not in use by some other thread
free(param_backup_file);
param_backup_file = nullptr;
free(_param_backup_file);
_param_backup_file = nullptr;
}
if (filename) {
param_backup_file = strdup(filename);
_param_backup_file = strdup(filename);
} else {
param_backup_file = nullptr; // backup disabled
_param_backup_file = nullptr; // backup disabled
}
return 0;
@ -1316,7 +1293,7 @@ int ParameterServer::saveDefault()
}
// take the file lock
do {} while (px4_sem_wait(&param_sem_save) != 0);
do {} while (px4_sem_wait(&_param_sem_save) != 0);
lockReader();
@ -1331,9 +1308,9 @@ int ParameterServer::saveDefault()
int fd = ::open(filename, O_WRONLY | O_CREAT | O_TRUNC, PX4_O_MODE_666);
if (fd > -1) {
perf_begin(param_export_perf);
perf_begin(_export_perf);
res = exportInternal(fd, nullptr);
perf_end(param_export_perf);
perf_end(_export_perf);
::close(fd);
if (res == PX4_OK) {
@ -1355,31 +1332,31 @@ int ParameterServer::saveDefault()
} else {
// TODO: flash params
// perf_begin(param_export_perf);
// perf_begin(_export_perf);
// res = flash_param_save(nullptr);
// perf_end(param_export_perf);
// perf_end(_export_perf);
}
if (res != PX4_OK) {
PX4_ERR("param export failed (%d)", res);
} else {
params_unsaved.reset();
_params_unsaved.reset();
// backup file
if (param_backup_file) {
int fd_backup_file = ::open(param_backup_file, O_WRONLY | O_CREAT | O_TRUNC, PX4_O_MODE_666);
if (_param_backup_file) {
int fd_backup_file = ::open(_param_backup_file, O_WRONLY | O_CREAT | O_TRUNC, PX4_O_MODE_666);
if (fd_backup_file > -1) {
int backup_export_ret = exportInternal(fd_backup_file, nullptr);
::close(fd_backup_file);
if (backup_export_ret != 0) {
PX4_ERR("backup parameter export to %s failed (%d)", param_backup_file, backup_export_ret);
PX4_ERR("backup parameter export to %s failed (%d)", _param_backup_file, backup_export_ret);
} else {
// verify export
int fd_verify = ::open(param_backup_file, O_RDONLY, PX4_O_MODE_666);
int fd_verify = ::open(_param_backup_file, O_RDONLY, PX4_O_MODE_666);
verifyBsonExport(fd_verify);
::close(fd_verify);
}
@ -1388,7 +1365,7 @@ int ParameterServer::saveDefault()
}
unlockReader();
px4_sem_post(&param_sem_save);
px4_sem_post(&_param_sem_save);
if (shutdown_lock_ret == 0) {
px4_shutdown_unlock();
@ -1464,50 +1441,56 @@ void ParameterServer::printStatus()
PX4_INFO("file: %s", filename);
}
if (param_backup_file) {
PX4_INFO("backup file: %s", param_backup_file);
if (_param_backup_file) {
PX4_INFO("backup file: %s", _param_backup_file);
}
#endif /* FLASH_BASED_PARAMS */
if (param_values != nullptr) {
if (_param_values != nullptr) {
PX4_INFO("storage array: %d/%d elements (%zu bytes total)",
utarray_len(param_values), param_values->n, param_values->n * sizeof(UT_icd));
utarray_len(_param_values), _param_values->n, _param_values->n * sizeof(UT_icd));
}
if (param_custom_default_values != nullptr) {
if (_param_custom_default_values != nullptr) {
PX4_INFO("storage array (custom defaults): %d/%d elements (%zu bytes total)",
utarray_len(param_custom_default_values), param_custom_default_values->n,
param_custom_default_values->n * sizeof(UT_icd));
utarray_len(_param_custom_default_values), _param_custom_default_values->n,
_param_custom_default_values->n * sizeof(UT_icd));
}
PX4_INFO("auto save: %s", autosave_disabled ? "off" : "on");
PX4_INFO("auto save: %s", _autosave_disabled ? "off" : "on");
if (!autosave_disabled && (last_autosave_timestamp > 0)) {
PX4_INFO("last auto save: %.3f seconds ago", hrt_elapsed_time(&last_autosave_timestamp) * 1e-6);
if (!_autosave_disabled && (_last_autosave_timestamp > 0)) {
PX4_INFO("last auto save: %.3f seconds ago", hrt_elapsed_time(&_last_autosave_timestamp) * 1e-6);
}
perf_print_counter(param_export_perf);
perf_print_counter(param_find_perf);
perf_print_counter(param_get_perf);
perf_print_counter(param_set_perf);
perf_print_counter(_export_perf);
perf_print_counter(_find_count_perf);
perf_print_counter(_get_count_perf);
perf_print_counter(_set_perf);
}
void ParameterServer::controlAutosave(bool enable)
{
lockWriter();
if (!enable && autosave_scheduled.load()) {
autosave_scheduled.store(false);
if (!enable && _autosave_scheduled.load()) {
_autosave_scheduled.store(false);
}
autosave_disabled = !enable;
_autosave_disabled = !enable;
unlockWriter();
}
void ParameterServer::autoSave()
void ParameterServer::autoSave(bool now)
{
if (autosave_scheduled.load() || autosave_disabled) {
if (now) {
_autosave_scheduled.store(true);
ScheduleNow();
return;
}
if (_autosave_scheduled.load() || _autosave_disabled) {
return;
}
@ -1518,13 +1501,13 @@ void ParameterServer::autoSave()
hrt_abstime delay = 300_ms;
static constexpr const hrt_abstime rate_limit = 2_s; // rate-limit saving to 2 seconds
const hrt_abstime last_save_elapsed = hrt_elapsed_time(&last_autosave_timestamp);
const hrt_abstime last_save_elapsed = hrt_elapsed_time(&_last_autosave_timestamp);
if (last_save_elapsed < rate_limit && rate_limit > last_save_elapsed + delay) {
delay = rate_limit - last_save_elapsed;
}
autosave_scheduled.store(true);
_autosave_scheduled.store(true);
ScheduleDelayed(delay);
}
@ -1548,12 +1531,12 @@ int ParameterServer::exportInternal(int fd, param_filter_func filter)
}
// no modified parameters, export empty BSON document
if (param_values == nullptr) {
if (_param_values == nullptr) {
result = 0;
goto out;
}
while ((s = (struct param_wbuf_s *)utarray_next(param_values, s)) != nullptr) {
while ((s = (struct param_wbuf_s *)utarray_next(_param_values, s)) != nullptr) {
if (filter && !filter(s->param)) {
continue;
}
@ -1632,54 +1615,109 @@ out:
void ParameterServer::Run()
{
// TODO: param_request
// Check for parameter requests (get/set/list)
if (_param_request_sub.updated()) {
parameter_request_s request;
_param_request_sub.copy(&request);
/*
* We know how many parameters are exposed by this node, so
* process the request.
*/
if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ) {
//parameter_value_s parameter_value{};
if (_param_request_sub.copy(&request)) {
if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ) {
parameter_value_s parameter_value{};
parameter_value.param_count = countUsed();
param_t param = findParameter(request.name);
if (param != PARAM_INVALID) {
parameter_value.param_index = param;
switch (getParameterType(param)) {
case PARAM_TYPE_INT32: {
int32_t v;
if (getParameterDefaultValue(param, &v) == 0) {
parameter_value.type = parameter_request_s::TYPE_INT32;
parameter_value.int64_value = v;
parameter_value.timestamp = hrt_absolute_time();
_param_response_pub.publish(parameter_value);
}
}
break;
case PARAM_TYPE_FLOAT: {
float v;
if (getParameterDefaultValue(param, &v) == 0) {
parameter_value.type = parameter_request_s::TYPE_FLOAT32;
parameter_value.float64_value = v;
parameter_value.timestamp = hrt_absolute_time();
_param_response_pub.publish(parameter_value);
}
}
break;
}
}
} else if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_SET) {
param_t param = findParameter(request.name);
if (param != PARAM_INVALID) {
switch (request.type) {
case parameter_request_s::TYPE_BOOL:
case parameter_request_s::TYPE_UINT8:
case parameter_request_s::TYPE_INT32:
case parameter_request_s::TYPE_INT64: {
int32_t i32_value = request.int64_value;
setParameter(param, &i32_value);
}
break;
case parameter_request_s::TYPE_FLOAT32:
case parameter_request_s::TYPE_FLOAT64: {
float float32_value = request.float64_value;
setParameter(param, &float32_value);
}
}
}
} else if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
// TODO:
} else if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_SET) {
} else if (request.node_id == parameter_request_s::NODE_ID_ALL) {
if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
} else if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
} else if (request.node_id == parameter_request_s::NODE_ID_ALL) {
if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
// TODO:
}
}
}
}
// autosave worker, run last
if (autosave_scheduled.load()) {
if (_autosave_scheduled.load()) {
bool disabled = false;
if (!getDefaultFile()) {
// In case we save to FLASH, defer param writes until disarmed,
// as writing to FLASH can stall the entire CPU (in rare cases around 300ms on STM32F7)
uORB::SubscriptionData<actuator_armed_s> armed_sub{ORB_ID(actuator_armed)};
_armed_sub.update();
if (armed_sub.get().armed) {
if (_armed_sub.get().armed) {
//work_queue(LPWORK, &autosave_work, (worker_t)&autosave_worker, nullptr, USEC2TICK(1_s));
return;
}
}
lockWriter();
last_autosave_timestamp = hrt_absolute_time();
autosave_scheduled.store(false);
disabled = autosave_disabled;
_last_autosave_timestamp = hrt_absolute_time();
_autosave_scheduled.store(false);
disabled = _autosave_disabled;
unlockWriter();
if (disabled) {
@ -1695,4 +1733,24 @@ void ParameterServer::Run()
}
if (_notify_scheduled.load()) {
lockReader();
_notify_scheduled.store(false);
parameter_update_s pup{};
pup.instance = _param_instance++;
pup.get_count = perf_event_count(_get_count_perf);
pup.set_count = perf_event_count(_set_perf);
pup.find_count = perf_event_count(_find_count_perf);
pup.export_count = perf_event_count(_export_perf);
pup.active = _params_active.count();
pup.changed = _params_changed.count();
pup.custom_default = _params_custom_default.count();
pup.timestamp = hrt_absolute_time();
_parameter_update_pub.publish(pup);
unlockReader();
}
}

View File

@ -86,7 +86,7 @@ public:
*
* @return The number of parameters.
*/
unsigned countUsed() const { return params_active.count(); }
unsigned countUsed() const { return _params_active.count(); }
/**
* Wether a parameter is in use in the system.
@ -341,7 +341,7 @@ public:
* a result of a call to param_set_default_file, or the
* built-in default.
*/
const char *getDefaultFile() const { return param_default_file; }
const char *getDefaultFile() const { return _param_default_file; }
/**
* Set the backup parameter file name.
@ -357,17 +357,15 @@ public:
*
* @return The path to the backup parameter file
*/
const char *getBackupFile() const { return param_backup_file; }
const char *getBackupFile() const { return _param_backup_file; }
/**
* Save parameters to the default file.
* Note: this method requires a large amount of stack size!
* Automatically save the parameters after a timeout and limited rate.
*
* This function saves all parameters with non-default values.
*
* @return Zero on success.
* This needs to be called with the writer lock held (it's not necessary that it's the writer lock, but it
* needs to be the same lock as autosave_worker() and param_control_autosave() use).
*/
int saveDefault();
void autoSave(bool now = false);
/**
* Load parameters from the default parameter file.
@ -448,18 +446,19 @@ private:
// get parameter default value, caller is responsible for locking
int getParameterDefaultValueInternal(param_t param, void *default_val);
/**
* 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.
*/
int saveDefault();
// internal parameter export, caller is responsible for locking
int exportInternal(int fd, param_filter_func filter);
/**
* Automatically save the parameters after a timeout and limited rate.
*
* This needs to be called with the writer lock held (it's not necessary that it's the writer lock, but it
* needs to be the same lock as autosave_worker() and param_control_autosave() use).
*/
void autoSave();
int bsonImportCallback(bson_decoder_t decoder, bson_node_t node);
static int importCallbackTrampoline(bson_decoder_t decoder, void *priv, bson_node_t node);
int importFromFileDescriptorInternal(int fd);
@ -472,89 +471,55 @@ private:
int bsonDumpCallback(bson_decoder_t decoder, bson_node_t node);
char *param_default_file = nullptr;
char *param_backup_file = nullptr;
char *_param_default_file{nullptr};
char *_param_backup_file{nullptr};
px4::AtomicBitset<param_info_count> params_active; // params found
px4::AtomicBitset<param_info_count> params_changed; // params non-default
px4::Bitset<param_info_count> params_custom_default; // params with runtime default value
px4::AtomicBitset<param_info_count> params_unsaved;
px4::AtomicBitset<param_info_count> _params_active; // params found
px4::AtomicBitset<param_info_count> _params_changed; // params non-default
px4::Bitset<param_info_count> _params_custom_default; // params with runtime default value
px4::AtomicBitset<param_info_count> _params_unsaved;
/** flexible array holding modified parameter values */
UT_array *param_values{nullptr};
UT_array *param_custom_default_values{nullptr};
UT_array *_param_values{nullptr};
UT_array *_param_custom_default_values{nullptr};
const UT_icd param_icd = {sizeof(param_wbuf_s), nullptr, nullptr, nullptr};
/** parameter update topic handle */
orb_advert_t param_topic = nullptr;
unsigned int param_instance = 0;
unsigned int _param_instance{0};
// the following implements an RW-lock using 2 semaphores (used as mutexes). It gives
// priority to readers, meaning a writer could suffer from starvation, but in our use-case
// we only have short periods of reads and writes are rare.
px4_sem_t param_sem; ///< this protects against concurrent access to param_values
int reader_lock_holders = 0;
px4_sem_t reader_lock_holders_lock; ///< this protects against concurrent access to reader_lock_holders
px4_sem_t _param_sem; ///< this protects against concurrent access to _param_values
int _reader_lock_holders{0};
px4_sem_t _reader_lock_holders_lock; ///< this protects against concurrent access to reader_lock_holders
perf_counter_t param_export_perf;
perf_counter_t param_find_perf;
perf_counter_t param_get_perf;
perf_counter_t param_set_perf;
perf_counter_t _export_perf{perf_alloc(PC_ELAPSED, "param: export")};
perf_counter_t _find_count_perf{perf_alloc(PC_COUNT, "param: find")};
perf_counter_t _get_count_perf{perf_alloc(PC_COUNT, "param: get")};
perf_counter_t _set_perf{perf_alloc(PC_ELAPSED, "param: set")};
px4_sem_t param_sem_save; ///< this protects against concurrent param saves (file or flash access).
px4_sem_t _param_sem_save; ///< this protects against concurrent param saves (file or flash access).
///< we use a separate lock to allow concurrent param reads and saves.
///< a param_set could still be blocked by a param save, because it
///< needs to take the reader lock
void Run() override;
uORB::Publication<parameter_value_s> _param_response_pub{ORB_ID(parameter_value)};
uORB::Publication<parameter_update_s> _parameter_update_pub{ORB_ID(parameter_update)};
uORB::Subscription _param_request_sub{ORB_ID(parameter_request)};
uORB::SubscriptionCallbackWorkItem _param_request_sub{this, ORB_ID(parameter_request)};
uORB::SubscriptionData<actuator_armed_s> _armed_sub{ORB_ID(actuator_armed)};
// autosaving variables
hrt_abstime last_autosave_timestamp = 0;
px4::atomic_bool autosave_scheduled{false};
bool autosave_disabled = false;
/*
* The MAVLink parameter bridge needs to know the maximum parameter index
* of each node so that clients can determine when parameter listings have
* finished. We do that by querying a node's entire parameter set whenever
* a parameter message is received for a node with a zero _param_count,
* and storing the count here. If a node doesn't respond, or doesn't have
* any parameters, its count will stay at zero and we'll try to query the
* set again next time.
*
* The node's UAVCAN ID is used as the index into the _param_counts array.
*/
uint8_t _param_counts[128] {};
bool _count_in_progress{false};
uint8_t _count_index{0};
bool _param_in_progress{false};
uint8_t _param_index{0};
bool _param_list_in_progress{false};
bool _param_list_all_nodes{false};
uint8_t _param_list_node_id{1};
uint32_t _param_dirty_bitmap[4] {};
uint8_t _param_save_opcode{0};
bool _cmd_in_progress{false};
hrt_abstime _last_autosave_timestamp{0};
px4::atomic_bool _autosave_scheduled{false};
bool _autosave_disabled{false};
px4::atomic_bool _notify_scheduled{false};
};

View File

@ -87,12 +87,12 @@ param_export_internal(param_filter_func filter)
bson_encoder_init_buf(&encoder, nullptr, 0);
/* no modified parameters -> we are done */
if (param_values == nullptr) {
if (_param_values == nullptr) {
result = 0;
goto out;
}
while ((s = (struct param_wbuf_s *)utarray_next(param_values, s)) != nullptr) {
while ((s = (struct param_wbuf_s *)utarray_next(_param_values, s)) != nullptr) {
int32_t i;
float f;

View File

@ -344,7 +344,8 @@ const char *param_get_backup_file()
int param_save_default()
{
if (parameter_server) {
return parameter_server->saveDefault();
parameter_server->autoSave(true);
return 0;
}
return -1;

View File

@ -1,199 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file parameters_ioctl.cpp
*
* Protected build kernel space interface to global parameter store.
*/
#define PARAM_IMPLEMENTATION
#include <errno.h>
#include "param.h"
#include "parameters_ioctl.h"
#include <px4_platform_common/defines.h>
int param_ioctl(unsigned int cmd, unsigned long arg)
{
int ret = OK;
switch (cmd) {
case PARAMIOCNOTIFY: {
param_notify_changes();
}
break;
case PARAMIOCFIND: {
paramiocfind_t *data = (paramiocfind_t *)arg;
if (data->notification) {
data->ret = param_find(data->name);
} else {
data->ret = param_find_no_notification(data->name);
}
}
break;
case PARAMIOCCOUNTUSED: {
paramioccountused_t *data = (paramioccountused_t *)arg;
data->ret = param_count_used();
}
break;
case PARAMIOCFORUSEDINDEX: {
paramiocforusedindex_t *data = (paramiocforusedindex_t *)arg;
data->ret = param_for_used_index(data->index);
}
break;
case PARAMIOCGETUSEDINDEX: {
paramiocgetusedindex_t *data = (paramiocgetusedindex_t *)arg;
data->ret = param_get_used_index(data->param);
}
break;
case PARAMIOCUNSAVED: {
paramiocunsaved_t *data = (paramiocunsaved_t *)arg;
data->ret = param_value_unsaved(data->param);
}
break;
case PARAMIOCGET: {
paramiocget_t *data = (paramiocget_t *)arg;
if (data->deflt) {
data->ret = param_get_default_value(data->param, data->val);
} else {
data->ret = param_get(data->param, data->val);
}
}
break;
case PARAMIOCAUTOSAVE: {
paramiocautosave_t *data = (paramiocautosave_t *)arg;
param_control_autosave(data->enable);
}
break;
case PARAMIOCSET: {
paramiocset_t *data = (paramiocset_t *)arg;
if (data->notification) {
data->ret = param_set(data->param, data->val);
} else {
data->ret = param_set_no_notification(data->param, data->val);
}
}
break;
case PARAMIOCUSED: {
paramiocused_t *data = (paramiocused_t *)arg;
data->ret = param_used(data->param);
}
break;
case PARAMIOCSETUSED: {
paramiocsetused_t *data = (paramiocsetused_t *)arg;
param_set_used(data->param);
}
break;
case PARAMIOCSETDEFAULT: {
paramiocsetdefault_t *data = (paramiocsetdefault_t *)arg;
data->ret = param_set_default_value(data->param, data->val);
}
break;
case PARAMIOCRESET: {
paramiocreset_t *data = (paramiocreset_t *)arg;
if (data->notification) {
data->ret = param_reset(data->param);
} else {
data->ret = param_reset_no_notification(data->param);
}
}
break;
case PARAMIOCRESETGROUP: {
paramiocresetgroup_t *data = (paramiocresetgroup_t *)arg;
if (data->type == PARAM_RESET_EXCLUDES) {
param_reset_excludes(data->group, data->num_in_group);
} else if (data->type == PARAM_RESET_SPECIFIC) {
param_reset_specific(data->group, data->num_in_group);
} else {
param_reset_all();
}
}
break;
case PARAMIOCSAVEDEFAULT: {
paramiocsavedefault_t *data = (paramiocsavedefault_t *)arg;
data->ret = param_save_default();
}
break;
case PARAMIOCLOADDEFAULT: {
paramiocloaddefault_t *data = (paramiocloaddefault_t *)arg;
data->ret = param_load_default();
}
break;
case PARAMIOCEXPORT: {
paramiocexport_t *data = (paramiocexport_t *)arg;
data->ret = param_export(data->filename, nullptr);
}
break;
case PARAMIOCHASH: {
paramiochash_t *data = (paramiochash_t *)arg;
data->ret = param_hash_check();
}
break;
default:
ret = -ENOTTY;
break;
}
return ret;
}

View File

@ -1,163 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file parameters_ioctl.h
*
* User space - kernel space interface to global parameter store.
*/
#pragma once
#define PARAM_IMPLEMENTATION
#include "param.h"
#include <px4_platform/board_ctrl.h>
#include <px4_platform_common/defines.h>
#define _PARAMIOC(_n) (_PX4_IOC(_PARAMIOCBASE, _n))
#define PARAMIOCNOTIFY _PARAMIOC(1)
#define PARAMIOCFIND _PARAMIOC(2)
typedef struct paramiocfind {
const char *name;
const bool notification;
param_t ret;
} paramiocfind_t;
#define PARAMIOCCOUNTUSED _PARAMIOC(3)
typedef struct paramioccountused {
unsigned ret;
} paramioccountused_t;
#define PARAMIOCFORUSEDINDEX _PARAMIOC(4)
typedef struct paramiocforusedindex {
const unsigned index;
param_t ret;
} paramiocforusedindex_t;
#define PARAMIOCGETUSEDINDEX _PARAMIOC(5)
typedef struct paramiocgetusedindex {
const param_t param;
unsigned ret;
} paramiocgetusedindex_t;
#define PARAMIOCUNSAVED _PARAMIOC(6)
typedef struct paramiocunsaved {
const param_t param;
bool ret;
} paramiocunsaved_t;
#define PARAMIOCGET _PARAMIOC(7)
typedef struct paramiocget {
const param_t param;
const bool deflt;
void *const val;
int ret;
} paramiocget_t;
#define PARAMIOCAUTOSAVE _PARAMIOC(8)
typedef struct paramiocautosave {
const bool enable;
} paramiocautosave_t;
#define PARAMIOCSET _PARAMIOC(9)
typedef struct paramiocset {
const param_t param;
const bool notification;
const void *val;
int ret;
} paramiocset_t;
#define PARAMIOCUSED _PARAMIOC(10)
typedef struct paramiocused {
const param_t param;
bool ret;
} paramiocused_t;
#define PARAMIOCSETUSED _PARAMIOC(11)
typedef struct paramiocsetused {
const param_t param;
} paramiocsetused_t;
#define PARAMIOCSETDEFAULT _PARAMIOC(12)
typedef struct paramiocsetdefault {
const param_t param;
const void *val;
int ret;
} paramiocsetdefault_t;
#define PARAMIOCRESET _PARAMIOC(13)
typedef struct paramiocreset {
const param_t param;
const bool notification;
int ret;
} paramiocreset_t;
#define PARAMIOCRESETGROUP _PARAMIOC(14)
typedef enum {
PARAM_RESET_ALL,
PARAM_RESET_EXCLUDES,
PARAM_RESET_SPECIFIC
} param_reset_type_t;
typedef struct paramiocresetgroup {
param_reset_type_t type;
const char **group;
const int num_in_group;
} paramiocresetgroup_t;
#define PARAMIOCSAVEDEFAULT _PARAMIOC(15)
typedef struct paramiocsavedefault {
int ret;
} paramiocsavedefault_t;
#define PARAMIOCLOADDEFAULT _PARAMIOC(16)
typedef struct paramiocloaddefault {
int ret;
} paramiocloaddefault_t;
#define PARAMIOCEXPORT _PARAMIOC(17)
typedef struct paramiocexport {
const char *filename;
int ret;
} paramiocexport_t;
#define PARAMIOCHASH _PARAMIOC(18)
typedef struct paramiochash {
uint32_t ret;
} paramiochash_t;
int param_ioctl(unsigned int cmd, unsigned long arg);

View File

@ -33,5 +33,5 @@
add_library(tinybson tinybson.cpp)
target_compile_definitions(tinybson PRIVATE -DMODULE_NAME="tinybson")
target_compile_options(tinybson PRIVATE -Wno-sign-compare) # TODO: fix this
target_compile_options(tinybson PRIVATE ${MAX_CUSTOM_OPT_LEVEL} -Wno-sign-compare) # TODO: fix this
add_dependencies(tinybson prebuild_targets)

View File

@ -1,221 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file usr_parameters_if.cpp
*
* Protected build user space interface to global parameter store.
*/
#define PARAM_IMPLEMENTATION
#include "param.h"
#include "parameters_ioctl.h"
#include <parameters/px4_parameters.hpp>
#include <sys/boardctl.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/log.h>
#include "parameters_common.cpp"
void
param_notify_changes()
{
boardctl(PARAMIOCNOTIFY, NULL);
}
param_t param_find(const char *name)
{
paramiocfind_t data = {name, true, PARAM_INVALID};
boardctl(PARAMIOCFIND, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
param_t param_find_no_notification(const char *name)
{
paramiocfind_t data = {name, false, PARAM_INVALID};
boardctl(PARAMIOCFIND, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
unsigned param_count_used()
{
paramioccountused_t data = {0};
boardctl(PARAMIOCCOUNTUSED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
param_t param_for_used_index(unsigned index)
{
paramiocforusedindex_t data = {index, 0};
boardctl(PARAMIOCFORUSEDINDEX, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_get_used_index(param_t param)
{
paramiocgetusedindex_t data = {param, 0};
boardctl(PARAMIOCGETUSEDINDEX, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
bool
param_value_unsaved(param_t param)
{
paramiocunsaved_t data = {param, false};
boardctl(PARAMIOCUNSAVED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_get(param_t param, void *val)
{
paramiocget_t data = {param, false, val, PX4_ERROR};
boardctl(PARAMIOCGET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_get_default_value(param_t param, void *default_val)
{
paramiocget_t data = {param, true, default_val, PX4_ERROR};
boardctl(PARAMIOCGET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void
param_control_autosave(bool enable)
{
paramiocautosave_t data = {enable};
boardctl(PARAMIOCAUTOSAVE, reinterpret_cast<unsigned long>(&data));
}
int param_set(param_t param, const void *val)
{
paramiocset_t data = {param, true, val, PX4_ERROR};
boardctl(PARAMIOCSET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_set_no_notification(param_t param, const void *val)
{
paramiocset_t data = {param, false, val, PX4_ERROR};
boardctl(PARAMIOCSET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
bool param_used(param_t param)
{
paramiocused_t data = {param, false};
boardctl(PARAMIOCUSED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void param_set_used(param_t param)
{
paramiocsetused_t data = {param};
boardctl(PARAMIOCSETUSED, reinterpret_cast<unsigned long>(&data));
}
int param_set_default_value(param_t param, const void *val)
{
paramiocsetdefault_t data = {param, val, PX4_ERROR};
boardctl(PARAMIOCSETDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_reset(param_t param)
{
paramiocreset_t data = {param, true, PX4_ERROR};
boardctl(PARAMIOCRESET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_reset_no_notification(param_t param)
{
paramiocreset_t data = {param, false, PX4_ERROR};
boardctl(PARAMIOCRESET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void
param_reset_all()
{
paramiocresetgroup_t data = {PARAM_RESET_ALL, nullptr, 0};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
void
param_reset_excludes(const char *excludes[], int num_excludes)
{
paramiocresetgroup_t data = {PARAM_RESET_EXCLUDES, excludes, num_excludes};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
void
param_reset_specific(const char *resets[], int num_resets)
{
paramiocresetgroup_t data = {PARAM_RESET_SPECIFIC, resets, num_resets};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
int param_save_default()
{
paramiocsavedefault_t data = {PX4_ERROR};
boardctl(PARAMIOCSAVEDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_load_default()
{
paramiocloaddefault_t data = {PX4_ERROR};
boardctl(PARAMIOCLOADDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_export(const char *filename, param_filter_func filter)
{
paramiocexport_t data = {filename, PX4_ERROR};
if (filter) { PX4_ERR("ERROR: filter not supported in userside blob"); }
boardctl(PARAMIOCEXPORT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
uint32_t param_hash_check()
{
paramiochash_t data = {0};
boardctl(PARAMIOCHASH, reinterpret_cast<unsigned long>(&data));
return data.ret;
}