mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-10 14:51:15 +08:00
parameters: merge generated files ito single static constexpr header
- store parameter type and if volatile separately (saves kilobytes of flash)
- use Bitset for tracking active and changed parameters
- use atomic for autosave_enabled flag
- compile at ${MAX_CUSTOM_OPT_LEVEL} (-O2 on non flash constrained boards)
This commit is contained in:
@@ -101,9 +101,6 @@ msg/tmp/
|
||||
msg/topics_sources/
|
||||
platforms/posix/apps.cpp
|
||||
platforms/posix/apps.h
|
||||
src/lib/parameters/px4_parameters.c
|
||||
src/lib/parameters/px4_parameters.h
|
||||
src/lib/parameters/px4_parameters_public.h
|
||||
src/lib/version/build_git_version.h
|
||||
src/modules/simulator/simulator_config.h
|
||||
src/systemcmds/topic_listener/listener_generated.cpp
|
||||
|
||||
@@ -1,3 +1,5 @@
|
||||
# workaround for syslink parameter PARAM_DEFINE_INT32(SLNK_RADIO_ADDR2, 3890735079); // 0xE7E7E7E7
|
||||
add_compile_options(-Wno-narrowing)
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
|
||||
@@ -1,3 +1,5 @@
|
||||
# workaround for syslink parameter PARAM_DEFINE_INT32(SLNK_RADIO_ADDR2, 3890735079); // 0xE7E7E7E7
|
||||
add_compile_options(-Wno-narrowing)
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
|
||||
#include "param_macros.h"
|
||||
|
||||
#include <parameters/px4_parameters_public.h>
|
||||
#include <parameters/px4_parameters.hpp>
|
||||
|
||||
/**
|
||||
* get the parameter handle from a parameter enum
|
||||
@@ -112,7 +112,7 @@ class Param<float, p>
|
||||
{
|
||||
public:
|
||||
// static type-check
|
||||
static_assert(px4::param_types_array[(int)p] == PARAM_TYPE_FLOAT, "parameter type must be float");
|
||||
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_FLOAT, "parameter type must be float");
|
||||
|
||||
Param()
|
||||
{
|
||||
@@ -151,7 +151,7 @@ class Param<float &, p>
|
||||
{
|
||||
public:
|
||||
// static type-check
|
||||
static_assert(px4::param_types_array[(int)p] == 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)
|
||||
@@ -190,7 +190,7 @@ class Param<int32_t, p>
|
||||
{
|
||||
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_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t");
|
||||
|
||||
Param()
|
||||
{
|
||||
@@ -229,7 +229,7 @@ class Param<int32_t &, p>
|
||||
{
|
||||
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_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t");
|
||||
|
||||
Param(int32_t &external_val)
|
||||
: _val(external_val)
|
||||
@@ -268,7 +268,7 @@ class Param<bool, p>
|
||||
{
|
||||
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_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t");
|
||||
|
||||
Param()
|
||||
{
|
||||
|
||||
@@ -31,6 +31,8 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_compile_options(${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
add_subdirectory(tinybson)
|
||||
|
||||
if (NOT PARAM_DEFAULT_OVERRIDES)
|
||||
@@ -113,16 +115,14 @@ add_custom_command(OUTPUT ${parameters_xml} ${parameters_json} ${parameters_json
|
||||
)
|
||||
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
|
||||
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.c.jinja
|
||||
templates/px4_parameters.h.jinja
|
||||
templates/px4_parameters_public.h.jinja
|
||||
templates/px4_parameters.hpp.jinja
|
||||
)
|
||||
|
||||
set(SRCS)
|
||||
@@ -147,10 +147,8 @@ endif()
|
||||
if (NOT "${PX4_BOARD}" MATCHES "px4_io")
|
||||
add_library(parameters
|
||||
${SRCS}
|
||||
px4_parameters.c
|
||||
px4_parameters.h
|
||||
px4_parameters_public.h
|
||||
)
|
||||
px4_parameters.hpp
|
||||
)
|
||||
|
||||
if ("${CONFIG_SHMEM}" STREQUAL "1")
|
||||
target_link_libraries(parameters PRIVATE px4_layer)
|
||||
|
||||
@@ -435,25 +435,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;
|
||||
};
|
||||
|
||||
|
||||
+126
-202
File diff suppressed because it is too large
Load Diff
@@ -50,9 +50,7 @@ def generate(xml_file, dest='.'):
|
||||
os.path.mkdir(dest)
|
||||
|
||||
template_files = [
|
||||
'px4_parameters.h.jinja',
|
||||
'px4_parameters_public.h.jinja',
|
||||
'px4_parameters.c.jinja',
|
||||
'px4_parameters.hpp.jinja',
|
||||
]
|
||||
for template_file in template_files:
|
||||
template = env.get_template(template_file)
|
||||
|
||||
@@ -1,35 +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
|
||||
|
||||
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 : #}
|
||||
@@ -1,21 +0,0 @@
|
||||
{# jinja syntax: http://jinja.pocoo.org/docs/2.9/templates/ #}
|
||||
#include <stdint.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
// 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 : #}
|
||||
@@ -0,0 +1,49 @@
|
||||
{# jinja syntax: http://jinja.pocoo.org/docs/2.9/templates/ #}
|
||||
|
||||
#include <stdint.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
// DO NOT EDIT
|
||||
// This file is autogenerated from parameters.xml
|
||||
|
||||
namespace px4 { {# wrap the enum in a namespace, otherwise we get shadowing errors for MAV_TYPE #}
|
||||
|
||||
/// Enum with all parameters
|
||||
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 %}
|
||||
{{ param.attrib["name"] }},
|
||||
{%- endfor %}
|
||||
|
||||
};
|
||||
|
||||
static constexpr param_info_s parameters[] = {
|
||||
{% for param in params %}
|
||||
{
|
||||
"{{ param.attrib["name"] }}",
|
||||
{%- if param.attrib["type"] == "FLOAT" %}
|
||||
.val = {{ "{" }} .f = {{ param.attrib["default"] }} {{ "}" }},
|
||||
{%- elif param.attrib["type"] == "INT32" %}
|
||||
.val = {{ "{" }} .i = {{ param.attrib["default"] }}{{ "}" }},
|
||||
{%- endif %}
|
||||
},
|
||||
{% 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
|
||||
@@ -1,37 +0,0 @@
|
||||
{# jinja syntax: http://jinja.pocoo.org/docs/2.9/templates/ #}
|
||||
#include <stdint.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
// 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 */
|
||||
|
||||
Reference in New Issue
Block a user