mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: always call load_all
this ensures defaults file works on first start after erase
This commit is contained in:
parent
f201552f6d
commit
907a680a3b
@ -1145,11 +1145,11 @@ void Copter::load_parameters(void)
|
|||||||
// save the current format version
|
// save the current format version
|
||||||
g.format_version.set_and_save(Parameters::k_format_version);
|
g.format_version.set_and_save(Parameters::k_format_version);
|
||||||
cliSerial->println("done.");
|
cliSerial->println("done.");
|
||||||
} else {
|
|
||||||
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));
|
|
||||||
cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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));
|
||||||
|
cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user