mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
added overclock feature
This commit is contained in:
parent
03fab3f915
commit
6716ecfe7e
7 changed files with 34 additions and 11 deletions
16
src/config.c
16
src/config.c
|
@ -56,8 +56,6 @@ static uint8_t validEEPROM(void)
|
|||
|
||||
void readEEPROM(void)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
// Sanity check
|
||||
if (!validEEPROM())
|
||||
failureMode(10);
|
||||
|
@ -67,8 +65,12 @@ void readEEPROM(void)
|
|||
// Copy current profile
|
||||
if (mcfg.current_profile > 2) // sanity check
|
||||
mcfg.current_profile = 0;
|
||||
memcpy(&cfg, &mcfg.profile[mcfg.current_profile], sizeof(config_t));
|
||||
memcpy(&cfg, &mcfg.profile[mcfg.current_profile], sizeof(config_t));
|
||||
}
|
||||
|
||||
void activateConfig(void)
|
||||
{
|
||||
uint8_t i;
|
||||
for (i = 0; i < PITCH_LOOKUP_LENGTH; i++)
|
||||
lookupPitchRollRC[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 2500;
|
||||
|
||||
|
@ -87,6 +89,12 @@ void readEEPROM(void)
|
|||
gpsSetPIDs();
|
||||
}
|
||||
|
||||
void loadAndActivateConfig(void)
|
||||
{
|
||||
readEEPROM();
|
||||
activateConfig();
|
||||
}
|
||||
|
||||
void writeEEPROM(uint8_t b, uint8_t updateProfile)
|
||||
{
|
||||
FLASH_Status status;
|
||||
|
@ -139,7 +147,7 @@ retry:
|
|||
}
|
||||
|
||||
// re-read written data
|
||||
readEEPROM();
|
||||
loadAndActivateConfig();
|
||||
if (b)
|
||||
blinkLED(15, 20, 1);
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue