mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: move parameter storage formatting up to AP_Vehicle
This commit is contained in:
parent
ea7788f49d
commit
5f24f33711
@ -811,22 +811,8 @@ const AP_Param::ConversionInfo conversion_table[] = {
|
||||
|
||||
void Rover::load_parameters(void)
|
||||
{
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
// erase all parameters
|
||||
hal.console->printf("Firmware change: erasing EEPROM...\n");
|
||||
StorageManager::erase();
|
||||
AP_Param::erase_all();
|
||||
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
|
||||
|
||||
// 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);
|
||||
|
||||
const 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::set_frame_type_flags(AP_PARAM_FRAME_ROVER);
|
||||
@ -839,7 +825,6 @@ void Rover::load_parameters(void)
|
||||
}
|
||||
|
||||
SRV_Channels::upgrade_parameters();
|
||||
hal.console->printf("load_all took %uus\n", unsigned(micros() - before));
|
||||
|
||||
// convert CH7_OPTION to RC7_OPTION for Rover-3.4 to 3.5 upgrade
|
||||
const AP_Param::ConversionInfo ch7_option_info = { Parameters::k_param_ch7_option, 0, AP_PARAM_INT8, "RC7_OPTION" };
|
||||
|
Loading…
Reference in New Issue
Block a user