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

a couple optimizations for dynamic HSE frequency - moved SetSysClock() to run after reset vector + bss init, and changed rcc which used hardcoded HSE_VALUE.

turn off leds/beeper before initializing pins to prevent flash at startup
uninitialized errorAngle fix in new PID


git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@362 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2013-07-02 00:58:50 +00:00
parent 3afeb3d1c8
commit 57cbd784a9
11 changed files with 3091 additions and 3036 deletions

View file

@ -6,7 +6,7 @@ uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Cor
__I uint8_t AHBPrescTable[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9 };
static int SetSysClock(void);
uint32_t hse_value = 8000000;
void SystemInit(void)
{
@ -29,10 +29,6 @@ void SystemInit(void)
/* Disable all interrupts and clear pending bits */
RCC->CIR = 0x009F0000;
/* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */
/* Configure the Flash Latency cycles and enable prefetch buffer */
SetSysClock();
SCB->VTOR = FLASH_BASE; /* Vector Table Relocation in Internal FLASH. */
}
@ -48,7 +44,7 @@ void SystemCoreClockUpdate(void)
SystemCoreClock = HSI_VALUE;
break;
case 0x04: /* HSE used as system clock */
SystemCoreClock = HSE_VALUE;
SystemCoreClock = hse_value;
break;
case 0x08: /* PLL used as system clock */
@ -64,9 +60,9 @@ void SystemCoreClockUpdate(void)
} else {
/* HSE selected as PLL clock entry */
if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t) RESET) { /* HSE oscillator clock divided by 2 */
SystemCoreClock = (HSE_VALUE >> 1) * pllmull;
SystemCoreClock = (hse_value >> 1) * pllmull;
} else {
SystemCoreClock = HSE_VALUE * pllmull;
SystemCoreClock = hse_value * pllmull;
}
}
break;
@ -90,7 +86,7 @@ enum {
};
// Set system clock to 72 (HSE) or 64 (HSI) MHz
static int SetSysClock(void)
void SetSysClock(void)
{
__IO uint32_t StartUpCounter = 0, status = 0, clocksrc = SRC_NONE;
__IO uint32_t *RCC_CRH = &GPIOC->CRH;
@ -140,10 +136,11 @@ static int SetSysClock(void)
*RCC_CRH &= (uint32_t)~((uint32_t)0xF << (RCC_CFGR_PLLMULL9 >> 16));
// Configure PLL
hse_value = 8000000;
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
*RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16);
GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET);
RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? StartUpCounter = 42, 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) {
case SRC_HSE:
// PLL configuration: PLLCLK = HSE * 9 = 72 MHz
@ -164,5 +161,6 @@ static int SetSysClock(void)
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
// Wait till PLL is used as system clock source
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08);
return StartUpCounter;
SystemCoreClockUpdate();
}

View file

@ -192,6 +192,7 @@
static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8};
extern uint32_t hse_value;
/**
* @}
@ -926,7 +927,7 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
break;
case 0x04: /* HSE used as system clock */
RCC_Clocks->SYSCLK_Frequency = HSE_VALUE;
RCC_Clocks->SYSCLK_Frequency = hse_value;
break;
case 0x08: /* PLL used as system clock */
@ -951,11 +952,11 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
/* HSE selected as PLL clock entry */
if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (uint32_t)RESET)
{/* HSE oscillator clock divided by 2 */
RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE >> 1) * pllmull;
RCC_Clocks->SYSCLK_Frequency = (hse_value >> 1) * pllmull;
}
else
{
RCC_Clocks->SYSCLK_Frequency = HSE_VALUE * pllmull;
RCC_Clocks->SYSCLK_Frequency = hse_value * pllmull;
}
#endif
}
@ -973,7 +974,7 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
if (pllsource == 0x00)
{/* HSI oscillator clock divided by 2 selected as PLL clock entry */
RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull;
RCC_Clocks->SYSCLK_Frequency = (hse_value >> 1) * pllmull;
}
else
{/* PREDIV1 selected as PLL clock entry */
@ -984,7 +985,7 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
if (prediv1source == 0)
{ /* HSE oscillator clock selected as PREDIV1 clock entry */
RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull;
RCC_Clocks->SYSCLK_Frequency = (hse_value / prediv1factor) * pllmull;
}
else
{/* PLL2 clock selected as PREDIV1 clock entry */
@ -992,7 +993,7 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
/* Get PREDIV2 division factor and PLL2 multiplication factor */
prediv2factor = ((RCC->CFGR2 & CFGR2_PREDIV2) >> 4) + 1;
pll2mull = ((RCC->CFGR2 & CFGR2_PLL2MUL) >> 8 ) + 2;
RCC_Clocks->SYSCLK_Frequency = (((HSE_VALUE / prediv2factor) * pll2mull) / prediv1factor) * pllmull;
RCC_Clocks->SYSCLK_Frequency = (((hse_value / prediv2factor) * pll2mull) / prediv1factor) * pllmull;
}
}
#endif /* STM32F10X_CL */

