AP_Param: Ignore FORMAT_VERSION param when loading SITL defaults

This fixes a bug where having FORMAT_VERSION in the SITL defaults file
can result in an invalid SITL EEPROM file. See issue #15579 for details.
This commit is contained in:
Nick Exton 2020-10-16 09:54:55 +11:00 committed by Peter Barker
parent 258083a6f2
commit 01155cc5d4

View File

@ -2005,6 +2005,16 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value, bool &re
if (strlen(pname) > AP_MAX_NAME_SIZE) {
return false;
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// Workaround to prevent FORMAT_VERSION in param file resulting in invalid
// EEPROM. For details, see: https://github.com/ArduPilot/ardupilot/issues/15579
if (strcmp(pname, "FORMAT_VERSION") == 0) {
::printf("Warning: Ignoring FORMAT_VERSION in param file\n");
return false;
}
#endif
const char *value_s = strtok_r(nullptr, ", =\t\r\n", &saveptr);
if (value_s == nullptr) {
return false;