mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
AP_Param: added support for embedded parameters
use a block of flash to hold embedded parameters that can be changed using apj_tool.py
This commit is contained in:
parent
0b4dcdde35
commit
4ac49483c8
@ -68,6 +68,18 @@ const AP_Param::Info *AP_Param::_var_info;
|
|||||||
struct AP_Param::param_override *AP_Param::param_overrides = nullptr;
|
struct AP_Param::param_override *AP_Param::param_overrides = nullptr;
|
||||||
uint16_t AP_Param::num_param_overrides = 0;
|
uint16_t AP_Param::num_param_overrides = 0;
|
||||||
|
|
||||||
|
/*
|
||||||
|
this holds default parameters in the normal NAME=value form for a
|
||||||
|
parameter file. It can be manipulated by apj_tool.py to change the
|
||||||
|
defaults on a binary without recompiling
|
||||||
|
*/
|
||||||
|
const AP_Param::param_defaults_struct AP_Param::param_defaults_data = {
|
||||||
|
"PARMDEF",
|
||||||
|
{ 0x55, 0x37, 0xf4, 0xa0, 0x38, 0x5d, 0x48, 0x5b },
|
||||||
|
AP_PARAM_MAX_EMBEDDED_PARAM,
|
||||||
|
0
|
||||||
|
};
|
||||||
|
|
||||||
// storage object
|
// storage object
|
||||||
StorageAccess AP_Param::_storage(StorageManager::StorageParam);
|
StorageAccess AP_Param::_storage(StorageManager::StorageParam);
|
||||||
|
|
||||||
@ -1287,6 +1299,11 @@ bool AP_Param::load_all(bool check_defaults_file)
|
|||||||
*/
|
*/
|
||||||
void AP_Param::reload_defaults_file(bool panic_on_error)
|
void AP_Param::reload_defaults_file(bool panic_on_error)
|
||||||
{
|
{
|
||||||
|
if (param_defaults_data.length != 0) {
|
||||||
|
load_embedded_param_defaults(panic_on_error);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
#if HAL_OS_POSIX_IO == 1
|
#if HAL_OS_POSIX_IO == 1
|
||||||
/*
|
/*
|
||||||
if the HAL specifies a defaults parameter file then override
|
if the HAL specifies a defaults parameter file then override
|
||||||
@ -1731,9 +1748,6 @@ void AP_Param::set_float(float value, enum ap_var_type var_type)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#if HAL_OS_POSIX_IO == 1
|
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
parse a parameter file line
|
parse a parameter file line
|
||||||
*/
|
*/
|
||||||
@ -1759,6 +1773,10 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#if HAL_OS_POSIX_IO == 1
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
// increments num_defaults for each default found in filename
|
// increments num_defaults for each default found in filename
|
||||||
bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults, bool panic_on_error)
|
bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults, bool panic_on_error)
|
||||||
{
|
{
|
||||||
@ -1886,6 +1904,129 @@ bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error)
|
|||||||
|
|
||||||
#endif // HAL_OS_POSIX_IO
|
#endif // HAL_OS_POSIX_IO
|
||||||
|
|
||||||
|
/*
|
||||||
|
count the number of embedded parameter defaults
|
||||||
|
*/
|
||||||
|
bool AP_Param::count_embedded_param_defaults(uint16_t &count, bool panic_on_error)
|
||||||
|
{
|
||||||
|
const volatile char *ptr = param_defaults_data.data;
|
||||||
|
uint16_t length = param_defaults_data.length;
|
||||||
|
count = 0;
|
||||||
|
|
||||||
|
while (length) {
|
||||||
|
char line[100];
|
||||||
|
char *pname;
|
||||||
|
float value;
|
||||||
|
uint16_t i;
|
||||||
|
uint16_t n = MIN(length, sizeof(line)-1);
|
||||||
|
for (i=0;i<n;i++) {
|
||||||
|
if (ptr[i] == '\n') {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (i == n) {
|
||||||
|
// no newline
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
memcpy(line, (void *)ptr, i);
|
||||||
|
line[i] = 0;
|
||||||
|
|
||||||
|
length -= i+1;
|
||||||
|
ptr += i+1;
|
||||||
|
|
||||||
|
if (line[0] == '#' || line[0] == 0) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!parse_param_line(line, &pname, value)) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
enum ap_var_type var_type;
|
||||||
|
if (!find(pname, &var_type)) {
|
||||||
|
if (panic_on_error) {
|
||||||
|
::printf("invalid param %s in defaults file\n", pname);
|
||||||
|
AP_HAL::panic("AP_Param: Invalid param in embedded defaults");
|
||||||
|
} else {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
count++;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
load a default set of parameters from a embedded parameter region
|
||||||
|
*/
|
||||||
|
void AP_Param::load_embedded_param_defaults(bool panic_on_error)
|
||||||
|
{
|
||||||
|
if (param_overrides != nullptr) {
|
||||||
|
free(param_overrides);
|
||||||
|
param_overrides = nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
num_param_overrides = 0;
|
||||||
|
uint16_t num_defaults = 0;
|
||||||
|
if (!count_embedded_param_defaults(num_defaults, panic_on_error)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
param_overrides = new param_override[num_defaults];
|
||||||
|
if (param_overrides == nullptr) {
|
||||||
|
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
const volatile char *ptr = param_defaults_data.data;
|
||||||
|
uint16_t length = param_defaults_data.length;
|
||||||
|
uint16_t idx = 0;
|
||||||
|
|
||||||
|
while (length) {
|
||||||
|
char line[100];
|
||||||
|
char *pname;
|
||||||
|
float value;
|
||||||
|
uint16_t i;
|
||||||
|
uint16_t n = MIN(length, sizeof(line)-1);
|
||||||
|
for (i=0;i<n;i++) {
|
||||||
|
if (ptr[i] == '\n') {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (i == n) {
|
||||||
|
// no newline
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
memcpy(line, (void*)ptr, i);
|
||||||
|
line[i] = 0;
|
||||||
|
|
||||||
|
length -= i+1;
|
||||||
|
ptr += i+1;
|
||||||
|
|
||||||
|
if (line[0] == '#' || line[0] == 0) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!parse_param_line(line, &pname, value)) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
enum ap_var_type var_type;
|
||||||
|
AP_Param *vp = find(pname, &var_type);
|
||||||
|
if (!vp) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
param_overrides[idx].object_ptr = vp;
|
||||||
|
param_overrides[idx].value = value;
|
||||||
|
idx++;
|
||||||
|
if (!vp->configured_in_storage()) {
|
||||||
|
vp->set_float(value, var_type);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
num_param_overrides = num_defaults;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
find a default value given a pointer to a default value in flash
|
find a default value given a pointer to a default value in flash
|
||||||
*/
|
*/
|
||||||
|
@ -31,6 +31,13 @@
|
|||||||
|
|
||||||
#define AP_MAX_NAME_SIZE 16
|
#define AP_MAX_NAME_SIZE 16
|
||||||
|
|
||||||
|
/*
|
||||||
|
maximum size of embedded parameter file
|
||||||
|
*/
|
||||||
|
#ifndef AP_PARAM_MAX_EMBEDDED_PARAM
|
||||||
|
#define AP_PARAM_MAX_EMBEDDED_PARAM 8192
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
flags for variables in var_info and group tables
|
flags for variables in var_info and group tables
|
||||||
*/
|
*/
|
||||||
@ -443,6 +450,19 @@ private:
|
|||||||
|
|
||||||
static uint16_t _frame_type_flags;
|
static uint16_t _frame_type_flags;
|
||||||
|
|
||||||
|
/*
|
||||||
|
structure for built-in defaults file that can be modified using apj_tool.py
|
||||||
|
*/
|
||||||
|
struct PACKED param_defaults_struct {
|
||||||
|
char magic_str[8];
|
||||||
|
uint8_t param_magic[8];
|
||||||
|
uint16_t max_length;
|
||||||
|
volatile uint16_t length;
|
||||||
|
volatile char data[AP_PARAM_MAX_EMBEDDED_PARAM];
|
||||||
|
};
|
||||||
|
static const param_defaults_struct param_defaults_data;
|
||||||
|
|
||||||
|
|
||||||
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size,
|
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size,
|
||||||
uint8_t max_bits, uint8_t prefix_length);
|
uint8_t max_bits, uint8_t prefix_length);
|
||||||
static bool duplicate_key(uint16_t vindex, uint16_t key);
|
static bool duplicate_key(uint16_t vindex, uint16_t key);
|
||||||
@ -521,16 +541,23 @@ private:
|
|||||||
// find a default value given a pointer to a default value in flash
|
// find a default value given a pointer to a default value in flash
|
||||||
static float get_default_value(const AP_Param *object_ptr, const float *def_value_ptr);
|
static float get_default_value(const AP_Param *object_ptr, const float *def_value_ptr);
|
||||||
|
|
||||||
|
static bool parse_param_line(char *line, char **vname, float &value);
|
||||||
|
|
||||||
#if HAL_OS_POSIX_IO == 1
|
#if HAL_OS_POSIX_IO == 1
|
||||||
/*
|
/*
|
||||||
load a parameter defaults file. This happens as part of load_all()
|
load a parameter defaults file. This happens as part of load_all()
|
||||||
*/
|
*/
|
||||||
static bool parse_param_line(char *line, char **vname, float &value);
|
|
||||||
static bool count_defaults_in_file(const char *filename, uint16_t &num_defaults, bool panic_on_error);
|
static bool count_defaults_in_file(const char *filename, uint16_t &num_defaults, bool panic_on_error);
|
||||||
static bool read_param_defaults_file(const char *filename);
|
static bool read_param_defaults_file(const char *filename);
|
||||||
static bool load_defaults_file(const char *filename, bool panic_on_error);
|
static bool load_defaults_file(const char *filename, bool panic_on_error);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
load defaults from embedded parameters
|
||||||
|
*/
|
||||||
|
static bool count_embedded_param_defaults(uint16_t &count, bool panic_on_error);
|
||||||
|
static void load_embedded_param_defaults(bool panic_on_error);
|
||||||
|
|
||||||
// send a parameter to all GCS instances
|
// send a parameter to all GCS instances
|
||||||
void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const;
|
void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user