added overclock feature

This commit is contained in:
Johannes Kasberger 2014-04-14 19:52:04 +02:00
parent 03fab3f915
commit 6716ecfe7e
7 changed files with 34 additions and 11 deletions

View File

@ -1,3 +1,4 @@
#include <stdbool.h>
#include "stm32f10x.h" #include "stm32f10x.h"
#define SYSCLK_FREQ_72MHz 72000000 #define SYSCLK_FREQ_72MHz 72000000
@ -86,7 +87,7 @@ enum {
}; };
// Set system clock to 72 (HSE) or 64 (HSI) MHz // Set system clock to 72 (HSE) or 64 (HSI) MHz
void SetSysClock(void) void SetSysClock(bool overclock)
{ {
__IO uint32_t StartUpCounter = 0, status = 0, clocksrc = SRC_NONE; __IO uint32_t StartUpCounter = 0, status = 0, clocksrc = SRC_NONE;
__IO uint32_t *RCC_CRH = &GPIOC->CRH; __IO uint32_t *RCC_CRH = &GPIOC->CRH;
@ -140,10 +141,18 @@ void SetSysClock(void)
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
*RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16); *RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16);
GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET); GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET);
RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9; RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9;
switch (clocksrc) { switch (clocksrc) {
case SRC_HSE: case SRC_HSE:
// PLL configuration: PLLCLK = HSE * 9 = 72 MHz if (overclock) {
if (RCC_CFGR_PLLMUL == RCC_CFGR_PLLMULL6)
RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL7;
else if (RCC_CFGR_PLLMUL == RCC_CFGR_PLLMULL9)
RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL10;
}
// overclock=false : PLL configuration: PLLCLK = HSE * 9 = 72 MHz || HSE * 6 = 72 MHz
// overclock=true : PLL configuration: PLLCLK = HSE * 10 = 80 MHz || HSE * 7 = 84 MHz
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMUL); RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMUL);
break; break;
case SRC_HSI: case SRC_HSI:

View File

@ -75,6 +75,7 @@ typedef enum {
FEATURE_POWERMETER = 1 << 12, FEATURE_POWERMETER = 1 << 12,
FEATURE_VARIO = 1 << 13, FEATURE_VARIO = 1 << 13,
FEATURE_3D = 1 << 14, FEATURE_3D = 1 << 14,
FEATURE_OVERCLOCK = 1 << 15,
} AvailableFeatures; } AvailableFeatures;
typedef enum { typedef enum {

View File

@ -54,7 +54,7 @@ static const char * const mixerNames[] = {
static const char * const featureNames[] = { static const char * const featureNames[] = {
"PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP", "PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP",
"SERVO_TILT", "SOFTSERIAL", "LED_RING", "GPS", "SERVO_TILT", "SOFTSERIAL", "LED_RING", "GPS",
"FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", "FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", "OVERCLOCK",
NULL NULL
}; };

View File

@ -56,8 +56,6 @@ static uint8_t validEEPROM(void)
void readEEPROM(void) void readEEPROM(void)
{ {
uint8_t i;
// Sanity check // Sanity check
if (!validEEPROM()) if (!validEEPROM())
failureMode(10); failureMode(10);
@ -68,7 +66,11 @@ void readEEPROM(void)
if (mcfg.current_profile > 2) // sanity check if (mcfg.current_profile > 2) // sanity check
mcfg.current_profile = 0; 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++) for (i = 0; i < PITCH_LOOKUP_LENGTH; i++)
lookupPitchRollRC[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 2500; lookupPitchRollRC[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 2500;
@ -87,6 +89,12 @@ void readEEPROM(void)
gpsSetPIDs(); gpsSetPIDs();
} }
void loadAndActivateConfig(void)
{
readEEPROM();
activateConfig();
}
void writeEEPROM(uint8_t b, uint8_t updateProfile) void writeEEPROM(uint8_t b, uint8_t updateProfile)
{ {
FLASH_Status status; FLASH_Status status;
@ -139,7 +147,7 @@ retry:
} }
// re-read written data // re-read written data
readEEPROM(); loadAndActivateConfig();
if (b) if (b)
blinkLED(15, 20, 1); blinkLED(15, 20, 1);
} }

View File

@ -5,7 +5,9 @@ static volatile uint32_t usTicks = 0;
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care. // current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
static volatile uint32_t sysTickUptime = 0; static volatile uint32_t sysTickUptime = 0;
// from system_stm32f10x.c // from system_stm32f10x.c
void SetSysClock(void); void SetSysClock(bool overclock);
// from config.h
bool feature(uint32_t mask);
#ifdef BUZZER #ifdef BUZZER
void systemBeep(bool onoff); void systemBeep(bool onoff);
static void beepRev4(bool onoff); static void beepRev4(bool onoff);
@ -75,7 +77,7 @@ void systemInit(void)
// Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers // Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers
// Configure the Flash Latency cycles and enable prefetch buffer // Configure the Flash Latency cycles and enable prefetch buffer
SetSysClock(); SetSysClock(feature(FEATURE_OVERCLOCK));
// Turn on clocks for stuff we use // Turn on clocks for stuff we use
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE); RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE);

View File

@ -36,13 +36,14 @@ int main(void)
serialPort_t* loopbackPort1 = NULL; serialPort_t* loopbackPort1 = NULL;
serialPort_t* loopbackPort2 = NULL; serialPort_t* loopbackPort2 = NULL;
#endif #endif
checkFirstTime(false);
readEEPROM();
systemInit(); systemInit();
#ifdef USE_LAME_PRINTF #ifdef USE_LAME_PRINTF
init_printf(NULL, _putc); init_printf(NULL, _putc);
#endif #endif
checkFirstTime(false); activateConfig();
readEEPROM();
// configure power ADC // configure power ADC
if (mcfg.power_adc_channel > 0 && (mcfg.power_adc_channel == 1 || mcfg.power_adc_channel == 9)) if (mcfg.power_adc_channel > 0 && (mcfg.power_adc_channel == 1 || mcfg.power_adc_channel == 9))

View File

@ -437,6 +437,8 @@ void serialCom(void);
// Config // Config
void parseRcChannels(const char *input); void parseRcChannels(const char *input);
void activateConfig(void);
void loadAndActivateConfig(void);
void readEEPROM(void); void readEEPROM(void);
void writeEEPROM(uint8_t b, uint8_t updateProfile); void writeEEPROM(uint8_t b, uint8_t updateProfile);
void checkFirstTime(bool reset); void checkFirstTime(bool reset);