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

Removed profile storage code from writeEEProm() to remove the boolean

flag from the method signature.  Now it is clear when the current
profile needs to be stored.
This commit is contained in:
Dominic Clifton 2014-04-21 01:02:53 +01:00
parent e969d184e6
commit 3daaf66b14
7 changed files with 28 additions and 20 deletions

View file

@ -93,7 +93,13 @@ void readEEPROM(void)
} }
void writeEEPROM(uint8_t b, uint8_t updateProfile) void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex)
{
// copy current in-memory profile to stored configuration
memcpy(&mcfg.profile[profileSlotIndex], &cfg, sizeof(config_t));
}
void writeEEPROM(uint8_t b)
{ {
FLASH_Status status; FLASH_Status status;
uint32_t i; uint32_t i;
@ -108,12 +114,6 @@ void writeEEPROM(uint8_t b, uint8_t updateProfile)
mcfg.magic_ef = 0xEF; mcfg.magic_ef = 0xEF;
mcfg.chk = 0; mcfg.chk = 0;
// when updateProfile = true, we copy contents of cfg to global configuration. when false, only profile number is updated, and then that profile is loaded on readEEPROM()
if (updateProfile) {
// copy current in-memory profile to stored configuration
memcpy(&mcfg.profile[mcfg.current_profile], &cfg, sizeof(config_t));
}
// recalculate checksum before writing // recalculate checksum before writing
for (p = (const uint8_t *)&mcfg; p < ((const uint8_t *)&mcfg + sizeof(master_t)); p++) for (p = (const uint8_t *)&mcfg; p < ((const uint8_t *)&mcfg + sizeof(master_t)); p++)
chk ^= *p; chk ^= *p;
@ -155,8 +155,7 @@ void checkFirstTime(bool reset)
// check the EEPROM integrity before resetting values // check the EEPROM integrity before resetting values
if (!validEEPROM() || reset) { if (!validEEPROM() || reset) {
resetConf(); resetConf();
// no need to memcpy profile again, we just did it in resetConf() above writeEEPROM(0);
writeEEPROM(0, false);
} }
} }

View file

@ -38,6 +38,8 @@ void featureClear(uint32_t mask);
void featureClearAll(void); void featureClearAll(void);
uint32_t featureMask(void); uint32_t featureMask(void);
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
void readEEPROM(void); void readEEPROM(void);
void writeEEPROM(uint8_t b, uint8_t updateProfile); void writeEEPROM(uint8_t b);
void checkFirstTime(bool reset); void checkFirstTime(bool reset);

View file

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

View file

@ -40,7 +40,8 @@ void ACC_Common(void)
mcfg.accZero[GI_YAW] = (a[GI_YAW] + (CALIBRATING_ACC_CYCLES / 2)) / CALIBRATING_ACC_CYCLES - acc_1G; mcfg.accZero[GI_YAW] = (a[GI_YAW] + (CALIBRATING_ACC_CYCLES / 2)) / CALIBRATING_ACC_CYCLES - acc_1G;
cfg.angleTrim[AI_ROLL] = 0; cfg.angleTrim[AI_ROLL] = 0;
cfg.angleTrim[AI_PITCH] = 0; cfg.angleTrim[AI_PITCH] = 0;
writeEEPROM(1, true); // write accZero in EEPROM copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(1); // write accZero in EEPROM
} }
calibratingA--; calibratingA--;
} }
@ -90,7 +91,8 @@ void ACC_Common(void)
mcfg.accZero[GI_YAW] = b[GI_YAW] / 50 - acc_1G; // for nunchuk 200=1G mcfg.accZero[GI_YAW] = b[GI_YAW] / 50 - acc_1G; // for nunchuk 200=1G
cfg.angleTrim[AI_ROLL] = 0; cfg.angleTrim[AI_ROLL] = 0;
cfg.angleTrim[AI_PITCH] = 0; cfg.angleTrim[AI_PITCH] = 0;
writeEEPROM(1, true); // write accZero in EEPROM copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(1); // write accZero in EEPROM
} }
} }

View file

@ -58,9 +58,11 @@ int Mag_getADC(void)
} }
} else { } else {
tCal = 0; tCal = 0;
for (axis = 0; axis < 3; axis++) for (axis = 0; axis < 3; axis++) {
mcfg.magZero[axis] = (magZeroTempMin[axis] + magZeroTempMax[axis]) / 2; // Calculate offsets mcfg.magZero[axis] = (magZeroTempMin[axis] + magZeroTempMax[axis]) / 2; // Calculate offsets
writeEEPROM(1, true); }
copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(1);
} }
} }

View file

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

View file

@ -357,7 +357,7 @@ static void evaluateCommand(void)
if (mcfg.current_profile > 2) if (mcfg.current_profile > 2)
mcfg.current_profile = 0; mcfg.current_profile = 0;
// this writes new profile index and re-reads it // this writes new profile index and re-reads it
writeEEPROM(0, false); writeEEPROM(0);
} }
headSerialReply(0); headSerialReply(0);
break; break;
@ -618,7 +618,8 @@ static void evaluateCommand(void)
if (f.ARMED) { if (f.ARMED) {
headSerialError(0); headSerialError(0);
} else { } else {
writeEEPROM(0, true); copyCurrentProfileToProfileSlot(mcfg.current_profile);
writeEEPROM(0);
headSerialReply(0); headSerialReply(0);
} }
break; break;