Cleanup EEPROM reset and validation methods so that it is obvious what
the code is doing. There are now no EEPROM read/write/reset/verify methods that take any arguments which removes magic boolean variables from method signatures. This also removes duplicate code in the cliDefaults and cliSave commands which results in smaller code also also due to the deduplication of a reboot message.
This commit is contained in:
parent
a012cb1c82
commit
bd95c38ff0
31
src/config.c
31
src/config.c
|
@ -45,7 +45,7 @@ config_t cfg; // profile config struct
|
||||||
static const uint8_t EEPROM_CONF_VERSION = 64;
|
static const uint8_t EEPROM_CONF_VERSION = 64;
|
||||||
static void resetConf(void);
|
static void resetConf(void);
|
||||||
|
|
||||||
static uint8_t validEEPROM(void)
|
static bool isEEPROMContentValid(void)
|
||||||
{
|
{
|
||||||
const master_t *temp = (const master_t *)FLASH_WRITE_ADDR;
|
const master_t *temp = (const master_t *)FLASH_WRITE_ADDR;
|
||||||
const uint8_t *p;
|
const uint8_t *p;
|
||||||
|
@ -53,11 +53,11 @@ static uint8_t validEEPROM(void)
|
||||||
|
|
||||||
// check version number
|
// check version number
|
||||||
if (EEPROM_CONF_VERSION != temp->version)
|
if (EEPROM_CONF_VERSION != temp->version)
|
||||||
return 0;
|
return false;
|
||||||
|
|
||||||
// check size and magic numbers
|
// check size and magic numbers
|
||||||
if (temp->size != sizeof(master_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF)
|
if (temp->size != sizeof(master_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF)
|
||||||
return 0;
|
return false;
|
||||||
|
|
||||||
// verify integrity of temporary copy
|
// verify integrity of temporary copy
|
||||||
for (p = (const uint8_t *)temp; p < ((const uint8_t *)temp + sizeof(master_t)); p++)
|
for (p = (const uint8_t *)temp; p < ((const uint8_t *)temp + sizeof(master_t)); p++)
|
||||||
|
@ -65,16 +65,16 @@ static uint8_t validEEPROM(void)
|
||||||
|
|
||||||
// checksum failed
|
// checksum failed
|
||||||
if (chk != 0)
|
if (chk != 0)
|
||||||
return 0;
|
return false;
|
||||||
|
|
||||||
// looks good, let's roll!
|
// looks good, let's roll!
|
||||||
return 1;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void readEEPROM(void)
|
void readEEPROM(void)
|
||||||
{
|
{
|
||||||
// Sanity check
|
// Sanity check
|
||||||
if (!validEEPROM())
|
if (!isEEPROMContentValid())
|
||||||
failureMode(10);
|
failureMode(10);
|
||||||
|
|
||||||
// Read flash
|
// Read flash
|
||||||
|
@ -146,19 +146,24 @@ retry:
|
||||||
FLASH_Lock();
|
FLASH_Lock();
|
||||||
|
|
||||||
// Flash write failed - just die now
|
// Flash write failed - just die now
|
||||||
if (tries == 3 || !validEEPROM()) {
|
if (tries == 3 || !isEEPROMContentValid()) {
|
||||||
failureMode(10);
|
failureMode(10);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void checkFirstTime(bool reset)
|
void ensureEEPROMContainsValidData(void)
|
||||||
{
|
{
|
||||||
// check the EEPROM integrity before resetting values
|
if (isEEPROMContentValid()) {
|
||||||
if (!validEEPROM() || reset) {
|
return;
|
||||||
resetConf();
|
|
||||||
writeEEPROM();
|
|
||||||
readEEPROM();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
resetEEPROM();
|
||||||
|
}
|
||||||
|
|
||||||
|
void resetEEPROM(void)
|
||||||
|
{
|
||||||
|
resetConf();
|
||||||
|
writeEEPROM();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Default settings
|
// Default settings
|
||||||
|
|
|
@ -40,7 +40,8 @@ uint32_t featureMask(void);
|
||||||
|
|
||||||
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
|
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
|
||||||
|
|
||||||
|
void resetEEPROM(void);
|
||||||
void readEEPROM(void);
|
void readEEPROM(void);
|
||||||
void readEEPROMAndNotify(void);
|
void readEEPROMAndNotify(void);
|
||||||
void writeEEPROM();
|
void writeEEPROM();
|
||||||
void checkFirstTime(bool reset);
|
void ensureEEPROMContainsValidData(void);
|
||||||
|
|
|
@ -38,7 +38,7 @@ int main(void)
|
||||||
systemInit();
|
systemInit();
|
||||||
initPrintfSupport();
|
initPrintfSupport();
|
||||||
|
|
||||||
checkFirstTime(false);
|
ensureEEPROMContainsValidData();
|
||||||
readEEPROM();
|
readEEPROM();
|
||||||
|
|
||||||
// configure power ADC
|
// configure power ADC
|
||||||
|
|
|
@ -550,15 +550,6 @@ static void cliCMix(char *cmdline)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cliDefaults(char *cmdline)
|
|
||||||
{
|
|
||||||
cliPrint("Resetting to defaults...\r\n");
|
|
||||||
checkFirstTime(true);
|
|
||||||
cliPrint("Rebooting...");
|
|
||||||
delay(10);
|
|
||||||
systemReset(false);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void cliDump(char *cmdline)
|
static void cliDump(char *cmdline)
|
||||||
{
|
{
|
||||||
int i;
|
int i;
|
||||||
|
@ -842,14 +833,25 @@ static void cliProfile(char *cmdline)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void cliReboot(void) {
|
||||||
|
cliPrint("\r\nRebooting...");
|
||||||
|
delay(10);
|
||||||
|
systemReset(false);
|
||||||
|
}
|
||||||
|
|
||||||
static void cliSave(char *cmdline)
|
static void cliSave(char *cmdline)
|
||||||
{
|
{
|
||||||
cliPrint("Saving...");
|
cliPrint("Saving...");
|
||||||
copyCurrentProfileToProfileSlot(mcfg.current_profile);
|
copyCurrentProfileToProfileSlot(mcfg.current_profile);
|
||||||
writeEEPROM();
|
writeEEPROM();
|
||||||
cliPrint("\r\nRebooting...");
|
cliReboot();
|
||||||
delay(10);
|
}
|
||||||
systemReset(false);
|
|
||||||
|
static void cliDefaults(char *cmdline)
|
||||||
|
{
|
||||||
|
cliPrint("Resetting to defaults...");
|
||||||
|
resetEEPROM();
|
||||||
|
cliReboot();
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cliPrint(const char *str)
|
static void cliPrint(const char *str)
|
||||||
|
|
|
@ -601,8 +601,10 @@ static void evaluateCommand(void)
|
||||||
headSerialReply(0);
|
headSerialReply(0);
|
||||||
break;
|
break;
|
||||||
case MSP_RESET_CONF:
|
case MSP_RESET_CONF:
|
||||||
if (!f.ARMED)
|
if (!f.ARMED) {
|
||||||
checkFirstTime(true);
|
resetEEPROM();
|
||||||
|
readEEPROM();
|
||||||
|
}
|
||||||
headSerialReply(0);
|
headSerialReply(0);
|
||||||
break;
|
break;
|
||||||
case MSP_ACC_CALIBRATION:
|
case MSP_ACC_CALIBRATION:
|
||||||
|
|
Loading…
Reference in New Issue