AP_Param: add support for converting between old and new parameters
this allows for a conversion table between old parameters and new parameters, making firmware upgrades with moved parameters much easier for users
This commit is contained in:
parent
e48b8c7b4a
commit
ad2f6e1217
@ -608,6 +608,17 @@ AP_Param::find(const char *name, enum ap_var_type *ptype)
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// Find a variable by name.
|
||||
//
|
||||
AP_Param *
|
||||
AP_Param::find_P(const prog_char_t *name, enum ap_var_type *ptype)
|
||||
{
|
||||
char param_name[AP_MAX_NAME_SIZE+1];
|
||||
strncpy_P(param_name, name, AP_MAX_NAME_SIZE);
|
||||
param_name[AP_MAX_NAME_SIZE] = 0;
|
||||
return find(param_name, ptype);
|
||||
}
|
||||
|
||||
// Find a variable by index. Note that this is quite slow.
|
||||
//
|
||||
AP_Param *
|
||||
@ -705,6 +716,7 @@ bool AP_Param::save(void)
|
||||
|
||||
if (ofs+type_size((enum ap_var_type)phdr.type)+2*sizeof(phdr) >= _eeprom_size) {
|
||||
// we are out of room for saving variables
|
||||
hal.console->println_P(PSTR("EEPROM full"));
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -770,20 +782,20 @@ bool AP_Param::load(void)
|
||||
}
|
||||
|
||||
// set a AP_Param variable to a specified value
|
||||
void AP_Param::set_value(enum ap_var_type type, void *ptr, float def_value)
|
||||
void AP_Param::set_value(enum ap_var_type type, void *ptr, float value)
|
||||
{
|
||||
switch (type) {
|
||||
case AP_PARAM_INT8:
|
||||
((AP_Int8 *)ptr)->set(def_value);
|
||||
((AP_Int8 *)ptr)->set(value);
|
||||
break;
|
||||
case AP_PARAM_INT16:
|
||||
((AP_Int16 *)ptr)->set(def_value);
|
||||
((AP_Int16 *)ptr)->set(value);
|
||||
break;
|
||||
case AP_PARAM_INT32:
|
||||
((AP_Int32 *)ptr)->set(def_value);
|
||||
((AP_Int32 *)ptr)->set(value);
|
||||
break;
|
||||
case AP_PARAM_FLOAT:
|
||||
((AP_Float *)ptr)->set(def_value);
|
||||
((AP_Float *)ptr)->set(value);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
@ -1054,3 +1066,72 @@ void AP_Param::show_all(AP_HAL::BetterStream *port)
|
||||
}
|
||||
}
|
||||
|
||||
// convert one old vehicle parameter to new object parameter
|
||||
void AP_Param::convert_old_parameter(const struct ConversionInfo *info)
|
||||
{
|
||||
|
||||
// find the old value in EEPROM.
|
||||
uint16_t pofs;
|
||||
AP_Param::Param_header header;
|
||||
header.type = PGM_UINT8(&info->type);
|
||||
header.key = PGM_UINT8(&info->old_key);
|
||||
header.group_element = PGM_UINT8(&info->old_group_element);
|
||||
if (!scan(&header, &pofs)) {
|
||||
// the old parameter isn't saved in the EEPROM. It was
|
||||
// probably still set to the default value, which isn't stored
|
||||
// no need to convert
|
||||
return;
|
||||
}
|
||||
|
||||
// load the old value from EEPROM
|
||||
uint8_t old_value[type_size((enum ap_var_type)header.type)];
|
||||
hal.storage->read_block(old_value, pofs+sizeof(header), sizeof(old_value));
|
||||
const AP_Param *ap = (const AP_Param *)&old_value[0];
|
||||
|
||||
// find the new variable in the variable structures
|
||||
enum ap_var_type ptype;
|
||||
AP_Param *ap2;
|
||||
ap2 = find_P((const prog_char_t *)&info->new_name[0], &ptype);
|
||||
if (ap2 == NULL) {
|
||||
hal.console->printf_P(PSTR("Unknown conversion '%S'\n"), info->new_name);
|
||||
return;
|
||||
}
|
||||
|
||||
// see if we can load it from EEPROM
|
||||
if (ap2->load()) {
|
||||
// the new parameter already has a value set by the user, or
|
||||
// has already been converted
|
||||
return;
|
||||
}
|
||||
|
||||
// see if they are the same type
|
||||
if (ptype == header.type) {
|
||||
// copy the value over only if the new parameter does not already
|
||||
// have the old value (via a default).
|
||||
if (memcmp(ap2, ap, sizeof(old_value)) != 0) {
|
||||
memcpy(ap2, ap, sizeof(old_value));
|
||||
// and save
|
||||
ap2->save();
|
||||
}
|
||||
} else if (ptype <= AP_PARAM_FLOAT && header.type <= AP_PARAM_FLOAT) {
|
||||
// perform scalar->scalar conversion
|
||||
float v = ap->cast_to_float((enum ap_var_type)header.type);
|
||||
if (v != ap2->cast_to_float(ptype)) {
|
||||
// the value needs to change
|
||||
set_value(ptype, ap2, v);
|
||||
ap2->save();
|
||||
}
|
||||
} else {
|
||||
// can't do vector<->scalar conversion, or different vector types
|
||||
hal.console->printf_P(PSTR("Bad conversion type '%S'\n"), info->new_name);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// convert old vehicle parameters to new object parametersv
|
||||
void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size)
|
||||
{
|
||||
for (uint8_t i=0; i<table_size; i++) {
|
||||
convert_old_parameter(&conversion_table[i]);
|
||||
}
|
||||
}
|
||||
|
@ -83,6 +83,12 @@ public:
|
||||
const float def_value;
|
||||
};
|
||||
};
|
||||
struct ConversionInfo {
|
||||
uint8_t old_key; // k_param_*
|
||||
uint8_t old_group_element; // index in old object
|
||||
enum ap_var_type type; // AP_PARAM_*
|
||||
const char new_name[AP_MAX_NAME_SIZE+1];
|
||||
};
|
||||
|
||||
// called once at startup to setup the _var_info[] table. This
|
||||
// will also check the EEPROM header and re-initialise it if the
|
||||
@ -137,6 +143,7 @@ public:
|
||||
/// it does not exist.
|
||||
///
|
||||
static AP_Param * find(const char *name, enum ap_var_type *ptype);
|
||||
static AP_Param * find_P(const prog_char_t *name, enum ap_var_type *ptype);
|
||||
|
||||
/// Find a variable by index.
|
||||
///
|
||||
@ -187,6 +194,9 @@ public:
|
||||
// does not recurse into the sub-objects
|
||||
static void setup_sketch_defaults(void);
|
||||
|
||||
// convert old vehicle parameters to new object parameters
|
||||
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size);
|
||||
|
||||
/// Erase all variables in EEPROM.
|
||||
///
|
||||
static void erase_all(void);
|
||||
@ -300,7 +310,7 @@ private:
|
||||
const struct GroupInfo *group_info,
|
||||
enum ap_var_type *ptype);
|
||||
static void write_sentinal(uint16_t ofs);
|
||||
bool scan(
|
||||
static bool scan(
|
||||
const struct Param_header *phdr,
|
||||
uint16_t *pofs);
|
||||
static uint8_t type_size(enum ap_var_type type);
|
||||
@ -325,6 +335,9 @@ private:
|
||||
static const uint8_t k_EEPROM_magic0 = 0x50;
|
||||
static const uint8_t k_EEPROM_magic1 = 0x41; ///< "AP"
|
||||
static const uint8_t k_EEPROM_revision = 6; ///< current format revision
|
||||
|
||||
// convert old vehicle parameters to new object parameters
|
||||
static void convert_old_parameter(const struct ConversionInfo *info);
|
||||
};
|
||||
|
||||
/// Template class for scalar variables.
|
||||
|
Loading…
Reference in New Issue
Block a user