mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Copter: bug fix to convert old batt params to BATT_ lib
This commit is contained in:
parent
6c0cb5f84d
commit
4036f50fc2
@ -1091,7 +1091,7 @@ static void load_parameters(void)
|
|||||||
uint32_t before = micros();
|
uint32_t before = micros();
|
||||||
// Load all auto-loaded EEPROM variables
|
// Load all auto-loaded EEPROM variables
|
||||||
AP_Param::load_all();
|
AP_Param::load_all();
|
||||||
|
AP_Param::convert_old_parameters(&conversion_table[0], sizeof(conversion_table)/sizeof(conversion_table[0]));
|
||||||
cliSerial->printf_P(PSTR("load_all took %luus\n"), micros() - before);
|
cliSerial->printf_P(PSTR("load_all took %luus\n"), micros() - before);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user