ArduPlane: move parameter storage formatting up to AP_Vehicle
This commit is contained in:
parent
00356e0eb4
commit
739a4a97da
@ -1344,23 +1344,8 @@ static const RCConversionInfo rc_option_conversion[] = {
|
|||||||
|
|
||||||
void Plane::load_parameters(void)
|
void Plane::load_parameters(void)
|
||||||
{
|
{
|
||||||
if (!g.format_version.load() ||
|
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
|
||||||
g.format_version != Parameters::k_format_version) {
|
|
||||||
|
|
||||||
// erase all parameters
|
|
||||||
hal.console->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);
|
|
||||||
hal.console->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));
|
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
|
||||||
|
|
||||||
// setup defaults in SRV_Channels
|
// setup defaults in SRV_Channels
|
||||||
@ -1577,6 +1562,4 @@ void Plane::load_parameters(void)
|
|||||||
#if HAL_LOGGING_ENABLED
|
#if HAL_LOGGING_ENABLED
|
||||||
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
|
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user