mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Param: fixed flymaple build
This commit is contained in:
parent
2aa195e39b
commit
b54bb757df
@ -1077,11 +1077,13 @@ bool AP_Param::load_all(void)
|
||||
struct Param_header phdr;
|
||||
uint16_t ofs = sizeof(AP_Param::EEPROM_header);
|
||||
|
||||
#if HAL_OS_POSIX_IO == 1
|
||||
/*
|
||||
if the HAL specifies a defaults parameter file then override
|
||||
defaults using that file
|
||||
*/
|
||||
load_defaults_file(hal.util->get_custom_defaults_file());
|
||||
#endif
|
||||
|
||||
while (ofs < _storage.size()) {
|
||||
_storage.read_block(&phdr, ofs, sizeof(phdr));
|
||||
|
Loading…
Reference in New Issue
Block a user