diff options
author | jaseg <git@jaseg.net> | 2016-12-19 02:32:36 +0100 |
---|---|---|
committer | jaseg <git@jaseg.net> | 2016-12-19 02:32:36 +0100 |
commit | b04d8b94aa6db9b6e63fbccc19304841188a4f84 (patch) | |
tree | c48bd9897322a131d860b7e3e343ded01c30a9d9 /olsndot/firmware | |
parent | b0d17eb4ae9ad7051188f60ba364ee86cba871b9 (diff) | |
download | olsndot-b04d8b94aa6db9b6e63fbccc19304841188a4f84.tar.gz olsndot-b04d8b94aa6db9b6e63fbccc19304841188a4f84.tar.bz2 olsndot-b04d8b94aa6db9b6e63fbccc19304841188a4f84.zip |
Add first firmware foo
Diffstat (limited to 'olsndot/firmware')
-rw-r--r-- | olsndot/firmware/Makefile | 44 | ||||
-rw-r--r-- | olsndot/firmware/main.c | 124 | ||||
-rw-r--r-- | olsndot/firmware/stm32_flash.ld | 124 | ||||
-rw-r--r-- | olsndot/firmware/system_stm32f0xx.c | 336 |
4 files changed, 628 insertions, 0 deletions
diff --git a/olsndot/firmware/Makefile b/olsndot/firmware/Makefile new file mode 100644 index 0000000..cf338eb --- /dev/null +++ b/olsndot/firmware/Makefile @@ -0,0 +1,44 @@ +# put your *.o targets here, make should handle the rest! +CMSIS_PATH ?= STM32Cube/Drivers/CMSIS +CMSIS_DEV_PATH ?= $(CMSIS_PATH)/Device/ST/STM32F0xx +HAL_PATH ?= STM32Cube/Drivers/STM32F0xx_HAL_Driver + +CC := arm-none-eabi-gcc +OBJCOPY := arm-none-eabi-objcopy +OBJDUMP := arm-none-eabi-objdump +SIZE := arm-none-eabi-size + +CFLAGS = -Wall -g -std=gnu11 -Os +CFLAGS += -mlittle-endian -mcpu=cortex-m0 -march=armv6-m -mthumb +CFLAGS += -ffunction-sections -fdata-sections +CFLAGS += -Wl,--gc-sections -Wl,-Map=main.map + +# Technically we're using an STM32F030F4, but apart from the TSSOP20 package that one is largely identical to the +# STM32F030*6 and there is no separate device header provided for it, so we're faking a *6 device here. This is +# even documented in stm32f0xx.h. Thanks ST! +CFLAGS += -DSTM32F030x6 + +CFLAGS += -Tstm32_flash.ld +CFLAGS += -I$(CMSIS_DEV_PATH)/Include -I$(CMSIS_PATH)/Include -I$(HAL_PATH)/Inc -Iconfig +CFLAGS += -L$(CMSIS_PATH)/Lib/GCC -larm_cortexM0l_math + +################################################### + +.PHONY: program clean + +all: main.elf + +main.elf: main.c startup_stm32f030x6.s system_stm32f0xx.c $(HAL_PATH)/Src/stm32f0xx_ll_utils.c + $(CC) $(CFLAGS) -o $@ $^ + $(OBJCOPY) -O ihex $@ $(@:.elf=.hex) + $(OBJCOPY) -O binary $@ $(@:.elf=.bin) + $(OBJDUMP) -St $@ >$(@:.elf=.lst) + $(SIZE) $@ + +program: main.elf openocd.cfg + openocd -f openocd.cfg -c "program $< verify reset exit" + +clean: + rm -f *.o + rm -f main.elf main.hex main.bin main.map main.lst + diff --git a/olsndot/firmware/main.c b/olsndot/firmware/main.c new file mode 100644 index 0000000..a4029c1 --- /dev/null +++ b/olsndot/firmware/main.c @@ -0,0 +1,124 @@ + +#include <stm32f0xx.h> +#include <stdint.h> +#include <system_stm32f0xx.h> +#include <stm32f0xx_ll_utils.h> +/* + * Part number: STM32F030F4C6 + */ + +int main(void) { + LL_Init1msTick(SystemCoreClock); + + RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN; + RCC->APB2ENR |= RCC_APB2ENR_SPI1EN | RCC_APB2ENR_TIM1EN | RCC_APB2ENR_USART1EN | RCC_APB2ENR_ADCEN; + + GPIOA->MODER |= + (3<<GPIO_MODER_MODER0_Pos) /* PA0 - Current measurement analog input */ + | (1<<GPIO_MODER_MODER1_Pos) /* PA1 - RS485 TX enable */ + | (2<<GPIO_MODER_MODER2_Pos) /* PA2 - RS485 TX */ + | (2<<GPIO_MODER_MODER3_Pos) /* PA3 - RS485 RX */ + | (1<<GPIO_MODER_MODER4_Pos) /* PA4 - LED1 open-drain output */ + | (2<<GPIO_MODER_MODER5_Pos) /* PA5 - Shift register clk/SCLK */ + | (1<<GPIO_MODER_MODER6_Pos) /* PA6 - LED2 open-drain output */ + | (2<<GPIO_MODER_MODER7_Pos) /* PA7 - Shift register data/MOSI */ + | (2<<GPIO_MODER_MODER9_Pos) /* PA9 - Shift register clear (TIM1_CH2) */ + | (2<<GPIO_MODER_MODER10_Pos);/* PA10 - Shift register strobe (TIM1_CH3) */ + GPIOB->MODER |= + (1<<GPIO_MODER_MODER1_Pos); /* PB1 - Current measurement range selection */ + + + GPIOA->OTYPER |= GPIO_OTYPER_OT_6 | GPIO_OTYPER_OT_4; /* LED outputs -> open drain */ + + /* Set shift register IO GPIO output speed */ + GPIOA->OSPEEDR |= + (1<<GPIO_OSPEEDR_OSPEEDR5_Pos) /* SCLK */ + | (1<<GPIO_OSPEEDR_OSPEEDR7_Pos) /* MOSI */ + | (1<<GPIO_OSPEEDR_OSPEEDR9_Pos) /* Clear */ + | (1<<GPIO_OSPEEDR_OSPEEDR10_Pos);/* Strobe */ + + GPIOA->AFR[0] |= + (1<<GPIO_AFRL_AFRL2_Pos) /* USART1_TX */ + | (1<<GPIO_AFRL_AFRL3_Pos) /* USART1_RX */ + | (0<<GPIO_AFRL_AFRL5_Pos) /* SPI1_SCK */ + | (0<<GPIO_AFRL_AFRL7_Pos); /* SPI1_MOSI */ + GPIOA->AFR[1] |= + (2<<GPIO_AFRH_AFRH1_Pos) /* TIM1_CH2 */ + | (2<<GPIO_AFRH_AFRH2_Pos); /* TIM1_CH3 */ + + GPIOB->BSRR = GPIO_BSRR_BR_1; /* clear output is active low */ + + /* Configure SPI controller */ + /* CPOL=0, CPHA=0, prescaler=8 -> 1MBd */ +// SPI1->CR1 = SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE | SPI_CR1_SSM | SPI_CR1_SSI | SPI_CR1_SPE | (2<<SPI_CR1_BR_Pos) | SPI_CR1_MSTR; + SPI1->CR1 = SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE | SPI_CR1_SSM | SPI_CR1_SSI | SPI_CR1_SPE | (7<<SPI_CR1_BR_Pos) | SPI_CR1_MSTR; + SPI1->CR2 = (7<<SPI_CR2_DS_Pos); + /* Configure TIM1 for display strobe generation */ + /* Configure UART for RS485 comm */ + /* 8N1, 115200Bd */ + TIM1->CR1 = TIM_CR1_ARPE; //TIM_CR1_OPM | + TIM1->PSC = 256; // debug + TIM1->CCMR1 = (6<<TIM_CCMR1_OC2M_Pos) | TIM_CCMR1_OC2PE | (6<<TIM_CCMR1_OC1M_Pos) | TIM_CCMR1_OC1PE; + TIM1->CCMR2 = (6<<TIM_CCMR2_OC3M_Pos) | TIM_CCMR2_OC3PE; + TIM1->CCER = TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E; + TIM1->BDTR = TIM_BDTR_MOE; + TIM1->RCR = 2; + TIM1->CCR1 = 1; + TIM1->CCR3 = 2; /* strobe */ + TIM1->ARR = 16384; +// TIM1->DIER = TIM_DIER_CC1IE; + + NVIC_EnableIRQ(TIM1_CC_IRQn); + NVIC_SetPriority(TIM1_CC_IRQn, 2); + + TIM1->EGR |= TIM_EGR_UG; + TIM1->CR1 |= TIM_CR1_CEN; + + for (;;) { + } +} + +#define NBITS 4 +uint8_t brightness_by_bit[NBITS] = { + 0x11, 0x22, 0x44, 0x88 +}; + +void TIM1_CC_IRQHandler(void) { + static uint32_t bitpos = 0; + bitpos = (bitpos+1)&(NBITS-1); + +// SPI1->DR = ((uint32_t)brightness_by_bit[bitpos])<<8; + SPI1->DR = (bitpos<<8) | (bitpos<<10) | (bitpos<<12) | (bitpos<<14); + while (SPI1->SR & SPI_SR_BSY); + + const uint32_t cycles_strobe = 2; + const uint32_t cycles_clear = 2; + const uint32_t base_val = 16; + uint32_t period = base_val<<bitpos; + + TIM1->ARR = 128;//period; +// TIM1->CCR3 = cycles_strobe; /* strobe */ +// TIM1->CCR2 = period-cycles_clear; /* clear */ +// TIM1->EGR |= TIM_EGR_UG; + TIM1->CR1 |= TIM_CR1_CEN; +// TIM1->ARR = cycles_strobe+1; +// GPIOA->BSRR = GPIO_BSRR_BR_4 | GPIO_BSRR_BS_6; +} + +void NMI_Handler(void) { +} + +void HardFault_Handler(void) { + for(;;); +} + +void SVC_Handler(void) { +} + + +void PendSV_Handler(void) { +} + +void SysTick_Handler(void) { +} + diff --git a/olsndot/firmware/stm32_flash.ld b/olsndot/firmware/stm32_flash.ld new file mode 100644 index 0000000..927e8b4 --- /dev/null +++ b/olsndot/firmware/stm32_flash.ld @@ -0,0 +1,124 @@ + +ENTRY(Reset_Handler) + +MEMORY { + FLASH (rx): ORIGIN = 0x08000000, LENGTH = 16K + RAM (xrw): ORIGIN = 0x20000000, LENGTH = 4K +} + +/* highest address of the user mode stack */ +_estack = 0x20001000; + +SECTIONS { + /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ + .isr_vector : { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* the program code is stored in the .text section, which goes to Flash */ + .text : { + . = ALIGN(4); + + *(.text) /* normal code */ + *(.text.*) /* -ffunction-sections code */ + *(.rodata) /* read-only data (constants) */ + *(.rodata*) /* -fdata-sections read only data */ + *(.glue_7) /* TBD - needed ? */ + *(.glue_7t) /* TBD - needed ? */ + + /* Necessary KEEP sections (see http://sourceware.org/ml/newlib/2005/msg00255.html) */ + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; + /* This is used by the startup in order to initialize the .data section */ + _sidata = _etext; + } >FLASH + + /* This is the initialized data section + The program executes knowing that the data is in the RAM + but the loader puts the initial values in the FLASH (inidata). + It is one task of the startup to copy the initial values from FLASH to RAM. */ + .data : AT ( _sidata ) { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _sdata = . ; + _data = . ; + + *(.data) + *(.data.*) + *(.RAMtext) + + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _edata = . ; + } >RAM + + /* This is the uninitialized data section */ + .bss : { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; + _bss = .; + + *(.bss) + *(.bss.*) /* patched by elias - allows the use of -fdata-sections */ + *(COMMON) + + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _ebss = . ; + } >RAM + + PROVIDE ( end = _ebss); + PROVIDE (_end = _ebss); + + __exidx_start = .; + __exidx_end = .; + + /* after that it's only debugging information. */ + + /* remove the debugging information from the standard libraries */ + /DISCARD/ : { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/olsndot/firmware/system_stm32f0xx.c b/olsndot/firmware/system_stm32f0xx.c new file mode 100644 index 0000000..c578424 --- /dev/null +++ b/olsndot/firmware/system_stm32f0xx.c @@ -0,0 +1,336 @@ +/** + ****************************************************************************** + * @file system_stm32f0xx.c + * copied from: STM32Cube/Drivers/CMSIS/Device/ST/STM32F0xx/Source/Templates + * @author MCD Application Team + * @version V2.3.1 + * @date 04-November-2016 + * @brief CMSIS Cortex-M0 Device Peripheral Access Layer System Source File. + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32f0xx.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the HSI (8 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f0xx.s" file, to + * configure the system clock before to branch to main program. + * + * 3. This file configures the system clock as follows: + *============================================================================= + * Supported STM32F0xx device + *----------------------------------------------------------------------------- + * System Clock source | HSI + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 8000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 8000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 1 + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + * <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2> + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f0xx_system + * @{ + */ + +/** @addtogroup STM32F0xx_System_Private_Includes + * @{ + */ + +#include "stm32f0xx.h" + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_Defines + * @{ + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz. + This value can be provided and adapted by the user application. */ +#endif /* HSE_VALUE */ + +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz. + This value can be provided and adapted by the user application. */ +#endif /* HSI_VALUE */ + +#if !defined (HSI48_VALUE) +#define HSI48_VALUE ((uint32_t)48000000) /*!< Default value of the HSI48 Internal oscillator in Hz. + This value can be provided and adapted by the user application. */ +#endif /* HSI48_VALUE */ +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_Variables + * @{ + */ + /* This variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetHCLKFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock there is no need to + call the 2 first functions listed above, since SystemCoreClock variable is + updated automatically. + */ +uint32_t SystemCoreClock = 8000000; + +const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; +const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4}; + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F0xx_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system. + * Initialize the default HSI clock source, vector table location and the PLL configuration is reset. + * @param None + * @retval None + */ +void SystemInit(void) +{ + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001U; + +#if defined (STM32F051x8) || defined (STM32F058x8) + /* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE and MCOSEL[2:0] bits */ + RCC->CFGR &= (uint32_t)0xF8FFB80CU; +#else + /* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE, MCOSEL[2:0], MCOPRE[2:0] and PLLNODIV bits */ + RCC->CFGR &= (uint32_t)0x08FFB80CU; +#endif /* STM32F051x8 or STM32F058x8 */ + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFFU; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFFU; + + /* Reset PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */ + RCC->CFGR &= (uint32_t)0xFFC0FFFFU; + + /* Reset PREDIV[3:0] bits */ + RCC->CFGR2 &= (uint32_t)0xFFFFFFF0U; + +#if defined (STM32F072xB) || defined (STM32F078xx) + /* Reset USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW, USBSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFCFE2CU; +#elif defined (STM32F071xB) + /* Reset USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFCEACU; +#elif defined (STM32F091xC) || defined (STM32F098xx) + /* Reset USART3SW[1:0], USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFF0FEACU; +#elif defined (STM32F030x6) || defined (STM32F030x8) || defined (STM32F031x6) || defined (STM32F038xx) || defined (STM32F030xC) + /* Reset USART1SW[1:0], I2C1SW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFEECU; +#elif defined (STM32F051x8) || defined (STM32F058xx) + /* Reset USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFEACU; +#elif defined (STM32F042x6) || defined (STM32F048xx) + /* Reset USART1SW[1:0], I2C1SW, CECSW, USBSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFE2CU; +#elif defined (STM32F070x6) || defined (STM32F070xB) + /* Reset USART1SW[1:0], I2C1SW, USBSW and ADCSW bits */ + RCC->CFGR3 &= (uint32_t)0xFFFFFE6CU; + /* Set default USB clock to PLLCLK, since there is no HSI48 */ + RCC->CFGR3 |= (uint32_t)0x00000080U; +#else + #warning "No target selected" +#endif + + /* Reset HSI14 bit */ + RCC->CR2 &= (uint32_t)0xFFFFFFFEU; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000U; + +} + +/** + * @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/divided by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f0xx_hal.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 stm32f0xx_hal.h file (default value + * 8 MHz), 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, predivfactor = 0; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case RCC_CFGR_SWS_HSI: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case RCC_CFGR_SWS_HSE: /* HSE used as system clock */ + SystemCoreClock = HSE_VALUE; + break; + case RCC_CFGR_SWS_PLL: /* PLL used as system clock */ + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & RCC_CFGR_PLLMUL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + pllmull = ( pllmull >> 18) + 2; + predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1; + + if (pllsource == RCC_CFGR_PLLSRC_HSE_PREDIV) + { + /* HSE used as PLL clock source : SystemCoreClock = HSE/PREDIV * PLLMUL */ + SystemCoreClock = (HSE_VALUE/predivfactor) * pllmull; + } +#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F091xC) || defined(STM32F098xx) + else if (pllsource == RCC_CFGR_PLLSRC_HSI48_PREDIV) + { + /* HSI48 used as PLL clock source : SystemCoreClock = HSI48/PREDIV * PLLMUL */ + SystemCoreClock = (HSI48_VALUE/predivfactor) * pllmull; + } +#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx || STM32F091xC || STM32F098xx */ + else + { +#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6) \ + || defined(STM32F078xx) || defined(STM32F071xB) || defined(STM32F072xB) \ + || defined(STM32F070xB) || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC) + /* HSI used as PLL clock source : SystemCoreClock = HSI/PREDIV * PLLMUL */ + SystemCoreClock = (HSI_VALUE/predivfactor) * pllmull; +#else + /* HSI used as PLL clock source : SystemCoreClock = HSI/2 * PLLMUL */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; +#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 || + STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || + STM32F091xC || STM32F098xx || STM32F030xC */ + } + break; + default: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + } + /* Compute HCLK clock frequency ----------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + |