From 00356e0eb4c61053090a1348e5085c034cd23230 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 10 Feb 2024 15:38:50 +1100 Subject: [PATCH] ArduCopter: move parameter storage formatting up to AP_Vehicle --- ArduCopter/Parameters.cpp | 22 +--------------------- 1 file changed, 1 insertion(+), 21 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index d5d7174ff1..162492ffd8 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1338,25 +1338,8 @@ const AP_Param::ConversionInfo conversion_table[] = { void Copter::load_parameters(void) { - hal.util->set_soft_armed(false); + AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version); - if (!g.format_version.load() || - g.format_version != Parameters::k_format_version) { - - // erase all parameters - DEV_PRINTF("Firmware change: erasing EEPROM...\n"); - StorageManager::erase(); - AP_Param::erase_all(); - - // save the current format version - g.format_version.set_and_save(Parameters::k_format_version); - DEV_PRINTF("done.\n"); - } - g.format_version.set_default(Parameters::k_format_version); - - uint32_t before = micros(); - // Load all auto-loaded EEPROM variables - AP_Param::load_all(); AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); #if AP_LANDINGGEAR_ENABLED @@ -1409,11 +1392,8 @@ void Copter::load_parameters(void) AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); #endif - hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); - // setup AP_Param frame type flags AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER); - } // handle conversion of PID gains