From 01155cc5d48ae4daaf7155e4a897d5b434a8335f Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Fri, 16 Oct 2020 09:54:55 +1100 Subject: [PATCH] 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. --- libraries/AP_Param/AP_Param.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 9806e824ee..9a44edb0fc 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -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;