diff --git a/src/config.c b/src/config.c index 7185f756b8..cddedcda7e 100755 --- a/src/config.c +++ b/src/config.c @@ -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; uint32_t i; @@ -108,12 +114,6 @@ void writeEEPROM(uint8_t b, uint8_t updateProfile) mcfg.magic_ef = 0xEF; 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 for (p = (const uint8_t *)&mcfg; p < ((const uint8_t *)&mcfg + sizeof(master_t)); p++) chk ^= *p; @@ -155,8 +155,7 @@ void checkFirstTime(bool reset) // check the EEPROM integrity before resetting values if (!validEEPROM() || reset) { resetConf(); - // no need to memcpy profile again, we just did it in resetConf() above - writeEEPROM(0, false); + writeEEPROM(0); } } diff --git a/src/config.h b/src/config.h index 25c6977494..f9d839e5a8 100644 --- a/src/config.h +++ b/src/config.h @@ -38,6 +38,8 @@ void featureClear(uint32_t mask); void featureClearAll(void); uint32_t featureMask(void); +void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex); + void readEEPROM(void); -void writeEEPROM(uint8_t b, uint8_t updateProfile); +void writeEEPROM(uint8_t b); void checkFirstTime(bool reset); diff --git a/src/mw.c b/src/mw.c index c01a1ea1c1..40dda9c5bb 100755 --- a/src/mw.c +++ b/src/mw.c @@ -496,7 +496,7 @@ void loop(void) i = 3; if (i) { mcfg.current_profile = i - 1; - writeEEPROM(0, false); + writeEEPROM(0); blinkLedAndSoundBeeper(2, 40, i); // TODO alarmArray[0] = i; } @@ -529,7 +529,8 @@ void loop(void) i = 1; } if (i) { - writeEEPROM(1, true); + copyCurrentProfileToProfileSlot(mcfg.current_profile); + writeEEPROM(1); rcDelayCommand = 0; // allow autorepetition } } diff --git a/src/sensors_acceleration.c b/src/sensors_acceleration.c index cbff683261..9c3b866049 100644 --- a/src/sensors_acceleration.c +++ b/src/sensors_acceleration.c @@ -40,7 +40,8 @@ void ACC_Common(void) mcfg.accZero[GI_YAW] = (a[GI_YAW] + (CALIBRATING_ACC_CYCLES / 2)) / CALIBRATING_ACC_CYCLES - acc_1G; cfg.angleTrim[AI_ROLL] = 0; cfg.angleTrim[AI_PITCH] = 0; - writeEEPROM(1, true); // write accZero in EEPROM + copyCurrentProfileToProfileSlot(mcfg.current_profile); + writeEEPROM(1); // write accZero in EEPROM } calibratingA--; } @@ -90,7 +91,8 @@ void ACC_Common(void) mcfg.accZero[GI_YAW] = b[GI_YAW] / 50 - acc_1G; // for nunchuk 200=1G cfg.angleTrim[AI_ROLL] = 0; cfg.angleTrim[AI_PITCH] = 0; - writeEEPROM(1, true); // write accZero in EEPROM + copyCurrentProfileToProfileSlot(mcfg.current_profile); + writeEEPROM(1); // write accZero in EEPROM } } diff --git a/src/sensors_compass.c b/src/sensors_compass.c index 4f71518ffb..799e57a3ee 100644 --- a/src/sensors_compass.c +++ b/src/sensors_compass.c @@ -58,9 +58,11 @@ int Mag_getADC(void) } } else { tCal = 0; - for (axis = 0; axis < 3; axis++) + for (axis = 0; axis < 3; axis++) { mcfg.magZero[axis] = (magZeroTempMin[axis] + magZeroTempMax[axis]) / 2; // Calculate offsets - writeEEPROM(1, true); + } + copyCurrentProfileToProfileSlot(mcfg.current_profile); + writeEEPROM(1); } } diff --git a/src/serial_cli.c b/src/serial_cli.c index 85fc967316..0a52e42d72 100644 --- a/src/serial_cli.c +++ b/src/serial_cli.c @@ -835,7 +835,7 @@ static void cliProfile(char *cmdline) i = atoi(cmdline); if (i >= 0 && i <= 2) { mcfg.current_profile = i; - writeEEPROM(0, false); + writeEEPROM(0); cliProfile(""); } } @@ -844,7 +844,8 @@ static void cliProfile(char *cmdline) static void cliSave(char *cmdline) { cliPrint("Saving..."); - writeEEPROM(0, true); + copyCurrentProfileToProfileSlot(mcfg.current_profile); + writeEEPROM(0); cliPrint("\r\nRebooting..."); delay(10); systemReset(false); diff --git a/src/serial_msp.c b/src/serial_msp.c index e0916b15de..64c3878f8f 100755 --- a/src/serial_msp.c +++ b/src/serial_msp.c @@ -357,7 +357,7 @@ static void evaluateCommand(void) if (mcfg.current_profile > 2) mcfg.current_profile = 0; // this writes new profile index and re-reads it - writeEEPROM(0, false); + writeEEPROM(0); } headSerialReply(0); break; @@ -618,7 +618,8 @@ static void evaluateCommand(void) if (f.ARMED) { headSerialError(0); } else { - writeEEPROM(0, true); + copyCurrentProfileToProfileSlot(mcfg.current_profile); + writeEEPROM(0); headSerialReply(0); } break;