Parameters: Add support for volatile parameters

Volatile parameters are ones that do not represent a fundamental configuration change but rather than incrementally changing settings. These include logged flight hours or sensor offsets. Marking them as volatile avoids these parameters forcing time-consuming telemetry updates.
This commit is contained in:
Lorenz Meier 2018-01-07 17:04:15 +01:00
parent f284385c3f
commit 7695f79239
3 changed files with 33 additions and 18 deletions

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2018 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
@ -489,6 +489,12 @@ param_name(param_t param)
return handle_in_range(param) ? param_info_base[param].name : NULL;
}
bool
param_is_volatile(param_t param)
{
return handle_in_range(param) ? param_info_base[param].volatile_param : false;
}
bool
param_value_is_default(param_t param)
{
@ -510,8 +516,9 @@ param_value_unsaved(param_t param)
return ret;
}
enum param_type_e
param_type(param_t param) {
param_type_t
param_type(param_t param)
{
return handle_in_range(param) ? param_info_base[param].type : PARAM_TYPE_UNKNOWN;
}
@ -680,7 +687,6 @@ param_control_autosave(bool enable)
#endif /* PARAM_NO_AUTOSAVE */
}
static int
param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_changes)
{
@ -1357,7 +1363,7 @@ uint32_t param_hash_check(void)
/* compute the CRC32 over all string param names and 4 byte values */
for (param_t param = 0; handle_in_range(param); param++) {
if (!param_used(param)) {
if (!param_used(param) && param_is_volatile(param)) {
continue;
}

View File

@ -50,24 +50,20 @@
#include <sys/types.h>
/** Maximum size of the parameter backing file */
#define PARAM_FILE_MAXSIZE 4096
#define PARAM_FILE_MAXSIZE 4096
__BEGIN_DECLS
/**
* Parameter types.
*/
typedef enum param_type_e {
/* globally-known parameter types */
PARAM_TYPE_INT32 = 0,
PARAM_TYPE_FLOAT,
#define PARAM_TYPE_INT32 0
#define PARAM_TYPE_FLOAT 1
#define PARAM_TYPE_STRUCT 100
#define PARAM_TYPE_STRUCT_MAX (16384 + PARAM_TYPE_STRUCT)
#define PARAM_TYPE_UNKNOWN (0xffff)
/* structure parameters; size is encoded in the type value */
PARAM_TYPE_STRUCT = 100,
PARAM_TYPE_STRUCT_MAX = 16384 + PARAM_TYPE_STRUCT,
PARAM_TYPE_UNKNOWN = 0xffff
} param_type_t;
typedef uint16_t param_type_t;
#ifdef __PX4_NUTTX // on NuttX use 16 bits to save RAM
@ -198,6 +194,14 @@ __EXPORT int param_get_used_index(param_t param);
*/
__EXPORT const char *param_name(param_t param);
/**
* Obtain the volatile state of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return true if the parameter is volatile
*/
__EXPORT bool param_is_volatile(param_t param);
/**
* Test whether a parameter's value has changed from the default.
*
@ -262,7 +266,7 @@ __EXPORT int param_set_no_notification(param_t param, const void *val);
* Notify the system about parameter changes. Can be used for example after several calls to
* param_set_no_notification() to avoid unnecessary system notifications.
*/
__EXPORT void param_notify_changes(void);
__EXPORT void param_notify_changes(void);
/**
* Reset a parameter to its default value.
@ -282,7 +286,6 @@ __EXPORT int param_reset(param_t param);
*/
__EXPORT void param_reset_all(void);
/**
* Reset all parameters to their default values except for excluded parameters.
*
@ -446,6 +449,7 @@ struct param_info_s {
;
#endif
param_type_t type;
uint16_t volatile_param: 1;
union param_value_u val;
};

View File

@ -16,6 +16,11 @@ struct px4_parameters_t px4_parameters = {
{
"{{ 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" %}