File diff suppressed because it is too large Load diff

View file

@ -42,6 +42,10 @@ bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc)
bool ack = false;
uint8_t sig = 0;
// Not supported with this frequency
if (hse_value == 12000000)
return false;
ack = i2cRead(ADXL345_ADDRESS, 0x00, 1, &sig);
if (!ack || sig != 0xE5)
return false;

View file

@ -95,6 +95,10 @@ bool bmp085Detect(baro_t *baro)
NVIC_InitTypeDef NVIC_InitStructure;
uint8_t data;
// Not supported with this frequency
if (hse_value == 12000000)
return false;
if (bmp085InitDone)
return true;

View file

@ -77,7 +77,6 @@ static void i2c_er_handler(void)
bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
{
uint8_t i;
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
addr = addr_ << 1;

View file

@ -59,6 +59,10 @@ bool mma8452Detect(sensor_t *acc)
bool ack = false;
uint8_t sig = 0;
// Not supported with this frequency
if (hse_value == 12000000)
return false;
ack = i2cRead(MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
return false;

View file

@ -36,17 +36,19 @@ static uint8_t ms5611_osr = CMD_ADC_4096;
bool ms5611Detect(baro_t *baro)
{
gpio_config_t gpio;
bool ack = false;
uint8_t sig;
int i;
// PC13 (BMP085's XCLR reset input, which we use to disable it)
if (hse_value != 12000000) {
// PC13 (BMP085's XCLR reset input, which we use to disable it). Only needed when running at 8MHz
gpio_config_t gpio;
gpio.pin = Pin_13;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_Out_PP;
gpioInit(GPIOC, &gpio);
BMP085_OFF;
}
delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms

View file

@ -4,6 +4,8 @@
static volatile uint32_t usTicks = 0;
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
static volatile uint32_t sysTickUptime = 0;
// from system_stm32f10x.c
void SetSysClock(void);
static void cycleCounterInit(void)
{
@ -60,8 +62,9 @@ void systemInit(void)
uint32_t i;
uint8_t gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
// This is needed because some shit inside Keil startup fucks with SystemCoreClock, setting it back to 72MHz even on HSI.
SystemCoreClockUpdate();
// Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers
// Configure the Flash Latency cycles and enable prefetch buffer
SetSysClock();
// Turn on clocks for stuff we use
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE);
@ -81,13 +84,13 @@ void systemInit(void)
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
// Configure gpio
for (i = 0; i < gpio_count; i++)
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
LED0_OFF;
LED1_OFF;
BEEP_OFF;
for (i = 0; i < gpio_count; i++)
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
// Init cycle counter
cycleCounterInit();

View file

@ -12,3 +12,6 @@ void failureMode(uint8_t mode);
// bootloader/IAP
void systemReset(bool toBootloader);
// current crystal frequency - 8 or 12MHz
extern uint32_t hse_value;

View file

@ -342,7 +342,7 @@ static void pidMultiWii(void)
static void pidRewrite(void)
{
int32_t errorAngle;
int32_t errorAngle = 0;
int axis;
int32_t delta, deltaSum;
static int32_t delta1[3], delta2[3];