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

Cleaned up SetSysClock to remove duplicated code when configuring HSE or HSI

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@359 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2013-06-30 06:25:24 +00:00
parent e4ea700fe0
commit e010e3a354
2 changed files with 1605 additions and 1693 deletions

View file

@ -2,255 +2,167 @@
#define SYSCLK_FREQ_72MHz 72000000 #define SYSCLK_FREQ_72MHz 72000000
/*!< Uncomment the following line if you need to relocate your vector Table in Internal SRAM. */ uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Core Clock) */
/* #define VECT_TAB_SRAM */
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Core Clock) */ __I uint8_t AHBPrescTable[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9 };
__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);
static void SetSysClock(void); void SystemInit(void)
/**
* @brief Setup the microcontroller system
* Initialize the Embedded Flash Interface, the PLL and update the
* SystemCoreClock variable.
* @note This function should be used only after reset.
* @param None
* @retval None
*/
void SystemInit (void)
{ {
/* Reset the RCC clock configuration to the default reset state(for debug purpose) */ /* Reset the RCC clock configuration to the default reset state(for debug purpose) */
/* Set HSION bit */ /* Set HSION bit */
RCC->CR |= (uint32_t)0x00000001; RCC->CR |= (uint32_t) 0x00000001;
/* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
RCC->CFGR &= (uint32_t)0xF8FF0000; RCC->CFGR &= (uint32_t) 0xF8FF0000;
/* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= (uint32_t)0xFEF6FFFF;
/* Reset HSEBYP bit */ /* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= (uint32_t)0xFFFBFFFF; RCC->CR &= (uint32_t) 0xFEF6FFFF;
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ /* Reset HSEBYP bit */
RCC->CFGR &= (uint32_t)0xFF80FFFF; RCC->CR &= (uint32_t) 0xFFFBFFFF;
/* Disable all interrupts and clear pending bits */ /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */
RCC->CIR = 0x009F0000; RCC->CFGR &= (uint32_t) 0xFF80FFFF;
/* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */
/* Configure the Flash Latency cycles and enable prefetch buffer */
SetSysClock();
#ifdef VECT_TAB_SRAM /* Disable all interrupts and clear pending bits */
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ RCC->CIR = 0x009F0000;
#else
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ /* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */
#endif /* Configure the Flash Latency cycles and enable prefetch buffer */
SetSysClock();
SCB->VTOR = FLASH_BASE; /* Vector Table Relocation in Internal FLASH. */
} }
/** void SystemCoreClockUpdate(void)
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
* or HSI_VALUE(*) multiplied by the PLL factors.
*
* (*) HSI_VALUE is a constant defined in stm32f1xx.h file (default value
* 8 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSE_VALUE is a constant defined in stm32f1xx.h file (default value
* 8 MHz or 25 MHz, depedning on the product used), user has to ensure
* that HSE_VALUE is same as the real frequency of the crystal used.
* Otherwise, this function may have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
* @param None
* @retval None
*/
void SystemCoreClockUpdate (void)
{ {
uint32_t tmp = 0, pllmull = 0, pllsource = 0; uint32_t tmp = 0, pllmull = 0, pllsource = 0;
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp)
{
case 0x00: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
case 0x04: /* HSE used as system clock */
SystemCoreClock = HSE_VALUE;
break;
case 0x08: /* PLL used as system clock */
/* Get PLL clock source and multiplication factor ----------------------*/ /* Get SYSCLK source ------------------------------------------------------- */
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; tmp = RCC->CFGR & RCC_CFGR_SWS;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
pllmull = ( pllmull >> 18) + 2;
if (pllsource == 0x00)
{
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
}
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;
}
else
{
SystemCoreClock = HSE_VALUE * pllmull;
}
}
break;
default: switch (tmp) {
SystemCoreClock = HSI_VALUE; case 0x00: /* HSI used as system clock */
break; SystemCoreClock = HSI_VALUE;
} break;
case 0x04: /* HSE used as system clock */
/* Compute HCLK clock frequency ----------------*/ SystemCoreClock = HSE_VALUE;
/* Get HCLK prescaler */ break;
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; case 0x08: /* PLL used as system clock */
/* HCLK clock frequency */
SystemCoreClock >>= tmp; /* Get PLL clock source and multiplication factor ---------------------- */
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
pllmull = (pllmull >> 18) + 2;
if (pllsource == 0x00) {
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
} 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;
} else {
SystemCoreClock = HSE_VALUE * pllmull;
}
}
break;
default:
SystemCoreClock = HSI_VALUE;
break;
}
/* Compute HCLK clock frequency ---------------- */
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
} }
enum {
SRC_NONE = 0,
SRC_HSI,
SRC_HSE
};
// Set system clock to 72 (HSE) or 64 (HSI) MHz // Set system clock to 72 (HSE) or 64 (HSI) MHz
static void SetSysClock(void) static int SetSysClock(void)
{ {
__IO uint32_t StartUpCounter = 0, HSEStatus = 0, HSIStatus = 0; __IO uint32_t StartUpCounter = 0, status = 0, clocksrc = SRC_NONE;
__IO uint32_t *RCC_CRH = &GPIOC->CRH;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ __IO uint32_t RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL9;
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET) // First, try running off HSE
{ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
HSEStatus = (uint32_t)0x01; RCC->APB2ENR |= RCC_CFGR_HPRE_0;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01) // Wait till HSE is ready
{
/* Enable Prefetch Buffer */
FLASH->ACR |= FLASH_ACR_PRFTBE;
/* Flash 2 wait state */
FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2;
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
/* PLL configuration: PLLCLK = HSE * 9 = 72 MHz */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL9);
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while((RCC->CR & RCC_CR_PLLRDY) == 0);
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
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);
}
else
{ /* If HSE fails to start-up, the application will have wrong clock configuration. User can add here some code to deal with this error */
/* Enable HSI */
RCC->CR |= ((uint32_t)RCC_CR_HSION);
StartUpCounter = 0;
do { do {
HSIStatus = RCC->CR & RCC_CR_HSIRDY; status = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++; StartUpCounter++;
} while((HSIStatus == 0) && (StartUpCounter != 0x0500)); } while ((status == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
/* If that was successfull, we configure the PLL to use HSI as entry clock and to generate a system clock frequency of 64 MHz */ if ((RCC->CR & RCC_CR_HSERDY) != RESET) {
if ((RCC->CR & RCC_CR_HSIRDY) != RESET) { // external xtal started up, we're good to go
/* Enable Prefetch Buffer */ clocksrc = SRC_HSE;
FLASH->ACR |= FLASH_ACR_PRFTBE; } else {
// If HSE fails to start-up, try to enable HSI and configure for 64MHz operation
/* Flash 2 wait state */ RCC->CR |= ((uint32_t)RCC_CR_HSION);
FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); StartUpCounter = 0;
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2; do {
status = RCC->CR & RCC_CR_HSIRDY;
/* HCLK = SYSCLK */ StartUpCounter++;
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; } while ((status == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSIRDY) != RESET) {
/* PCLK2 = HCLK */ // we're on internal RC
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; clocksrc = SRC_HSI;
} else {
/* PCLK1 = HCLK */ // We're fucked
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; while(1);
}
/* PLL configuration: PLLCLK = HSI/2 * 16 = 64 MHz */
/* Set Bits to 0 */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
/* Set Bits to 1 */
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSI_Div2 | RCC_CFGR_PLLMULL16);
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while((RCC->CR & RCC_CR_PLLRDY) == 0);
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
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);
SystemCoreClockUpdate();
} }
}
// Enable Prefetch Buffer
FLASH->ACR |= FLASH_ACR_PRFTBE;
// Flash 2 wait state
FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2;
// HCLK = SYSCLK
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
// PCLK2 = HCLK
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
// PCLK1 = HCLK
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
*RCC_CRH &= (uint32_t)~((uint32_t)0xF << (RCC_CFGR_PLLMULL9 >> 16));
// Configure PLL
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;
switch (clocksrc) {
case SRC_HSE:
// PLL configuration: PLLCLK = HSE * 9 = 72 MHz
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMUL);
break;
case SRC_HSI:
// PLL configuration: PLLCLK = HSI / 2 * 16 = 64 MHz
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSI_Div2 | RCC_CFGR_PLLMULL16);
break;
}
// Enable PLL
RCC->CR |= RCC_CR_PLLON;
// Wait till PLL is ready
while ((RCC->CR & RCC_CR_PLLRDY) == 0);
// Select PLL as system clock source
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
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;
} }

File diff suppressed because it is too large Load diff