From 306aa828c8e4c681070a869fb95faa0159d1e5ba Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 29 Sep 2018 11:20:30 -0400 Subject: [PATCH 1/6] parameters generate as single static constexpr header --- src/lib/parameters/CMakeLists.txt | 10 ++--- src/lib/parameters/parameters.cpp | 4 +- src/lib/parameters/parameters_shmem.cpp | 4 +- src/lib/parameters/px_generate_params.py | 3 +- .../templates/px4_parameters.c.jinja | 38 ------------------- .../templates/px4_parameters.h.jinja | 21 ---------- .../templates/px4_parameters.hpp.jinja | 26 +++++++++++++ 7 files changed, 35 insertions(+), 71 deletions(-) delete mode 100644 src/lib/parameters/templates/px4_parameters.c.jinja delete mode 100644 src/lib/parameters/templates/px4_parameters.h.jinja create mode 100644 src/lib/parameters/templates/px4_parameters.hpp.jinja diff --git a/src/lib/parameters/CMakeLists.txt b/src/lib/parameters/CMakeLists.txt index 6ee025585670..fb8994bc7643 100644 --- a/src/lib/parameters/CMakeLists.txt +++ b/src/lib/parameters/CMakeLists.txt @@ -109,15 +109,14 @@ add_custom_command(OUTPUT ${parameters_xml} ) add_custom_target(parameters_xml DEPENDS ${parameters_xml}) -# generate px4_parameters.c and px4_parameters{,_public}.h -add_custom_command(OUTPUT px4_parameters.c px4_parameters.h px4_parameters_public.h +# generate px4_parameters.hpp and px4_parameters_public.h +add_custom_command(OUTPUT px4_parameters.hpp px4_parameters_public.h COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/px_generate_params.py --xml ${parameters_xml} --dest ${CMAKE_CURRENT_BINARY_DIR} DEPENDS ${PX4_BINARY_DIR}/parameters.xml px_generate_params.py - templates/px4_parameters.c.jinja - templates/px4_parameters.h.jinja + templates/px4_parameters.hpp.jinja templates/px4_parameters_public.h.jinja ) @@ -138,8 +137,7 @@ endif() if (NOT "${PX4_BOARD}" MATCHES "px4_io") add_library(parameters ${SRCS} - px4_parameters.c - px4_parameters.h + px4_parameters.hpp px4_parameters_public.h ) diff --git a/src/lib/parameters/parameters.cpp b/src/lib/parameters/parameters.cpp index 3c5cad2879bc..a57eb18824a2 100644 --- a/src/lib/parameters/parameters.cpp +++ b/src/lib/parameters/parameters.cpp @@ -42,7 +42,7 @@ */ #include "param.h" -#include +#include #include "tinybson/tinybson.h" #include @@ -101,7 +101,7 @@ static bool autosave_disabled = false; * Array of static parameter info. */ static const param_info_s *param_info_base = (const param_info_s *) &px4_parameters; -#define param_info_count px4_parameters.param_count +static constexpr int param_info_count = sizeof(px4_parameters) / sizeof(param_info_s); /** * Storage for modified parameters. diff --git a/src/lib/parameters/parameters_shmem.cpp b/src/lib/parameters/parameters_shmem.cpp index 9081e2ac6704..d687f92de629 100644 --- a/src/lib/parameters/parameters_shmem.cpp +++ b/src/lib/parameters/parameters_shmem.cpp @@ -42,7 +42,7 @@ */ #include "param.h" -#include +#include #include "tinybson/tinybson.h" #include @@ -103,7 +103,7 @@ static bool autosave_disabled = false; * Array of static parameter info. */ static const param_info_s *param_info_base = (const param_info_s *) &px4_parameters; -#define param_info_count px4_parameters.param_count +static constexpr int param_info_count = sizeof(px4_parameters) / sizeof(param_info_s); /** * Storage for modified parameters. diff --git a/src/lib/parameters/px_generate_params.py b/src/lib/parameters/px_generate_params.py index af746fb7ed5d..c0ee6302f4ec 100755 --- a/src/lib/parameters/px_generate_params.py +++ b/src/lib/parameters/px_generate_params.py @@ -39,9 +39,8 @@ def generate(xml_file, dest='.'): os.path.mkdir(dest) template_files = [ - 'px4_parameters.h.jinja', + 'px4_parameters.hpp.jinja', 'px4_parameters_public.h.jinja', - 'px4_parameters.c.jinja', ] for template_file in template_files: template = env.get_template(template_file) diff --git a/src/lib/parameters/templates/px4_parameters.c.jinja b/src/lib/parameters/templates/px4_parameters.c.jinja deleted file mode 100644 index 6cf47754b22a..000000000000 --- a/src/lib/parameters/templates/px4_parameters.c.jinja +++ /dev/null @@ -1,38 +0,0 @@ -{# jinja syntax: http://jinja.pocoo.org/docs/2.9/templates/ #} -#include "px4_parameters.h" - -// DO NOT EDIT -// This file is autogenerated from paramaters.xml - -__BEGIN_DECLS - -const -#ifndef __PX4_DARWIN -__attribute__((used, section("__param"))) -#endif - -struct px4_parameters_t px4_parameters = { -{% for param in params %} - { - "{{ param.attrib["name"] }}", - PARAM_TYPE_{{ param.attrib["type"] }}, - {%- if param.attrib["volatile"] == "true" %} - .volatile_param = 1, - {%- else %} - .volatile_param = 0, - {%- endif %} - {%- if param.attrib["type"] == "FLOAT" %} - .val.f = {{ param.attrib["default"] }} - {%- elif param.attrib["type"] == "INT32" %} - .val.i = {{ param.attrib["default"] }} - {%- endif %} - }, -{% endfor %} - {{ params | length }} -}; - -//extern const struct px4_parameters_t px4_parameters; - -__END_DECLS - -{# vim: set noet ft=jinja fenc=utf-8 ff=unix sts=4 sw=4 ts=4 : #} diff --git a/src/lib/parameters/templates/px4_parameters.h.jinja b/src/lib/parameters/templates/px4_parameters.h.jinja deleted file mode 100644 index 807aa21c820c..000000000000 --- a/src/lib/parameters/templates/px4_parameters.h.jinja +++ /dev/null @@ -1,21 +0,0 @@ -{# jinja syntax: http://jinja.pocoo.org/docs/2.9/templates/ #} -#include -#include - -// DO NOT EDIT -// This file is autogenerated from parameters.xml - -__BEGIN_DECLS - -struct px4_parameters_t { -{%- for param in params %} - const struct param_info_s __param__{{ param.attrib["name"] }}; -{%- endfor %} - const unsigned int param_count; -}; - -extern const struct px4_parameters_t px4_parameters; - -__END_DECLS - -{# vim: set noet ft=jinja fenc=utf-8 ff=unix sts=4 sw=4 ts=4 : #} diff --git a/src/lib/parameters/templates/px4_parameters.hpp.jinja b/src/lib/parameters/templates/px4_parameters.hpp.jinja new file mode 100644 index 000000000000..43bd3d86dca7 --- /dev/null +++ b/src/lib/parameters/templates/px4_parameters.hpp.jinja @@ -0,0 +1,26 @@ +{# jinja syntax: http://jinja.pocoo.org/docs/2.9/templates/ #} + +#include +#include + +// DO NOT EDIT +// This file is autogenerated from parameters.xml + +static constexpr param_info_s px4_parameters[] = { +{% for param in params %} + { + "{{ param.attrib["name"] }}", + PARAM_TYPE_{{ param.attrib["type"] }}, + {%- if param.attrib["volatile"] == "true" %} + .volatile_param = 1, + {%- else %} + .volatile_param = 0, + {%- endif %} + {%- if param.attrib["type"] == "FLOAT" %} + .val = {{ "{" }} .f = {{ param.attrib["default"] }} {{ "}" }}, + {%- elif param.attrib["type"] == "INT32" %} + .val = {{ "{" }} .i = {{ param.attrib["default"] }}{{ "}" }}, + {%- endif %} + }, +{% endfor %} +}; From 073b201731d2f12154284284962f9cdcec0a8e74 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 29 Sep 2018 11:47:58 -0400 Subject: [PATCH 2/6] parameters merge px4_parameters.hpp and px4_parameters_public.h --- src/lib/parameters/CMakeLists.txt | 6 +-- src/lib/parameters/parameters.cpp | 20 ++++------ src/lib/parameters/parameters_shmem.cpp | 22 ++++------- src/lib/parameters/px_generate_params.py | 1 - .../templates/px4_parameters.hpp.jinja | 16 +++++++- .../templates/px4_parameters_public.h.jinja | 37 ------------------- src/platforms/px4_param.h | 12 +++--- 7 files changed, 38 insertions(+), 76 deletions(-) delete mode 100644 src/lib/parameters/templates/px4_parameters_public.h.jinja diff --git a/src/lib/parameters/CMakeLists.txt b/src/lib/parameters/CMakeLists.txt index fb8994bc7643..c2eaa0326c7f 100644 --- a/src/lib/parameters/CMakeLists.txt +++ b/src/lib/parameters/CMakeLists.txt @@ -109,15 +109,14 @@ add_custom_command(OUTPUT ${parameters_xml} ) add_custom_target(parameters_xml DEPENDS ${parameters_xml}) -# generate px4_parameters.hpp and px4_parameters_public.h -add_custom_command(OUTPUT px4_parameters.hpp px4_parameters_public.h +# generate px4_parameters.hpp +add_custom_command(OUTPUT px4_parameters.hpp COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/px_generate_params.py --xml ${parameters_xml} --dest ${CMAKE_CURRENT_BINARY_DIR} DEPENDS ${PX4_BINARY_DIR}/parameters.xml px_generate_params.py templates/px4_parameters.hpp.jinja - templates/px4_parameters_public.h.jinja ) set(SRCS) @@ -138,7 +137,6 @@ if (NOT "${PX4_BOARD}" MATCHES "px4_io") add_library(parameters ${SRCS} px4_parameters.hpp - px4_parameters_public.h ) if ("${CONFIG_SHMEM}" STREQUAL "1") diff --git a/src/lib/parameters/parameters.cpp b/src/lib/parameters/parameters.cpp index a57eb18824a2..42efbeef033a 100644 --- a/src/lib/parameters/parameters.cpp +++ b/src/lib/parameters/parameters.cpp @@ -97,15 +97,9 @@ static volatile bool autosave_scheduled = false; static bool autosave_disabled = false; #endif /* PARAM_NO_AUTOSAVE */ -/** - * Array of static parameter info. - */ -static const param_info_s *param_info_base = (const param_info_s *) &px4_parameters; -static constexpr int param_info_count = sizeof(px4_parameters) / sizeof(param_info_s); +static constexpr int param_info_count = sizeof(px4::parameters) / sizeof(param_info_s); -/** - * Storage for modified parameters. - */ +// Storage for modified parameters. struct param_wbuf_s { union param_value_u val; param_t param; @@ -336,7 +330,7 @@ param_find_internal(const char *name, bool notification) while (front <= last) { middle = front + (last - front) / 2; - int ret = strcmp(name, param_info_base[middle].name); + int ret = strcmp(name, px4::parameters[middle].name); if (ret == 0) { if (notification) { @@ -483,13 +477,13 @@ param_get_used_index(param_t param) const char * param_name(param_t param) { - return handle_in_range(param) ? param_info_base[param].name : nullptr; + return handle_in_range(param) ? px4::parameters[param].name : nullptr; } bool param_is_volatile(param_t param) { - return handle_in_range(param) ? param_info_base[param].volatile_param : false; + return handle_in_range(param) ? px4::parameters[param].volatile_param : false; } bool @@ -516,7 +510,7 @@ param_value_unsaved(param_t param) param_type_t param_type(param_t param) { - return handle_in_range(param) ? param_info_base[param].type : PARAM_TYPE_UNKNOWN; + return handle_in_range(param) ? px4::parameters[param].type : PARAM_TYPE_UNKNOWN; } size_t @@ -567,7 +561,7 @@ param_get_value_ptr(param_t param) v = &s->val; } else { - v = ¶m_info_base[param].val; + v = &px4::parameters[param].val; } if (param_type(param) >= PARAM_TYPE_STRUCT && diff --git a/src/lib/parameters/parameters_shmem.cpp b/src/lib/parameters/parameters_shmem.cpp index d687f92de629..0d9d16dce040 100644 --- a/src/lib/parameters/parameters_shmem.cpp +++ b/src/lib/parameters/parameters_shmem.cpp @@ -99,15 +99,9 @@ static bool autosave_scheduled = false; static bool autosave_disabled = false; #endif /* PARAM_NO_AUTOSAVE */ -/** - * Array of static parameter info. - */ -static const param_info_s *param_info_base = (const param_info_s *) &px4_parameters; -static constexpr int param_info_count = sizeof(px4_parameters) / sizeof(param_info_s); +static constexpr int param_info_count = sizeof(px4::parameters) / sizeof(param_info_s); -/** - * Storage for modified parameters. - */ +// Storage for modified parameters. struct param_wbuf_s { union param_value_u val; param_t param; @@ -364,7 +358,7 @@ param_find_internal(const char *name, bool notification) /* perform a linear search of the known parameters */ for (param = 0; handle_in_range(param); param++) { - if (!strcmp(param_info_base[param].name, name)) { + if (!strcmp(px4::parameters[param].name, name)) { if (notification) { param_set_used_internal(param); } @@ -514,13 +508,13 @@ param_get_used_index(param_t param) const char * param_name(param_t param) { - return handle_in_range(param) ? param_info_base[param].name : nullptr; + return handle_in_range(param) ? px4::parameters[param].name : nullptr; } bool param_is_volatile(param_t param) { - return handle_in_range(param) ? param_info_base[param].volatile_param : false; + return handle_in_range(param) ? px4::parameters[param].volatile_param : false; } bool @@ -547,7 +541,7 @@ param_value_unsaved(param_t param) param_type_t param_type(param_t param) { - return handle_in_range(param) ? param_info_base[param].type : PARAM_TYPE_UNKNOWN; + return handle_in_range(param) ? px4::parameters[param].type : PARAM_TYPE_UNKNOWN; } size_t @@ -598,7 +592,7 @@ param_get_value_ptr(param_t param) v = &s->val; } else { - v = ¶m_info_base[param].val; + v = &px4::parameters[param].val; } if (param_type(param) >= PARAM_TYPE_STRUCT && @@ -1527,7 +1521,7 @@ void init_params() param_import_done = 1; #ifdef __PX4_QURT - copy_params_to_shmem(param_info_base); + copy_params_to_shmem(px4::parameters); #ifdef ENABLE_SHMEM_DEBUG PX4_INFO("Offsets:"); diff --git a/src/lib/parameters/px_generate_params.py b/src/lib/parameters/px_generate_params.py index c0ee6302f4ec..2d34c9604e59 100755 --- a/src/lib/parameters/px_generate_params.py +++ b/src/lib/parameters/px_generate_params.py @@ -40,7 +40,6 @@ def generate(xml_file, dest='.'): template_files = [ 'px4_parameters.hpp.jinja', - 'px4_parameters_public.h.jinja', ] for template_file in template_files: template = env.get_template(template_file) diff --git a/src/lib/parameters/templates/px4_parameters.hpp.jinja b/src/lib/parameters/templates/px4_parameters.hpp.jinja index 43bd3d86dca7..e477344237e9 100644 --- a/src/lib/parameters/templates/px4_parameters.hpp.jinja +++ b/src/lib/parameters/templates/px4_parameters.hpp.jinja @@ -6,7 +6,19 @@ // DO NOT EDIT // This file is autogenerated from parameters.xml -static constexpr param_info_s px4_parameters[] = { +namespace px4 { {# wrap the enum in a namespace, otherwise we get shadowing errors for MAV_TYPE #} + +/// Enum with all parameters +enum class params { + {# enums are guaranteed to start with 0 (if the value for the first is not + specified), and then incremented by 1 (the implementation depends on that!) #} +{%- for param in params %} + {{ param.attrib["name"] }}, +{%- endfor %} + +}; + +static constexpr param_info_s parameters[] = { {% for param in params %} { "{{ param.attrib["name"] }}", @@ -24,3 +36,5 @@ static constexpr param_info_s px4_parameters[] = { }, {% endfor %} }; + +} // namespace px4 diff --git a/src/lib/parameters/templates/px4_parameters_public.h.jinja b/src/lib/parameters/templates/px4_parameters_public.h.jinja deleted file mode 100644 index f3f22cd01344..000000000000 --- a/src/lib/parameters/templates/px4_parameters_public.h.jinja +++ /dev/null @@ -1,37 +0,0 @@ -{# jinja syntax: http://jinja.pocoo.org/docs/2.9/templates/ #} -#include -#include - -// DO NOT EDIT -// This file is autogenerated from parameters.xml - - -#ifdef __cplusplus - -namespace px4 { {# wrap the enum in a namespace, otherwise we get shadowing errors for MAV_TYPE #} - -/// Enum with all parameters -enum class params { - {# enums are guaranteed to start with 0 (if the value for the first is not - specified), and then incremented by 1 (the implementation depends on that!) #} -{%- for param in params %} - {{ param.attrib["name"] }}, -{%- endfor %} - - _COUNT -}; - -// All parameter types -{# (px4_parameters is marked as extern, so we cannot use it as constexpr) #} -static const constexpr int param_types_array[] = { -{%- for param in params %} - PARAM_TYPE_{{ param.attrib["type"] }}, // {{ param.attrib["name"] }} -{%- endfor %} -}; - - -} // namespace px4 - - -#endif /* __cplusplus */ - diff --git a/src/platforms/px4_param.h b/src/platforms/px4_param.h index e526defd9586..de0130afd26e 100644 --- a/src/platforms/px4_param.h +++ b/src/platforms/px4_param.h @@ -41,7 +41,7 @@ #include "px4_param_macros.h" -#include +#include /** * get the parameter handle from a parameter enum @@ -112,7 +112,7 @@ class Param { public: // static type-check - static_assert(px4::param_types_array[(int)p] == PARAM_TYPE_FLOAT, "parameter type must be float"); + static_assert(px4::parameters[(int)p].type == PARAM_TYPE_FLOAT, "parameter type must be float"); Param() { @@ -145,7 +145,7 @@ class Param { public: // static type-check - static_assert(px4::param_types_array[(int)p] == PARAM_TYPE_FLOAT, "parameter type must be float"); + static_assert(px4::parameters[(int)p].type == PARAM_TYPE_FLOAT, "parameter type must be float"); Param(float &external_val) : _val(external_val) @@ -178,7 +178,7 @@ class Param { public: // static type-check - static_assert(px4::param_types_array[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t"); + static_assert(px4::parameters[(int)p].type == PARAM_TYPE_INT32, "parameter type must be int32_t"); Param() { @@ -211,7 +211,7 @@ class Param { public: // static type-check - static_assert(px4::param_types_array[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t"); + static_assert(px4::parameters[(int)p].type == PARAM_TYPE_INT32, "parameter type must be int32_t"); Param(int32_t &external_val) : _val(external_val) @@ -244,7 +244,7 @@ class Param { public: // static type-check - static_assert(px4::param_types_array[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t"); + static_assert(px4::parameters[(int)p].type == PARAM_TYPE_INT32, "parameter type must be int32_t"); Param() { From 33a4f8bfa3aa55fba078618277cf629320805460 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 29 Sep 2018 12:23:04 -0400 Subject: [PATCH 3/6] parameters replace param_changed_storage storage with AtomicBitset - add Bitset and AtomicBitset with testing --- boards/bitcraze/crazyflie/default.cmake | 4 + platforms/posix/cmake/sitl_tests.cmake | 2 + src/lib/parameters/parameters.cpp | 201 ++++-------- src/lib/parameters/parameters_shmem.cpp | 338 +++++++++----------- src/lib/perf/CMakeLists.txt | 2 +- src/platforms/px4_atomic.h | 5 +- src/platforms/px4_atomic_bitset.hpp | 106 ++++++ src/platforms/px4_bitset.hpp | 95 ++++++ src/systemcmds/tests/CMakeLists.txt | 2 + src/systemcmds/tests/test_atomic_bitset.cpp | 175 ++++++++++ src/systemcmds/tests/test_bitset.cpp | 175 ++++++++++ src/systemcmds/tests/tests_main.c | 3 +- src/systemcmds/tests/tests_main.h | 2 + 13 files changed, 789 insertions(+), 321 deletions(-) create mode 100644 src/platforms/px4_atomic_bitset.hpp create mode 100644 src/platforms/px4_bitset.hpp create mode 100644 src/systemcmds/tests/test_atomic_bitset.cpp create mode 100644 src/systemcmds/tests/test_bitset.cpp diff --git a/boards/bitcraze/crazyflie/default.cmake b/boards/bitcraze/crazyflie/default.cmake index 73a9a8cf1550..b82098a98158 100644 --- a/boards/bitcraze/crazyflie/default.cmake +++ b/boards/bitcraze/crazyflie/default.cmake @@ -1,4 +1,8 @@ +# workaround for syslink parameter +# PARAM_DEFINE_INT32(SLNK_RADIO_ADDR2, 3890735079); // 0xE7E7E7E7 +add_compile_options(-Wno-narrowing) + px4_add_board( PLATFORM nuttx VENDOR bitcraze diff --git a/platforms/posix/cmake/sitl_tests.cmake b/platforms/posix/cmake/sitl_tests.cmake index 5ec133cc7d11..e42daeeb58d8 100644 --- a/platforms/posix/cmake/sitl_tests.cmake +++ b/platforms/posix/cmake/sitl_tests.cmake @@ -4,8 +4,10 @@ # TODO: find a way to keep this in sync with tests_main set(tests + atomic_bitset autodeclination bezier + bitset bson commander controllib diff --git a/src/lib/parameters/parameters.cpp b/src/lib/parameters/parameters.cpp index 42efbeef033a..03e043c5444d 100644 --- a/src/lib/parameters/parameters.cpp +++ b/src/lib/parameters/parameters.cpp @@ -49,6 +49,7 @@ #include #include +#include #include #include #include @@ -93,11 +94,11 @@ static char *param_user_file = nullptr; /* autosaving variables */ static hrt_abstime last_autosave_timestamp = 0; static struct work_s autosave_work {}; -static volatile bool autosave_scheduled = false; +static px4::atomic autosave_scheduled{false}; static bool autosave_disabled = false; #endif /* PARAM_NO_AUTOSAVE */ -static constexpr int param_info_count = sizeof(px4::parameters) / sizeof(param_info_s); +static constexpr uint16_t param_info_count = sizeof(px4::parameters) / sizeof(param_info_s); // Storage for modified parameters. struct param_wbuf_s { @@ -106,31 +107,7 @@ struct param_wbuf_s { bool unsaved; }; - -uint8_t *param_changed_storage = nullptr; -int size_param_changed_storage_bytes = 0; -const int bits_per_allocation_unit = (sizeof(*param_changed_storage) * 8); - - -static unsigned -get_param_info_count() -{ - /* Singleton creation of and array of bits to track changed values */ - if (!param_changed_storage) { - /* Note that we have a (highly unlikely) race condition here: in the worst case the allocation is done twice */ - size_param_changed_storage_bytes = (param_info_count / bits_per_allocation_unit) + 1; - param_changed_storage = (uint8_t *)calloc(size_param_changed_storage_bytes, 1); - - /* If the allocation fails we need to indicate failure in the - * API by returning PARAM_INVALID - */ - if (param_changed_storage == nullptr) { - return 0; - } - } - - return param_info_count; -} +static px4::AtomicBitset params_active; /** flexible array holding modified parameter values */ UT_array *param_values{nullptr}; @@ -144,9 +121,9 @@ static orb_advert_t param_topic = nullptr; static unsigned int param_instance = 0; #endif -static void param_set_used_internal(param_t param); - static param_t param_find_internal(const char *name, bool notification); +int param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_changes); +const void *param_get_value_ptr(param_t param); // 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 @@ -211,13 +188,6 @@ param_unlock_writer() px4_sem_post(¶m_sem); } -/** assert that the parameter store is locked */ -static void -param_assert_locked() -{ - /* XXX */ -} - void param_init() { @@ -237,15 +207,14 @@ param_init() * @param param The parameter handle to test. * @return True if the handle is valid. */ -static bool +static constexpr bool handle_in_range(param_t param) { - unsigned count = get_param_info_count(); - return (count && param < count); + return (param < param_info_count); } /** - * Compare two modifid parameter structures to determine ordering. + * Compare two modified parameter structures to determine ordering. * * This function is suitable for passing to qsort or bsearch. */ @@ -276,14 +245,15 @@ param_compare_values(const void *a, const void *b) static param_wbuf_s * param_find_changed(param_t param) { - param_wbuf_s *s = nullptr; + param_wbuf_s *s = nullptr; - param_assert_locked(); + if (params_active[param]) { - if (param_values != nullptr) { - param_wbuf_s key{}; - key.param = param; - s = (param_wbuf_s *)utarray_find(param_values, &key, param_compare_values); + if (param_values != nullptr) { + param_wbuf_s key{}; + key.param = param; + s = (param_wbuf_s *)utarray_find(param_values, &key, param_compare_values); + } } return s; @@ -324,17 +294,17 @@ param_find_internal(const char *name, bool notification) param_t middle; param_t front = 0; - param_t last = get_param_info_count(); + param_t last = param_info_count; /* perform a binary search of the known parameters */ while (front <= last) { middle = front + (last - front) / 2; - int ret = strcmp(name, px4::parameters[middle].name); + int ret = strcmp(name, param_name(middle)); if (ret == 0) { if (notification) { - param_set_used_internal(middle); + param_set_used(middle); } perf_end(param_find_perf); @@ -373,35 +343,19 @@ param_find_no_notification(const char *name) unsigned param_count() { - return get_param_info_count(); + return param_info_count; } unsigned param_count_used() { - unsigned count = 0; - - // ensure the allocation has been done - if (get_param_info_count()) { - - for (int i = 0; i < size_param_changed_storage_bytes; i++) { - for (int j = 0; j < bits_per_allocation_unit; j++) { - if (param_changed_storage[i] & (1 << j)) { - count++; - } - } - } - } - - return count; + return params_active.count(); } param_t param_for_index(unsigned index) { - unsigned count = get_param_info_count(); - - if (count && index < count) { + if (index < param_info_count) { return (param_t)index; } @@ -411,25 +365,19 @@ param_for_index(unsigned index) param_t param_for_used_index(unsigned index) { - int count = get_param_info_count(); - - if (count && (int)index < count) { - /* walk all params and count used params */ + if (index < param_info_count) { + // walk all params and count used params unsigned used_count = 0; - for (int i = 0; i < size_param_changed_storage_bytes; i++) { - for (int j = 0; j < bits_per_allocation_unit; j++) { - if (param_changed_storage[i] & (1 << j)) { + for (int i = 0; i < params_active.size(); i++) { - /* we found the right used count, - * return the param value - */ - if (index == used_count) { - return (param_t)(i * bits_per_allocation_unit + j); - } - - used_count++; + if (params_active[i]) { + // we found the right used count, return the param_t value + if (index == used_count) { + return (param_t)i; } + + used_count++; } } } @@ -458,16 +406,16 @@ param_get_used_index(param_t param) /* walk all params and count, now knowing that it has a valid index */ int used_count = 0; - for (int i = 0; i < size_param_changed_storage_bytes; i++) { - for (int j = 0; j < bits_per_allocation_unit; j++) { - if (param_changed_storage[i] & (1 << j)) { - - if ((int)param == i * bits_per_allocation_unit + j) { - return used_count; - } + for (int i = 0; i < params_active.size(); i++) { - used_count++; + if (params_active[i]) { + if (param == i) { + // found the right parameter, + // return the index within the used set (count) + return used_count; } + + used_count++; } } @@ -480,6 +428,12 @@ param_name(param_t param) return handle_in_range(param) ? px4::parameters[param].name : nullptr; } +param_type_t +param_type(param_t param) +{ + return handle_in_range(param) ? px4::parameters[param].type : PARAM_TYPE_UNKNOWN; +} + bool param_is_volatile(param_t param) { @@ -507,12 +461,6 @@ param_value_unsaved(param_t param) return ret; } -param_type_t -param_type(param_t param) -{ - return handle_in_range(param) ? px4::parameters[param].type : PARAM_TYPE_UNKNOWN; -} - size_t param_size(param_t param) { @@ -543,13 +491,11 @@ param_size(param_t param) * @return A pointer to the parameter value, or nullptr * if the parameter does not exist. */ -static const void * +const void * param_get_value_ptr(param_t param) { const void *result = nullptr; - param_assert_locked(); - if (handle_in_range(param)) { const union param_value_u *v; @@ -610,7 +556,7 @@ autosave_worker(void *arg) param_lock_writer(); last_autosave_timestamp = hrt_absolute_time(); - autosave_scheduled = false; + autosave_scheduled.store(false); disabled = autosave_disabled; param_unlock_writer(); @@ -638,7 +584,7 @@ param_autosave() { #ifndef PARAM_NO_AUTOSAVE - if (autosave_scheduled || autosave_disabled) { + if (autosave_scheduled.load() || autosave_disabled) { return; } @@ -648,14 +594,14 @@ param_autosave() // looks at all unsaved params. hrt_abstime delay = 300_ms; - static constexpr const hrt_abstime rate_limit = 2_s; // rate-limit saving to 2 seconds + static constexpr hrt_abstime rate_limit = 2_s; // rate-limit saving to 2 seconds 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 = true; + autosave_scheduled.store(true); work_queue(LPWORK, &autosave_work, (worker_t)&autosave_worker, nullptr, USEC2TICK(delay)); #endif /* PARAM_NO_AUTOSAVE */ } @@ -666,9 +612,9 @@ param_control_autosave(bool enable) #ifndef PARAM_NO_AUTOSAVE param_lock_writer(); - if (!enable && autosave_scheduled) { + if (!enable && autosave_scheduled.load()) { work_cancel(LPWORK, &autosave_work); - autosave_scheduled = false; + autosave_scheduled.store(false); } autosave_disabled = !enable; @@ -676,7 +622,7 @@ param_control_autosave(bool enable) #endif /* PARAM_NO_AUTOSAVE */ } -static int +int param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_changes) { int result = -1; @@ -685,8 +631,14 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_ param_lock_writer(); perf_begin(param_set_perf); + // create the parameter store if it doesn't exist if (param_values == nullptr) { utarray_new(param_values, ¶m_icd); + + // mark all parameters inactive + for (int i = 0; i < params_active.size(); i++) { + params_active.set(i, false); + } } if (param_values == nullptr) { @@ -701,7 +653,7 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_ if (s == nullptr) { /* construct a new parameter */ - param_wbuf_s buf = {}; + param_wbuf_s buf{}; buf.param = param; params_changed = true; @@ -711,6 +663,7 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_ utarray_sort(param_values, param_compare_values); /* find it after sorting */ + param_set_used(param); s = param_find_changed(param); } @@ -802,32 +755,18 @@ param_set_no_notification(param_t param, const void *val) bool param_used(param_t param) { - int param_index = param_get_index(param); - - if (param_index < 0) { - return false; + if (handle_in_range(param)) { + return params_active[param]; } - return param_changed_storage[param_index / bits_per_allocation_unit] & - (1 << param_index % bits_per_allocation_unit); + return false; } void param_set_used(param_t param) { - param_set_used_internal(param); -} - -void param_set_used_internal(param_t param) -{ - int param_index = param_get_index(param); - - if (param_index < 0) { - return; + if (handle_in_range(param)) { + params_active.set(param, true); } - - // FIXME: this needs locking too - param_changed_storage[param_index / bits_per_allocation_unit] |= - (1 << param_index % bits_per_allocation_unit); } int @@ -892,9 +831,7 @@ param_reset_all() void param_reset_excludes(const char *excludes[], int num_excludes) { - param_t param; - - for (param = 0; handle_in_range(param); param++) { + for (param_t param = 0; handle_in_range(param); param++) { const char *name = param_name(param); bool exclude = false; @@ -1327,9 +1264,7 @@ param_load(int fd) void param_foreach(void (*func)(void *arg, param_t param), void *arg, bool only_changed, bool only_used) { - param_t param; - - for (param = 0; handle_in_range(param); param++) { + for (param_t param = 0; handle_in_range(param); param++) { /* if requested, skip unchanged values */ if (only_changed && (param_find_changed(param) == nullptr)) { diff --git a/src/lib/parameters/parameters_shmem.cpp b/src/lib/parameters/parameters_shmem.cpp index 0d9d16dce040..192bae565d00 100644 --- a/src/lib/parameters/parameters_shmem.cpp +++ b/src/lib/parameters/parameters_shmem.cpp @@ -49,16 +49,18 @@ #include #include +#include #include +#include #include #include #include #include #include - -#include #include +using namespace time_literals; + //#define PARAM_NO_ORB ///< if defined, avoid uorb dependency. This disables publication of parameter_update on param change //#define PARAM_NO_AUTOSAVE ///< if defined, do not autosave (avoids LP work queue dependency) @@ -69,6 +71,12 @@ #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) { 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 #include @@ -94,12 +102,12 @@ static char *param_user_file = nullptr; #include /* autosaving variables */ static hrt_abstime last_autosave_timestamp = 0; -static struct work_s autosave_work; -static bool autosave_scheduled = false; +static struct work_s autosave_work {}; +static px4::atomic autosave_scheduled{false}; static bool autosave_disabled = false; #endif /* PARAM_NO_AUTOSAVE */ -static constexpr int param_info_count = sizeof(px4::parameters) / sizeof(param_info_s); +static constexpr uint16_t param_info_count = sizeof(px4::parameters) / sizeof(param_info_s); // Storage for modified parameters. struct param_wbuf_s { @@ -108,15 +116,11 @@ struct param_wbuf_s { bool unsaved; }; - -uint8_t *param_changed_storage = nullptr; -int size_param_changed_storage_bytes = 0; -const int bits_per_allocation_unit = (sizeof(*param_changed_storage) * 8); +static px4::AtomicBitset params_active; //#define ENABLE_SHMEM_DEBUG static void init_params(); -static int param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_changes); static unsigned char set_called_from_get = 0; static int param_import_done = @@ -124,26 +128,6 @@ static int param_import_done = static int param_load_default_no_notify(); -static unsigned -get_param_info_count() -{ - /* Singleton creation of and array of bits to track changed values */ - if (!param_changed_storage) { - /* Note that we have a (highly unlikely) race condition here: in the worst case the allocation is done twice */ - size_param_changed_storage_bytes = (param_info_count / bits_per_allocation_unit) + 1; - param_changed_storage = (uint8_t *)calloc(size_param_changed_storage_bytes, 1); - - /* If the allocation fails we need to indicate failure in the - * API by returning PARAM_INVALID - */ - if (param_changed_storage == nullptr) { - return 0; - } - } - - return param_info_count; -} - /** flexible array holding modified parameter values */ UT_array *param_values{nullptr}; @@ -156,9 +140,9 @@ static orb_advert_t param_topic = nullptr; static unsigned int param_instance = 0; #endif -static void param_set_used_internal(param_t param); - static param_t param_find_internal(const char *name, bool notification); +int param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_changes); +const void *param_get_value_ptr(param_t param); // TODO: not working on Snappy just yet // the following implements an RW-lock using 2 semaphores (used as mutexes). It gives @@ -237,13 +221,6 @@ param_unlock_writer() #endif } -/** assert that the parameter store is locked */ -static void -param_assert_locked() -{ - /* XXX */ -} - void param_init() { @@ -261,6 +238,11 @@ param_init() PX4_DEBUG("Syncing params to shared memory\n"); init_params(); #endif + + // mark all parameters active + for (int i = 0; i < params_active.size(); i++) { + params_active.set(i, true); + } } /** @@ -272,12 +254,11 @@ param_init() bool handle_in_range(param_t param) { - unsigned count = get_param_info_count(); - return (count && param < count); + return (param < param_info_count); } /** - * Compare two modifid parameter structures to determine ordering. + * Compare two modified parameter structures to determine ordering. * * This function is suitable for passing to qsort or bsearch. */ @@ -308,14 +289,15 @@ param_compare_values(const void *a, const void *b) param_wbuf_s * param_find_changed(param_t param) { - param_wbuf_s *s = nullptr; + param_wbuf_s *s = nullptr; - param_assert_locked(); + if (params_active[param]) { - if (param_values != nullptr) { - param_wbuf_s key{}; - key.param = param; - s = (param_wbuf_s *)utarray_find(param_values, &key, param_compare_values); + if (param_values != nullptr) { + param_wbuf_s key{}; + key.param = param; + s = (param_wbuf_s *)utarray_find(param_values, &key, param_compare_values); + } } return s; @@ -354,17 +336,33 @@ param_find_internal(const char *name, bool notification) { perf_begin(param_find_perf); - param_t param; + param_t middle; + param_t front = 0; + param_t last = param_info_count; + + /* perform a binary search of the known parameters */ - /* perform a linear search of the known parameters */ - for (param = 0; handle_in_range(param); param++) { - if (!strcmp(px4::parameters[param].name, name)) { + while (front <= last) { + middle = front + (last - front) / 2; + int ret = strcmp(name, param_name(middle)); + + if (ret == 0) { if (notification) { - param_set_used_internal(param); + param_set_used(middle); } perf_end(param_find_perf); - return param; + return middle; + + } else if (middle == front) { + /* An end point has been hit, but there has been no match */ + break; + + } else if (ret < 0) { + last = middle; + + } else { + front = middle; } } @@ -389,40 +387,19 @@ param_find_no_notification(const char *name) unsigned param_count() { - return get_param_info_count(); + return param_info_count; } unsigned param_count_used() { - //TODO FIXME: all params used right now -#if 0 - unsigned count = 0; - - // ensure the allocation has been done - if (get_param_info_count()) { - - for (int i = 0; i < size_param_changed_storage_bytes; i++) { - for (int j = 0; j < bits_per_allocation_unit; j++) { - if (param_changed_storage[i] & (1 << j)) { - count++; - } - } - } - } - - return count; -#else - return get_param_info_count(); -#endif + return params_active.count(); } param_t param_for_index(unsigned index) { - unsigned count = get_param_info_count(); - - if (count && index < count) { + if (index < param_info_count) { return (param_t)index; } @@ -432,34 +409,24 @@ param_for_index(unsigned index) param_t param_for_used_index(unsigned index) { -#if 0 - int count = get_param_info_count(); - - if (count && (int)index < count) { - /* walk all params and count used params */ + if (index < param_info_count) { + // walk all params and count used params unsigned used_count = 0; - for (int i = 0; i < size_param_changed_storage_bytes; i++) { - for (int j = 0; j < bits_per_allocation_unit; j++) { - if (param_changed_storage[i] & (1 << j)) { + for (int i = 0; i < params_active.size(); i++) { - /* we found the right used count, - * return the param value - */ - if (index == used_count) { - return (param_t)(i * bits_per_allocation_unit + j); - } - - used_count++; + if (params_active[i]) { + // we found the right used count, return the param_t value + if (index == used_count) { + return (param_t)i; } + + used_count++; } } } return PARAM_INVALID; -#else - return param_for_index(index); -#endif } int @@ -475,8 +442,6 @@ param_get_index(param_t param) int param_get_used_index(param_t param) { - // TODO FIXME: the used bit is not supported right now, therefore just count all. -#if 0 /* this tests for out of bounds and does a constant time lookup */ if (!param_used(param)) { return -1; @@ -485,24 +450,20 @@ param_get_used_index(param_t param) /* walk all params and count, now knowing that it has a valid index */ int used_count = 0; - for (int i = 0; i < size_param_changed_storage_bytes; i++) { - for (int j = 0; j < bits_per_allocation_unit; j++) { - if (param_changed_storage[i] & (1 << j)) { - - if ((int)param == i * bits_per_allocation_unit + j) { - return used_count; - } + for (int i = 0; i < params_active.size(); i++) { - used_count++; + if (params_active[i]) { + if (param == i) { + // found the right parameter, + // return the index within the used set (count) + return used_count; } + + used_count++; } } return -1; -#else - return param; -#endif - } const char * @@ -511,6 +472,12 @@ param_name(param_t param) return handle_in_range(param) ? px4::parameters[param].name : nullptr; } +param_type_t +param_type(param_t param) +{ + return handle_in_range(param) ? px4::parameters[param].type : PARAM_TYPE_UNKNOWN; +} + bool param_is_volatile(param_t param) { @@ -538,12 +505,6 @@ param_value_unsaved(param_t param) return ret; } -param_type_t -param_type(param_t param) -{ - return handle_in_range(param) ? px4::parameters[param].type : PARAM_TYPE_UNKNOWN; -} - size_t param_size(param_t param) { @@ -574,13 +535,11 @@ param_size(param_t param) * @return A pointer to the parameter value, or nullptr * if the parameter does not exist. */ -static const void * +const void * param_get_value_ptr(param_t param) { const void *result = nullptr; - param_assert_locked(); - if (handle_in_range(param)) { const union param_value_u *v; @@ -669,7 +628,7 @@ autosave_worker(void *arg) param_lock_writer(); last_autosave_timestamp = hrt_absolute_time(); - autosave_scheduled = false; + autosave_scheduled.store(false); disabled = autosave_disabled; param_unlock_writer(); @@ -681,7 +640,7 @@ autosave_worker(void *arg) int ret = param_save_default(); if (ret != 0) { - PX4_ERR("param save failed (%i)", ret); + PX4_ERR("param auto save failed (%i)", ret); } } #endif /* PARAM_NO_AUTOSAVE */ @@ -697,7 +656,7 @@ param_autosave() { #ifndef PARAM_NO_AUTOSAVE - if (autosave_scheduled || autosave_disabled) { + if (autosave_scheduled.load() || autosave_disabled) { return; } @@ -705,16 +664,16 @@ param_autosave() // - tasks often call param_set() for multiple params, so this avoids unnecessary save calls // - the logger stores changed params. He gets notified on a param change via uORB and then // looks at all unsaved params. - hrt_abstime delay = 300 * 1000; + hrt_abstime delay = 300_ms; - const hrt_abstime rate_limit = 2000 * 1000; // rate-limit saving to 2 seconds - hrt_abstime last_save_elapsed = hrt_elapsed_time(&last_autosave_timestamp); + static constexpr hrt_abstime rate_limit = 2_s; // rate-limit saving to 2 seconds + 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 = true; + autosave_scheduled.store(true); work_queue(LPWORK, &autosave_work, (worker_t)&autosave_worker, nullptr, USEC2TICK(delay)); #endif /* PARAM_NO_AUTOSAVE */ } @@ -725,9 +684,9 @@ param_control_autosave(bool enable) #ifndef PARAM_NO_AUTOSAVE param_lock_writer(); - if (!enable && autosave_scheduled) { + if (!enable && autosave_scheduled.load()) { work_cancel(LPWORK, &autosave_work); - autosave_scheduled = false; + autosave_scheduled.store(false); } autosave_disabled = !enable; @@ -735,7 +694,7 @@ param_control_autosave(bool enable) #endif /* PARAM_NO_AUTOSAVE */ } -static int +int param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_changes) { int result = -1; @@ -744,8 +703,14 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_ param_lock_writer(); perf_begin(param_set_perf); + // create the parameter store if it doesn't exist if (param_values == nullptr) { utarray_new(param_values, ¶m_icd); + + // mark all parameters inactive + for (int i = 0; i < params_active.size(); i++) { + params_active.set(i, false); + } } if (param_values == nullptr) { @@ -760,7 +725,7 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_ if (s == nullptr) { /* construct a new parameter */ - param_wbuf_s buf = {}; + param_wbuf_s buf{}; buf.param = param; params_changed = true; @@ -770,6 +735,7 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_ utarray_sort(param_values, param_compare_values); /* find it after sorting */ + param_set_used(param); s = param_find_changed(param); } @@ -828,7 +794,9 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_ * a thing has been set. */ - if (!param_import_done) { notify_changes = 0; } + if (!param_import_done) { + notify_changes = 0; + } if (params_changed && notify_changes) { _param_notify_changes(); @@ -884,35 +852,18 @@ param_set_no_notification(param_t param, const void *val) bool param_used(param_t param) { - // TODO FIXME: for now all params are used - return true; - - int param_index = param_get_index(param); - - if (param_index < 0) { - return false; + if (handle_in_range(param)) { + return params_active[param]; } - return param_changed_storage[param_index / bits_per_allocation_unit] & - (1 << param_index % bits_per_allocation_unit); + return false; } void param_set_used(param_t param) { - param_set_used_internal(param); -} - -void param_set_used_internal(param_t param) -{ - int param_index = param_get_index(param); - - if (param_index < 0) { - return; + if (handle_in_range(param)) { + params_active.set(param, true); } - - // FIXME: this needs locking too - param_changed_storage[param_index / bits_per_allocation_unit] |= - (1 << param_index % bits_per_allocation_unit); } int @@ -977,9 +928,7 @@ param_reset_all() void param_reset_excludes(const char *excludes[], int num_excludes) { - param_t param; - - for (param = 0; handle_in_range(param); param++) { + for (param_t param = 0; handle_in_range(param); param++) { const char *name = param_name(param); bool exclude = false; @@ -1006,6 +955,11 @@ param_reset_excludes(const char *excludes[], int num_excludes) int param_set_default_file(const char *filename) { +#ifdef FLASH_BASED_PARAMS + // the default for flash-based params is always the FLASH + (void)filename; +#else + if (param_user_file != nullptr) { // we assume this is not in use by some other thread free(param_user_file); @@ -1016,6 +970,8 @@ param_set_default_file(const char *filename) param_user_file = strdup(filename); } +#endif /* FLASH_BASED_PARAMS */ + return 0; } @@ -1072,13 +1028,18 @@ int param_load_default() { int res = 0; -#if !defined(FLASH_BASED_PARAMS) - int fd_load = PARAM_OPEN(param_get_default_file(), O_RDONLY); + const char *filename = param_get_default_file(); + + if (!filename) { + return flash_param_load(); + } + + int fd_load = PARAM_OPEN(filename, O_RDONLY); if (fd_load < 0) { /* no parameter file is OK, otherwise this is an error */ if (errno != ENOENT) { - PX4_ERR("open '%s' for reading failed", param_get_default_file()); + PX4_ERR("open '%s' for reading failed", filename); return -1; } @@ -1089,14 +1050,10 @@ param_load_default() PARAM_CLOSE(fd_load); if (result != 0) { - PX4_ERR("error reading parameters from '%s'", param_get_default_file()); + PX4_ERR("error reading parameters from '%s'", filename); return -2; } -#else - // no need for locking - res = flash_param_load(); -#endif return res; } @@ -1139,11 +1096,19 @@ param_load_default_no_notify() int param_export(int fd, bool only_unsaved) { + int result = -1; perf_begin(param_export_perf); - param_wbuf_s *s = nullptr; - int result = -1; + if (fd < 0) { + param_lock_writer(); + // flash_param_save() will take the shutdown lock + result = flash_param_save(only_unsaved); + param_unlock_writer(); + perf_end(param_export_perf); + return result; + } + param_wbuf_s *s = nullptr; struct bson_encoder_s encoder; int shutdown_lock_ret = px4_shutdown_lock(); @@ -1157,7 +1122,8 @@ param_export(int fd, bool only_unsaved) param_lock_reader(); - bson_encoder_init_file(&encoder, fd); + uint8_t bson_buffer[256]; + bson_encoder_init_buf_file(&encoder, fd, &bson_buffer, sizeof(bson_buffer)); /* no modified parameters -> we are done */ if (param_values == nullptr) { @@ -1165,9 +1131,11 @@ param_export(int fd, bool only_unsaved) goto out; } +#ifdef CONFIG_SHMEM /* First of all, update the index which will call param_get for params * that have recently been changed. */ update_index_from_shmem(); +#endif /* CONFIG_SHMEM */ while ((s = (struct param_wbuf_s *)utarray_next(param_values, s)) != nullptr) { /* @@ -1180,8 +1148,10 @@ param_export(int fd, bool only_unsaved) s->unsaved = false; +#ifdef CONFIG_SHMEM /* Make sure to get latest from shmem before saving. */ update_from_shmem(s->param, &s->val); +#endif /* CONFIG_SHMEM */ const char *name = param_name(s->param); const size_t size = param_size(s->param); @@ -1238,20 +1208,21 @@ param_export(int fd, bool only_unsaved) result = 0; out: + + if (result == 0) { + if (bson_encoder_fini(&encoder) != PX4_OK) { + PX4_ERR("bson encoder finish failed"); + } + } + param_unlock_reader(); //px4_sem_post(¶m_sem_save); - 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); - } - perf_end(param_export_perf); return result; @@ -1404,7 +1375,6 @@ param_import_internal(int fd, bool mark_saved) do { result = bson_decoder_next(&decoder); - usleep(1); } while (result > 0); @@ -1414,18 +1384,20 @@ param_import_internal(int fd, bool mark_saved) int param_import(int fd) { -#if !defined(FLASH_BASED_PARAMS) + if (fd < 0) { + return flash_param_import(); + } + return param_import_internal(fd, false); -#else - (void)fd; // unused - // no need for locking here - return flash_param_import(); -#endif } int param_load(int fd) { + if (fd < 0) { + return flash_param_load(); + } + param_reset_all_internal(false); return param_import_internal(fd, true); } @@ -1433,9 +1405,7 @@ param_load(int fd) void param_foreach(void (*func)(void *arg, param_t param), void *arg, bool only_changed, bool only_used) { - param_t param; - - for (param = 0; handle_in_range(param); param++) { + for (param_t param = 0; handle_in_range(param); param++) { /* if requested, skip unchanged values */ if (only_changed && (param_find_changed(param) == nullptr)) { diff --git a/src/lib/perf/CMakeLists.txt b/src/lib/perf/CMakeLists.txt index ee474d8ecba9..0da8658ef16a 100644 --- a/src/lib/perf/CMakeLists.txt +++ b/src/lib/perf/CMakeLists.txt @@ -32,4 +32,4 @@ ############################################################################ add_library(perf perf_counter.cpp) -add_dependencies(perf prebuild_targets) \ No newline at end of file +add_dependencies(perf prebuild_targets) diff --git a/src/platforms/px4_atomic.h b/src/platforms/px4_atomic.h index be2858ea830d..c7392b46dfae 100644 --- a/src/platforms/px4_atomic.h +++ b/src/platforms/px4_atomic.h @@ -72,6 +72,7 @@ class atomic static_assert(__atomic_always_lock_free(sizeof(T), 0), "atomic is not lock-free for the given type T"); #endif + atomic() = default; explicit atomic(T value) : _value(value) {} @@ -170,9 +171,9 @@ class atomic #ifdef __PX4_QURT // It seems that __atomic_store and __atomic_load are not supported on Qurt, // so the best that we can do is to use volatile. - volatile T _value; + volatile T _value{}; #else - T _value; + T _value {}; #endif }; diff --git a/src/platforms/px4_atomic_bitset.hpp b/src/platforms/px4_atomic_bitset.hpp new file mode 100644 index 000000000000..23900338126b --- /dev/null +++ b/src/platforms/px4_atomic_bitset.hpp @@ -0,0 +1,106 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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 + * 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. + * + ****************************************************************************/ + +#pragma once + +#include "px4_atomic.h" + +namespace px4 +{ + +template +class AtomicBitset +{ +public: + + AtomicBitset() + { + for (auto &x : _data) { + x.store(0); + } + } + + size_t count() const + { + size_t total = 0; + + for (const auto &x : _data) { + const uint32_t y = x.load(); + + for (uint8_t i = 0; i < BITS_PER_ELEMENT; i++) { + const uint32_t mask = 1 << i; + + if (y & mask) { + total++; + } + } + } + + return total; + } + + size_t size() const { return N; } + + bool operator[](size_t position) const + { + return _data[array_index(position)].load() & element_index(position); + } + + void set(size_t pos, bool val = true) + { + const uint32_t bitmask = element_index(pos); + + if (val) { + _data[array_index(pos)].fetch_or(bitmask); + + } else { + _data[array_index(pos)].fetch_and(~bitmask); + } + } + +private: + + static constexpr uint8_t BITS_PER_ELEMENT = 32; + static constexpr size_t ARRAY_SIZE = ((N % BITS_PER_ELEMENT) == 0) ? (N / BITS_PER_ELEMENT) : + (N / BITS_PER_ELEMENT + 1); + static constexpr size_t ALLOCATED_BITS = ARRAY_SIZE * BITS_PER_ELEMENT; + + size_t array_index(size_t position) const { return position / BITS_PER_ELEMENT; } + + uint32_t element_index(size_t position) const { return (1 << (position % BITS_PER_ELEMENT)); } + + px4::atomic _data[ARRAY_SIZE]; + +}; + +} // namespace px4 diff --git a/src/platforms/px4_bitset.hpp b/src/platforms/px4_bitset.hpp new file mode 100644 index 000000000000..053005e05b62 --- /dev/null +++ b/src/platforms/px4_bitset.hpp @@ -0,0 +1,95 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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 + * 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. + * + ****************************************************************************/ + +#pragma once + +namespace px4 +{ + +template +class Bitset +{ +public: + + size_t count() const + { + size_t total = 0; + + for (const auto &x : _data) { + for (uint8_t i = 0; i < BITS_PER_ELEMENT; i++) { + const uint8_t mask = 1 << i; + + if (x & mask) { + total++; + } + } + } + + return total; + } + + size_t size() const { return N; } + + bool operator[](size_t position) const + { + return _data[array_index(position)] & element_index(position); + } + + void set(size_t pos, bool val = true) + { + const uint8_t bitmask = element_index(pos); + + if (val) { + _data[array_index(pos)] |= bitmask; + + } else { + _data[array_index(pos)] &= ~bitmask; + } + } + +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; + static constexpr size_t ALLOCATED_BITS = ARRAY_SIZE * BITS_PER_ELEMENT; + + size_t array_index(size_t position) const { return position / BITS_PER_ELEMENT; } + + uint8_t element_index(size_t position) const { return (1 << position % BITS_PER_ELEMENT); } + + + uint8_t _data[ARRAY_SIZE] {}; + +}; + +} // namespace px4 diff --git a/src/systemcmds/tests/CMakeLists.txt b/src/systemcmds/tests/CMakeLists.txt index ea77ef548e85..5e6c1877fc1b 100644 --- a/src/systemcmds/tests/CMakeLists.txt +++ b/src/systemcmds/tests/CMakeLists.txt @@ -33,8 +33,10 @@ set(srcs test_adc.c + test_atomic_bitset.cpp test_autodeclination.cpp test_bezierQuad.cpp + test_bitset.cpp test_bson.cpp test_controlmath.cpp test_conv.cpp diff --git a/src/systemcmds/tests/test_atomic_bitset.cpp b/src/systemcmds/tests/test_atomic_bitset.cpp new file mode 100644 index 000000000000..c9072fd1d8c7 --- /dev/null +++ b/src/systemcmds/tests/test_atomic_bitset.cpp @@ -0,0 +1,175 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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 + * 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. + * + ****************************************************************************/ + +#include + +#include + +class AtomicBitsetTest : public UnitTest +{ +public: + virtual bool run_tests(); + +private: + bool constructTest(); + bool setAllTest(); + bool setRandomTest(); + +}; + +bool AtomicBitsetTest::run_tests() +{ + ut_run_test(constructTest); + ut_run_test(setAllTest); + ut_run_test(setRandomTest); + + return (_tests_failed == 0); +} + + +ut_declare_test_c(test_atomic_bitset, AtomicBitsetTest) + +bool AtomicBitsetTest::constructTest() +{ + px4::AtomicBitset<10> test_bitset1; + + ut_compare("bitset size 10", test_bitset1.size(), 10); + ut_compare("bitset init count 0", test_bitset1.count(), 0); + + for (int i = 0; i < test_bitset1.size(); i++) { + ut_compare("bitset not set by default", test_bitset1[i], false); + } + + return true; +} + +bool AtomicBitsetTest::setAllTest() +{ + px4::AtomicBitset<100> test_bitset2; + + ut_compare("bitset size 100", test_bitset2.size(), 100); + ut_compare("bitset init count 0", test_bitset2.count(), 0); + + for (int i = 0; i < test_bitset2.size(); i++) { + ut_compare("bitset not set by default", test_bitset2[i], false); + } + + // set all + for (int i = 0; i < test_bitset2.size(); i++) { + test_bitset2.set(i, true); + } + + // check count + ut_compare("bitset count", test_bitset2.count(), 100); + + // verify all set + for (int i = 0; i < test_bitset2.size(); i++) { + ut_compare("bitset not true", test_bitset2[i], true); + } + + // set all back to false + for (int i = 0; i < test_bitset2.size(); i++) { + test_bitset2.set(i, false); + } + + // check count + ut_compare("bitset count", test_bitset2.count(), 0); + + // verify all no longer set + for (int i = 0; i < test_bitset2.size(); i++) { + ut_compare("bitset not false", test_bitset2[i], false); + } + + return true; +} + +bool AtomicBitsetTest::setRandomTest() +{ + px4::AtomicBitset<999> test_bitset3; + + ut_compare("bitset size 999", test_bitset3.size(), 999); + ut_compare("bitset init count 0", test_bitset3.count(), 0); + + for (int i = 0; i < test_bitset3.size(); i++) { + ut_compare("bitset not set by default", test_bitset3[i], false); + } + + // random set and verify 100 elements + const int random_test_size = 5; + int random_array[random_test_size] = { 3, 1, 4, 5, 9 }; + + // set random elements + for (auto x : random_array) { + test_bitset3.set(x, true); + ut_less_than("invalid test element range", x, test_bitset3.size()); + } + + // check count + ut_compare("bitset count", test_bitset3.count(), random_test_size); + + // check that only random elements are set + for (int i = 0; i < test_bitset3.size(); i++) { + + // is i in the random test array + // if so it should be set + bool i_in_random = false; + + for (auto x : random_array) { + if (i == x) { + i_in_random = true; + } + } + + if (i_in_random) { + ut_compare("bitset true", test_bitset3[i], true); + + } else { + ut_compare("bitset false", test_bitset3[i], false); + } + } + + // set all back to false + for (int i = 0; i < test_bitset3.size(); i++) { + test_bitset3.set(i, false); + } + + // check count + ut_compare("bitset count", test_bitset3.count(), 0); + + // verify all no longer set + for (int i = 0; i < test_bitset3.size(); i++) { + ut_compare("bitset not false", test_bitset3[i], false); + } + + return true; +} diff --git a/src/systemcmds/tests/test_bitset.cpp b/src/systemcmds/tests/test_bitset.cpp new file mode 100644 index 000000000000..8632924c7174 --- /dev/null +++ b/src/systemcmds/tests/test_bitset.cpp @@ -0,0 +1,175 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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 + * 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. + * + ****************************************************************************/ + +#include + +#include + +class BitsetTest : public UnitTest +{ +public: + virtual bool run_tests(); + +private: + bool constructTest(); + bool setAllTest(); + bool setRandomTest(); + +}; + +bool BitsetTest::run_tests() +{ + ut_run_test(constructTest); + ut_run_test(setAllTest); + ut_run_test(setRandomTest); + + return (_tests_failed == 0); +} + + +ut_declare_test_c(test_bitset, BitsetTest) + +bool BitsetTest::constructTest() +{ + px4::Bitset<10> test_bitset1; + + ut_compare("bitset size 10", test_bitset1.size(), 10); + ut_compare("bitset init count 0", test_bitset1.count(), 0); + + for (int i = 0; i < test_bitset1.size(); i++) { + ut_compare("bitset not set by default", test_bitset1[i], false); + } + + return true; +} + +bool BitsetTest::setAllTest() +{ + px4::Bitset<100> test_bitset2; + + ut_compare("bitset size 100", test_bitset2.size(), 100); + ut_compare("bitset init count 0", test_bitset2.count(), 0); + + for (int i = 0; i < test_bitset2.size(); i++) { + ut_compare("bitset not set by default", test_bitset2[i], false); + } + + // set all + for (int i = 0; i < test_bitset2.size(); i++) { + test_bitset2.set(i, true); + } + + // check count + ut_compare("bitset count", test_bitset2.count(), 100); + + // verify all set + for (int i = 0; i < test_bitset2.size(); i++) { + ut_compare("bitset not true", test_bitset2[i], true); + } + + // set all back to false + for (int i = 0; i < test_bitset2.size(); i++) { + test_bitset2.set(i, false); + } + + // check count + ut_compare("bitset count", test_bitset2.count(), 0); + + // verify all no longer set + for (int i = 0; i < test_bitset2.size(); i++) { + ut_compare("bitset not false", test_bitset2[i], false); + } + + return true; +} + +bool BitsetTest::setRandomTest() +{ + px4::Bitset<999> test_bitset3; + + ut_compare("bitset size 999", test_bitset3.size(), 999); + ut_compare("bitset init count 0", test_bitset3.count(), 0); + + for (int i = 0; i < test_bitset3.size(); i++) { + ut_compare("bitset not set by default", test_bitset3[i], false); + } + + // random set and verify 100 elements + const int random_test_size = 5; + int random_array[random_test_size] = { 3, 1, 4, 5, 9 }; + + // set random elements + for (auto x : random_array) { + test_bitset3.set(x, true); + ut_less_than("invalid test element range", x, test_bitset3.size()); + } + + // check count + ut_compare("bitset count", test_bitset3.count(), random_test_size); + + // check that only random elements are set + for (int i = 0; i < test_bitset3.size(); i++) { + + // is i in the random test array + // if so it should be set + bool i_in_random = false; + + for (auto x : random_array) { + if (i == x) { + i_in_random = true; + } + } + + if (i_in_random) { + ut_compare("bitset true", test_bitset3[i], true); + + } else { + ut_compare("bitset false", test_bitset3[i], false); + } + } + + // set all back to false + for (int i = 0; i < test_bitset3.size(); i++) { + test_bitset3.set(i, false); + } + + // check count + ut_compare("bitset count", test_bitset3.count(), 0); + + // verify all no longer set + for (int i = 0; i < test_bitset3.size(); i++) { + ut_compare("bitset not false", test_bitset3[i], false); + } + + return true; +} diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c index 7d4049cd11f2..37c8df0fe60d 100644 --- a/src/systemcmds/tests/tests_main.c +++ b/src/systemcmds/tests/tests_main.c @@ -81,9 +81,10 @@ const struct { {"rc", rc_tests_main, 0}, #endif /* __PX4_NUTTX */ - + {"atomic_bitset", test_atomic_bitset, 0}, {"autodeclination", test_autodeclination, 0}, {"bezier", test_bezierQuad, 0}, + {"bitset", test_bitset, 0}, {"bson", test_bson, 0}, {"conv", test_conv, 0}, {"ctlmath", test_controlmath, 0}, diff --git a/src/systemcmds/tests/tests_main.h b/src/systemcmds/tests/tests_main.h index 064669763544..cafc35d6d40a 100644 --- a/src/systemcmds/tests/tests_main.h +++ b/src/systemcmds/tests/tests_main.h @@ -44,8 +44,10 @@ __BEGIN_DECLS extern int test_adc(int argc, char *argv[]); +extern int test_atomic_bitset(int argc, char *argv[]); extern int test_autodeclination(int argc, char *argv[]); extern int test_bezierQuad(int argc, char *argv[]); +extern int test_bitset(int argc, char *argv[]); extern int test_bson(int argc, char *argv[]); extern int test_controlmath(int argc, char *argv[]); extern int test_conv(int argc, char *argv[]); From 24582c20c66be2db486920b16976dac5d87ad1c2 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 12 Jan 2019 11:06:04 -0500 Subject: [PATCH 4/6] boards delete unused __param linkage --- .../airmind/mindpx-v2/nuttx-config/scripts/script.ld | 9 --------- boards/auav/esc35-v1/nuttx-config/scripts/script.ld | 8 -------- boards/auav/x21/nuttx-config/scripts/script.ld | 8 -------- boards/av/x-v1/nuttx-config/scripts/script.ld | 8 -------- .../crazyflie/nuttx-config/scripts/script.ld | 8 -------- .../holybro/kakutef7/nuttx-config/scripts/script.ld | 9 --------- .../intel/aerofc-v1/nuttx-config/scripts/script.ld | 8 -------- .../mro/ctrl-zero-f7/nuttx-config/scripts/script.ld | 9 --------- boards/nxp/fmuk66-v3/nuttx-config/scripts/script.ld | 12 ------------ boards/omnibus/f4sd/nuttx-config/scripts/script.ld | 8 -------- boards/px4/cannode-v1/nuttx-config/scripts/script.ld | 8 -------- boards/px4/esc-v1/nuttx-config/scripts/script.ld | 8 -------- boards/px4/fmu-v2/nuttx-config/scripts/script.ld | 8 -------- boards/px4/fmu-v3/nuttx-config/scripts/script.ld | 8 -------- boards/px4/fmu-v4/nuttx-config/scripts/script.ld | 8 -------- boards/px4/fmu-v4pro/nuttx-config/scripts/script.ld | 8 -------- boards/px4/fmu-v5/nuttx-config/scripts/script.ld | 8 -------- boards/px4/fmu-v5x/nuttx-config/scripts/script.ld | 9 --------- .../s2740vc-v1/nuttx-config/scripts/script.ld | 8 -------- boards/uvify/core/nuttx-config/scripts/script.ld | 9 --------- 20 files changed, 169 deletions(-) diff --git a/boards/airmind/mindpx-v2/nuttx-config/scripts/script.ld b/boards/airmind/mindpx-v2/nuttx-config/scripts/script.ld index 0d19229c01cf..226e708fbddb 100644 --- a/boards/airmind/mindpx-v2/nuttx-config/scripts/script.ld +++ b/boards/airmind/mindpx-v2/nuttx-config/scripts/script.ld @@ -105,15 +105,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash - .ARM.extab : { *(.ARM.extab*) } > flash diff --git a/boards/auav/esc35-v1/nuttx-config/scripts/script.ld b/boards/auav/esc35-v1/nuttx-config/scripts/script.ld index 7a97b71f7010..c39d2c0db72b 100644 --- a/boards/auav/esc35-v1/nuttx-config/scripts/script.ld +++ b/boards/auav/esc35-v1/nuttx-config/scripts/script.ld @@ -98,14 +98,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/auav/x21/nuttx-config/scripts/script.ld b/boards/auav/x21/nuttx-config/scripts/script.ld index 0d19229c01cf..7b05d02ab1c0 100644 --- a/boards/auav/x21/nuttx-config/scripts/script.ld +++ b/boards/auav/x21/nuttx-config/scripts/script.ld @@ -105,14 +105,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/av/x-v1/nuttx-config/scripts/script.ld b/boards/av/x-v1/nuttx-config/scripts/script.ld index fae1d95de0ba..978468c3821c 100644 --- a/boards/av/x-v1/nuttx-config/scripts/script.ld +++ b/boards/av/x-v1/nuttx-config/scripts/script.ld @@ -129,14 +129,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/bitcraze/crazyflie/nuttx-config/scripts/script.ld b/boards/bitcraze/crazyflie/nuttx-config/scripts/script.ld index 0e83e428533f..1c820ddaea48 100644 --- a/boards/bitcraze/crazyflie/nuttx-config/scripts/script.ld +++ b/boards/bitcraze/crazyflie/nuttx-config/scripts/script.ld @@ -103,14 +103,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/holybro/kakutef7/nuttx-config/scripts/script.ld b/boards/holybro/kakutef7/nuttx-config/scripts/script.ld index 8b468bd6213a..156fe745b8c1 100644 --- a/boards/holybro/kakutef7/nuttx-config/scripts/script.ld +++ b/boards/holybro/kakutef7/nuttx-config/scripts/script.ld @@ -130,15 +130,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash - .ARM.extab : { *(.ARM.extab*) } > flash diff --git a/boards/intel/aerofc-v1/nuttx-config/scripts/script.ld b/boards/intel/aerofc-v1/nuttx-config/scripts/script.ld index e2d376d35cd4..57ef29871bf1 100644 --- a/boards/intel/aerofc-v1/nuttx-config/scripts/script.ld +++ b/boards/intel/aerofc-v1/nuttx-config/scripts/script.ld @@ -97,14 +97,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/mro/ctrl-zero-f7/nuttx-config/scripts/script.ld b/boards/mro/ctrl-zero-f7/nuttx-config/scripts/script.ld index d6188a20ef1d..0eefe88dff39 100644 --- a/boards/mro/ctrl-zero-f7/nuttx-config/scripts/script.ld +++ b/boards/mro/ctrl-zero-f7/nuttx-config/scripts/script.ld @@ -129,15 +129,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash - .ARM.extab : { *(.ARM.extab*) } > flash diff --git a/boards/nxp/fmuk66-v3/nuttx-config/scripts/script.ld b/boards/nxp/fmuk66-v3/nuttx-config/scripts/script.ld index a5db9d15b0a3..87c96efc45e8 100644 --- a/boards/nxp/fmuk66-v3/nuttx-config/scripts/script.ld +++ b/boards/nxp/fmuk66-v3/nuttx-config/scripts/script.ld @@ -105,18 +105,6 @@ SECTIONS . += 8; } > progflash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - . = ALIGN(8); - FILL(0xff) - . += 8; - } > progflash - .ARM.extab : { *(.ARM.extab*) . = ALIGN(8); diff --git a/boards/omnibus/f4sd/nuttx-config/scripts/script.ld b/boards/omnibus/f4sd/nuttx-config/scripts/script.ld index fce016b8285b..15dbed4d99b4 100644 --- a/boards/omnibus/f4sd/nuttx-config/scripts/script.ld +++ b/boards/omnibus/f4sd/nuttx-config/scripts/script.ld @@ -97,14 +97,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/px4/cannode-v1/nuttx-config/scripts/script.ld b/boards/px4/cannode-v1/nuttx-config/scripts/script.ld index 91e245b9fcbf..29a0f23c54b0 100644 --- a/boards/px4/cannode-v1/nuttx-config/scripts/script.ld +++ b/boards/px4/cannode-v1/nuttx-config/scripts/script.ld @@ -97,14 +97,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/px4/esc-v1/nuttx-config/scripts/script.ld b/boards/px4/esc-v1/nuttx-config/scripts/script.ld index 9382c28d9c00..28c75aa290fe 100644 --- a/boards/px4/esc-v1/nuttx-config/scripts/script.ld +++ b/boards/px4/esc-v1/nuttx-config/scripts/script.ld @@ -99,14 +99,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/px4/fmu-v2/nuttx-config/scripts/script.ld b/boards/px4/fmu-v2/nuttx-config/scripts/script.ld index c4e1cc90e770..0f733d4e80d1 100644 --- a/boards/px4/fmu-v2/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v2/nuttx-config/scripts/script.ld @@ -106,14 +106,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/px4/fmu-v3/nuttx-config/scripts/script.ld b/boards/px4/fmu-v3/nuttx-config/scripts/script.ld index 0d19229c01cf..7b05d02ab1c0 100644 --- a/boards/px4/fmu-v3/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v3/nuttx-config/scripts/script.ld @@ -105,14 +105,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/px4/fmu-v4/nuttx-config/scripts/script.ld b/boards/px4/fmu-v4/nuttx-config/scripts/script.ld index 0d19229c01cf..7b05d02ab1c0 100644 --- a/boards/px4/fmu-v4/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v4/nuttx-config/scripts/script.ld @@ -105,14 +105,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/px4/fmu-v4pro/nuttx-config/scripts/script.ld b/boards/px4/fmu-v4pro/nuttx-config/scripts/script.ld index 93e151556037..e729b537b601 100644 --- a/boards/px4/fmu-v4pro/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v4pro/nuttx-config/scripts/script.ld @@ -105,14 +105,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/px4/fmu-v5/nuttx-config/scripts/script.ld b/boards/px4/fmu-v5/nuttx-config/scripts/script.ld index fae1d95de0ba..978468c3821c 100644 --- a/boards/px4/fmu-v5/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v5/nuttx-config/scripts/script.ld @@ -129,14 +129,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld b/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld index fae1d95de0ba..0f4eb1884306 100644 --- a/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld @@ -129,15 +129,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash - .ARM.extab : { *(.ARM.extab*) } > flash diff --git a/boards/thiemar/s2740vc-v1/nuttx-config/scripts/script.ld b/boards/thiemar/s2740vc-v1/nuttx-config/scripts/script.ld index 5d92a06ccb94..533cb10bc85e 100644 --- a/boards/thiemar/s2740vc-v1/nuttx-config/scripts/script.ld +++ b/boards/thiemar/s2740vc-v1/nuttx-config/scripts/script.ld @@ -86,14 +86,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param)) - __param_end = ABSOLUTE(.); - } > flash .ARM.extab : { *(.ARM.extab*) diff --git a/boards/uvify/core/nuttx-config/scripts/script.ld b/boards/uvify/core/nuttx-config/scripts/script.ld index 0d19229c01cf..226e708fbddb 100644 --- a/boards/uvify/core/nuttx-config/scripts/script.ld +++ b/boards/uvify/core/nuttx-config/scripts/script.ld @@ -105,15 +105,6 @@ SECTIONS _einit = ABSOLUTE(.); } > flash - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash - .ARM.extab : { *(.ARM.extab*) } > flash From 6d2dfe2758d7c2af00b64e7cd64dcbd030967cce Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 29 Sep 2019 17:15:06 -0400 Subject: [PATCH 5/6] parameters: generated header store type and volatile separately --- src/lib/parameters/param.h | 20 +--------------- src/lib/parameters/parameters.cpp | 13 +++++++++-- src/lib/parameters/parameters_shmem.cpp | 13 +++++++++-- .../templates/px4_parameters.hpp.jinja | 23 +++++++++++++------ src/platforms/px4_param.h | 10 ++++---- 5 files changed, 44 insertions(+), 35 deletions(-) diff --git a/src/lib/parameters/param.h b/src/lib/parameters/param.h index e2cf3127fe7b..dd11835fae0e 100644 --- a/src/lib/parameters/param.h +++ b/src/lib/parameters/param.h @@ -447,25 +447,7 @@ union param_value_u { * instead. */ struct param_info_s { - const char *name - -// GCC 4.8 and higher don't implement proper alignment of static data on -// 64-bit. This means that the 24-byte param_info_s variables are -// 16 byte aligned by GCC and that messes up the assumption that -// sequential items in the __param segment can be addressed as an array. -// The assumption is that the address of the second parameter is at -// ¶m[0]+sizeof(param[0]). When compiled with clang it is -// true, with gcc is is not true. -// See https://llvm.org/bugs/show_bug.cgi?format=multiple&id=18006 -// The following hack is for GCC >=4.8 only. Clang works fine without -// this. -#ifdef __PX4_POSIX - __attribute__((aligned(16))); -#else - ; -#endif - param_type_t type; - uint16_t volatile_param: 1; + const char *name; union param_value_u val; }; diff --git a/src/lib/parameters/parameters.cpp b/src/lib/parameters/parameters.cpp index 03e043c5444d..d3fcd213e72a 100644 --- a/src/lib/parameters/parameters.cpp +++ b/src/lib/parameters/parameters.cpp @@ -431,13 +431,22 @@ param_name(param_t param) param_type_t param_type(param_t param) { - return handle_in_range(param) ? px4::parameters[param].type : PARAM_TYPE_UNKNOWN; + return handle_in_range(param) ? px4::parameters_type[param] : PARAM_TYPE_UNKNOWN; } bool param_is_volatile(param_t param) { - return handle_in_range(param) ? px4::parameters[param].volatile_param : false; + if (handle_in_range(param)) { + + for (const auto &p : px4::parameters_volatile) { + if (static_cast(param) == p) { + return true; + } + } + } + + return false; } bool diff --git a/src/lib/parameters/parameters_shmem.cpp b/src/lib/parameters/parameters_shmem.cpp index 192bae565d00..e4bf09cfc9b5 100644 --- a/src/lib/parameters/parameters_shmem.cpp +++ b/src/lib/parameters/parameters_shmem.cpp @@ -475,13 +475,22 @@ param_name(param_t param) param_type_t param_type(param_t param) { - return handle_in_range(param) ? px4::parameters[param].type : PARAM_TYPE_UNKNOWN; + return handle_in_range(param) ? px4::parameters_type[param] : PARAM_TYPE_UNKNOWN; } bool param_is_volatile(param_t param) { - return handle_in_range(param) ? px4::parameters[param].volatile_param : false; + if (handle_in_range(param)) { + + for (const auto &p : px4::parameters_volatile) { + if (static_cast(param) == p) { + return true; + } + } + } + + return false; } bool diff --git a/src/lib/parameters/templates/px4_parameters.hpp.jinja b/src/lib/parameters/templates/px4_parameters.hpp.jinja index e477344237e9..04ea82991a2a 100644 --- a/src/lib/parameters/templates/px4_parameters.hpp.jinja +++ b/src/lib/parameters/templates/px4_parameters.hpp.jinja @@ -9,7 +9,7 @@ namespace px4 { {# wrap the enum in a namespace, otherwise we get shadowing errors for MAV_TYPE #} /// Enum with all parameters -enum class params { +enum class params : uint16_t { {# enums are guaranteed to start with 0 (if the value for the first is not specified), and then incremented by 1 (the implementation depends on that!) #} {%- for param in params %} @@ -22,12 +22,6 @@ static constexpr param_info_s parameters[] = { {% for param in params %} { "{{ param.attrib["name"] }}", - PARAM_TYPE_{{ param.attrib["type"] }}, - {%- if param.attrib["volatile"] == "true" %} - .volatile_param = 1, - {%- else %} - .volatile_param = 0, - {%- endif %} {%- if param.attrib["type"] == "FLOAT" %} .val = {{ "{" }} .f = {{ param.attrib["default"] }} {{ "}" }}, {%- elif param.attrib["type"] == "INT32" %} @@ -37,4 +31,19 @@ static constexpr param_info_s parameters[] = { {% endfor %} }; +static constexpr param_type_t parameters_type[] = { +{% for param in params %} + PARAM_TYPE_{{ param.attrib["type"] }}, +{%- endfor -%} +}; + +static constexpr params parameters_volatile[] = { +{% for param in params %} + {%- if param.attrib["volatile"] == "true" %} + params::{{ param.attrib["name"] }}, + {%- endif -%} +{% endfor %} +}; + + } // namespace px4 diff --git a/src/platforms/px4_param.h b/src/platforms/px4_param.h index de0130afd26e..809aa82e469a 100644 --- a/src/platforms/px4_param.h +++ b/src/platforms/px4_param.h @@ -112,7 +112,7 @@ class Param { public: // static type-check - static_assert(px4::parameters[(int)p].type == PARAM_TYPE_FLOAT, "parameter type must be float"); + static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_FLOAT, "parameter type must be float"); Param() { @@ -145,7 +145,7 @@ class Param { public: // static type-check - static_assert(px4::parameters[(int)p].type == PARAM_TYPE_FLOAT, "parameter type must be float"); + static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_FLOAT, "parameter type must be float"); Param(float &external_val) : _val(external_val) @@ -178,7 +178,7 @@ class Param { public: // static type-check - static_assert(px4::parameters[(int)p].type == PARAM_TYPE_INT32, "parameter type must be int32_t"); + static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t"); Param() { @@ -211,7 +211,7 @@ class Param { public: // static type-check - static_assert(px4::parameters[(int)p].type == PARAM_TYPE_INT32, "parameter type must be int32_t"); + static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t"); Param(int32_t &external_val) : _val(external_val) @@ -244,7 +244,7 @@ class Param { public: // static type-check - static_assert(px4::parameters[(int)p].type == PARAM_TYPE_INT32, "parameter type must be int32_t"); + static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t"); Param() { From 559137d3445c4e2b4c4c39a6b3de2e2bad5b9db8 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 29 Sep 2019 17:37:20 -0400 Subject: [PATCH 6/6] parameters: only notify once when import finishes --- src/lib/parameters/parameters.cpp | 4 +++- src/lib/parameters/parameters_shmem.cpp | 4 +++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/lib/parameters/parameters.cpp b/src/lib/parameters/parameters.cpp index d3fcd213e72a..3e0ae322c553 100644 --- a/src/lib/parameters/parameters.cpp +++ b/src/lib/parameters/parameters.cpp @@ -1205,7 +1205,7 @@ param_import_callback(bson_decoder_t decoder, void *priv, bson_node_t node) goto out; } - if (param_set_internal(param, v, state->mark_saved, true)) { + if (param_set_internal(param, v, state->mark_saved, false)) { PX4_DEBUG("error setting value for '%s'", node->name); goto out; } @@ -1246,6 +1246,8 @@ param_import_internal(int fd, bool mark_saved) } while (result > 0); + param_notify_changes(); + return result; } diff --git a/src/lib/parameters/parameters_shmem.cpp b/src/lib/parameters/parameters_shmem.cpp index e4bf09cfc9b5..f0197bd7ea46 100644 --- a/src/lib/parameters/parameters_shmem.cpp +++ b/src/lib/parameters/parameters_shmem.cpp @@ -1346,7 +1346,7 @@ param_import_callback(bson_decoder_t decoder, void *priv, bson_node_t node) goto out; } - if (param_set_internal(param, v, state->mark_saved, true)) { + if (param_set_internal(param, v, state->mark_saved, false)) { PX4_DEBUG("error setting value for '%s'", node->name); goto out; } @@ -1387,6 +1387,8 @@ param_import_internal(int fd, bool mark_saved) } while (result > 0); + param_notify_changes(); + return result; }