mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: always call load_all
this ensures defaults file works on first start after erase
This commit is contained in:
parent
f17ec284f7
commit
be456fc33d
@ -582,13 +582,13 @@ void Rover::load_parameters(void)
|
||||
// save the current format version
|
||||
g.format_version.set_and_save(Parameters::k_format_version);
|
||||
cliSerial->println("done.");
|
||||
} else {
|
||||
unsigned long before = micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
}
|
||||
|
||||
cliSerial->printf("load_all took %luus\n", micros() - before);
|
||||
}
|
||||
unsigned long before = micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
|
||||
cliSerial->printf("load_all took %luus\n", micros() - before);
|
||||
|
||||
// set a more reasonable default NAVL1_PERIOD for rovers
|
||||
L1_controller.set_default_period(8);
|
||||
|
Loading…
Reference in New Issue
Block a user