1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 06:15:16 +03:00

Merge pull request #78 from schugabe/overclock

Added overclock feature
This commit is contained in:
dongie 2014-04-21 19:47:11 +09:00
commit 9f107545e2
7 changed files with 37 additions and 14 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

@ -113,6 +113,7 @@ typedef struct {
const clivalue_t valueTable[] = { const clivalue_t valueTable[] = {
{ "looptime", VAR_UINT16, &mcfg.looptime, 0, 9000 }, { "looptime", VAR_UINT16, &mcfg.looptime, 0, 9000 },
{ "emf_avoidance", VAR_UINT8, &mcfg.emfAvoidance, 0, 1 },
{ "midrc", VAR_UINT16, &mcfg.midrc, 1200, 1700 }, { "midrc", VAR_UINT16, &mcfg.midrc, 1200, 1700 },
{ "minthrottle", VAR_UINT16, &mcfg.minthrottle, 0, 2000 }, { "minthrottle", VAR_UINT16, &mcfg.minthrottle, 0, 2000 },
{ "maxthrottle", VAR_UINT16, &mcfg.maxthrottle, 0, 2000 }, { "maxthrottle", VAR_UINT16, &mcfg.maxthrottle, 0, 2000 },

View file

@ -13,7 +13,7 @@ master_t mcfg; // master config struct with data independent from profiles
config_t cfg; // profile config struct config_t cfg; // profile config struct
const char rcChannelLetters[] = "AERT1234"; const char rcChannelLetters[] = "AERT1234";
static const uint8_t EEPROM_CONF_VERSION = 62; static const uint8_t EEPROM_CONF_VERSION = 63;
static uint32_t enabledSensors = 0; static uint32_t enabledSensors = 0;
static void resetConf(void); static void resetConf(void);
@ -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);
} }
@ -220,6 +228,7 @@ static void resetConf(void)
mcfg.softserial_1_inverted = 0; mcfg.softserial_1_inverted = 0;
mcfg.softserial_2_inverted = 0; mcfg.softserial_2_inverted = 0;
mcfg.looptime = 3500; mcfg.looptime = 3500;
mcfg.emfAvoidance = 0;
mcfg.rssi_aux_channel = 0; mcfg.rssi_aux_channel = 0;
cfg.pidController = 0; cfg.pidController = 0;

View file

@ -5,7 +5,7 @@ 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);
#ifdef BUZZER #ifdef BUZZER
void systemBeep(bool onoff); void systemBeep(bool onoff);
static void beepRev4(bool onoff); static void beepRev4(bool onoff);
@ -43,7 +43,7 @@ uint32_t millis(void)
return sysTickUptime; return sysTickUptime;
} }
void systemInit(void) void systemInit(bool overclock)
{ {
struct { struct {
GPIO_TypeDef *gpio; GPIO_TypeDef *gpio;
@ -75,7 +75,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(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

@ -1,6 +1,6 @@
#pragma once #pragma once
void systemInit(void); void systemInit(bool overclock);
void delayMicroseconds(uint32_t us); void delayMicroseconds(uint32_t us);
void delay(uint32_t ms); void delay(uint32_t ms);

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
systemInit(); checkFirstTime(false);
readEEPROM();
systemInit(mcfg.emfAvoidance);
#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

@ -224,6 +224,7 @@ typedef struct master_t {
uint8_t mixerConfiguration; uint8_t mixerConfiguration;
uint32_t enabledFeatures; uint32_t enabledFeatures;
uint16_t looptime; // imu loop time in us uint16_t looptime; // imu loop time in us
uint8_t emfAvoidance; // change pll settings to avoid noise in the uhf band
motorMixer_t customMixer[MAX_MOTORS]; // custom mixtable motorMixer_t customMixer[MAX_MOTORS]; // custom mixtable
// motor/esc/servo related stuff // motor/esc/servo related stuff
@ -437,6 +438,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);