AP_Param: fixed param class conversion code

param class conversion was unconditionally overwriting the parameter
from the old parameter. This meant if the user has set a value in an
old firmware they could not change it in a new firmware.

I hit this with ARSPD_TYPE. I had previously set this to 0 in a
previous use of the board, and found that it kept resetting to 0 on
the new firmware when I tried to enable airspeed
This commit is contained in:
Andrew Tridgell 2022-03-28 16:00:55 +11:00 committed by Randy Mackay
parent adabaca240
commit 3713769e57

View File

@ -1950,6 +1950,10 @@ void AP_Param::convert_class(uint16_t param_key, void *object_pointer,
}
AP_Param *ap2 = (AP_Param *)(group_info[i].offset + (uint8_t *)object_pointer);
if (ap2->configured_in_storage()) {
// user has already set a value, or previous conversion was done
continue;
}
memcpy(ap2, ap, sizeof(old_value));
// and save
ap2->save();