mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_Param: added CONVERT_FLAG_REVERSE and CONVERT_FLAG_FORCE
This commit is contained in:
parent
a3220944d8
commit
05e9462a9c
@ -1592,7 +1592,7 @@ bool AP_Param::find_old_parameter(const struct ConversionInfo *info, AP_Param *v
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wformat"
|
||||
// convert one old vehicle parameter to new object parameter
|
||||
void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float scaler)
|
||||
void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags)
|
||||
{
|
||||
uint8_t old_value[type_size(info->type)];
|
||||
AP_Param *ap = (AP_Param *)&old_value[0];
|
||||
@ -1614,14 +1614,14 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float sc
|
||||
}
|
||||
|
||||
// see if we can load it from EEPROM
|
||||
if (ap2->load()) {
|
||||
if (!(flags & CONVERT_FLAG_FORCE) && ap2->configured_in_storage()) {
|
||||
// the new parameter already has a value set by the user, or
|
||||
// has already been converted
|
||||
return;
|
||||
}
|
||||
|
||||
// see if they are the same type and no scaling applied
|
||||
if (ptype == info->type && is_equal(scaler, 1.0f)) {
|
||||
if (ptype == info->type && is_equal(scaler, 1.0f) && flags == 0) {
|
||||
// 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) {
|
||||
@ -1632,6 +1632,10 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float sc
|
||||
} else if (ptype <= AP_PARAM_FLOAT && info->type <= AP_PARAM_FLOAT) {
|
||||
// perform scalar->scalar conversion
|
||||
float v = ap->cast_to_float(info->type);
|
||||
if (flags & CONVERT_FLAG_REVERSE) {
|
||||
// convert a _REV parameter to a _REVERSED parameter
|
||||
v = is_equal(v, -1.0f)?1:0;
|
||||
}
|
||||
if (!is_equal(v,ap2->cast_to_float(ptype))) {
|
||||
// the value needs to change
|
||||
set_value(ptype, ap2, v * scaler);
|
||||
@ -1646,10 +1650,10 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float sc
|
||||
|
||||
|
||||
// convert old vehicle parameters to new object parametersv
|
||||
void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size)
|
||||
void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags)
|
||||
{
|
||||
for (uint8_t i=0; i<table_size; i++) {
|
||||
convert_old_parameter(&conversion_table[i], 1.0f);
|
||||
convert_old_parameter(&conversion_table[i], 1.0f, flags);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -296,10 +296,14 @@ public:
|
||||
static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value);
|
||||
|
||||
// convert old vehicle parameters to new object parameters
|
||||
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size);
|
||||
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0);
|
||||
|
||||
// convert a single parameter with scaling
|
||||
static void convert_old_parameter(const struct ConversionInfo *info, float scaler);
|
||||
enum {
|
||||
CONVERT_FLAG_REVERSE=1, // handle _REV -> _REVERSED conversion
|
||||
CONVERT_FLAG_FORCE=2 // store new value even if configured in eeprom already
|
||||
};
|
||||
static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0);
|
||||
|
||||
/// Erase all variables in EEPROM.
|
||||
///
|
||||
|
Loading…
Reference in New Issue
Block a user