1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Decouple reading EEPROM from writing EEPROM. Now writeEEPROM() does

only what it's name implies and it's method takes no arguments.  This
avoids the 0/1 magic numbers which was a flag to decide whether the user
should be notified after the EEPROM has been read (!).

Introduced a method called readEEPROMAndNotify() which is used in all
cases where writeEEPROM(1) was previously called.

Additionally this avoid re-reading the profile when the reboot command
is issued which speeds up reboots.

Finally this avoid needless comments because the code tells you now what
it is going to do.
This commit is contained in:
Dominic Clifton 2014-04-21 01:18:15 +01:00
parent 3daaf66b14
commit a012cb1c82
7 changed files with 30 additions and 19 deletions

View file

@ -90,7 +90,13 @@ void readEEPROM(void)
setPIDController(cfg.pidController);
gpsSetPIDs();
useFailsafeConfig(&cfg.failsafeConfig);
}
void readEEPROMAndNotify(void)
{
// re-read written data
readEEPROM();
blinkLedAndSoundBeeper(15, 20, 1);
}
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex)
@ -99,7 +105,7 @@ void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex)
memcpy(&mcfg.profile[profileSlotIndex], &cfg, sizeof(config_t));
}
void writeEEPROM(uint8_t b)
void writeEEPROM(void)
{
FLASH_Status status;
uint32_t i;
@ -143,11 +149,6 @@ retry:
if (tries == 3 || !validEEPROM()) {
failureMode(10);
}
// re-read written data
readEEPROM();
if (b)
blinkLedAndSoundBeeper(15, 20, 1);
}
void checkFirstTime(bool reset)
@ -155,7 +156,8 @@ void checkFirstTime(bool reset)
// check the EEPROM integrity before resetting values
if (!validEEPROM() || reset) {
resetConf();
writeEEPROM(0);
writeEEPROM();
readEEPROM();
}
}

View file

@ -41,5 +41,6 @@ uint32_t featureMask(void);
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
void readEEPROM(void);
void writeEEPROM(uint8_t b);
void readEEPROMAndNotify(void);
void writeEEPROM();
void checkFirstTime(bool reset);

View file

@ -496,7 +496,8 @@ void loop(void)
i = 3;
if (i) {
mcfg.current_profile = i - 1;
writeEEPROM(0);
writeEEPROM();
readEEPROM();
blinkLedAndSoundBeeper(2, 40, i);
// TODO alarmArray[0] = i;
}
@ -530,7 +531,8 @@ void loop(void)
}
if (i) {
copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(1);
writeEEPROM();
readEEPROMAndNotify();
rcDelayCommand = 0; // allow autorepetition
}
}

View file

@ -41,7 +41,8 @@ void ACC_Common(void)
cfg.angleTrim[AI_ROLL] = 0;
cfg.angleTrim[AI_PITCH] = 0;
copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(1); // write accZero in EEPROM
writeEEPROM(); // write accZero in EEPROM
readEEPROMAndNotify();
}
calibratingA--;
}
@ -92,7 +93,8 @@ void ACC_Common(void)
cfg.angleTrim[AI_ROLL] = 0;
cfg.angleTrim[AI_PITCH] = 0;
copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(1); // write accZero in EEPROM
writeEEPROM(); // write accZero in EEPROM
readEEPROMAndNotify();
}
}

View file

@ -62,7 +62,8 @@ int Mag_getADC(void)
mcfg.magZero[axis] = (magZeroTempMin[axis] + magZeroTempMax[axis]) / 2; // Calculate offsets
}
copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(1);
writeEEPROM();
readEEPROMAndNotify();
}
}

View file

@ -835,7 +835,8 @@ static void cliProfile(char *cmdline)
i = atoi(cmdline);
if (i >= 0 && i <= 2) {
mcfg.current_profile = i;
writeEEPROM(0);
writeEEPROM();
readEEPROM();
cliProfile("");
}
}
@ -845,7 +846,7 @@ static void cliSave(char *cmdline)
{
cliPrint("Saving...");
copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(0);
writeEEPROM();
cliPrint("\r\nRebooting...");
delay(10);
systemReset(false);

View file

@ -354,10 +354,11 @@ static void evaluateCommand(void)
case MSP_SELECT_SETTING:
if (!f.ARMED) {
mcfg.current_profile = read8();
if (mcfg.current_profile > 2)
if (mcfg.current_profile > 2) {
mcfg.current_profile = 0;
// this writes new profile index and re-reads it
writeEEPROM(0);
}
writeEEPROM();
readEEPROM();
}
headSerialReply(0);
break;
@ -619,7 +620,8 @@ static void evaluateCommand(void)
headSerialError(0);
} else {
copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(0);
writeEEPROM();
readEEPROM();
headSerialReply(0);
}
break;