From 0879b497a44a5af8f335a45e60fdfb85aba42cc2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 28 Mar 2022 16:00:55 +1100 Subject: [PATCH] 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 --- libraries/AP_Param/AP_Param.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index ab351c50c8..f1eecc4fdf 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1951,6 +1951,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();