aboutsummaryrefslogtreecommitdiff
path: root/driver_fw
diff options
context:
space:
mode:
authorjaseg <git@jaseg.net>2019-03-04 23:16:42 +0900
committerjaseg <git@jaseg.net>2019-03-04 23:16:42 +0900
commitd48b92b93507f46ba2623284d8a0841e22e9a09b (patch)
tree902491412a82f8e1d0ddf0fcdcf65bd33477414e /driver_fw
parentca0439cb8ea63e2e1fbd19873b1540b177e31df7 (diff)
download8seg-d48b92b93507f46ba2623284d8a0841e22e9a09b.tar.gz
8seg-d48b92b93507f46ba2623284d8a0841e22e9a09b.tar.bz2
8seg-d48b92b93507f46ba2623284d8a0841e22e9a09b.zip
driver/fw: Beginnings of a firmware
This code starts up and blinks a led. This means RCC, GPIO and SPI1 are working.
Diffstat (limited to 'driver_fw')
-rw-r--r--driver_fw/Makefile17
-rw-r--r--driver_fw/cmsis_exports.c50
-rw-r--r--driver_fw/main.c155
-rw-r--r--driver_fw/openocd.cfg2
-rw-r--r--driver_fw/startup_stm32f103xb.s379
-rw-r--r--driver_fw/stm32_flash.ld259
-rw-r--r--driver_fw/system_stm32f1xx.c438
7 files changed, 267 insertions, 1033 deletions
diff --git a/driver_fw/Makefile b/driver_fw/Makefile
index 5ad3b23..b38bcd3 100644
--- a/driver_fw/Makefile
+++ b/driver_fw/Makefile
@@ -1,7 +1,7 @@
-CUBE_PATH ?= $(wildcard ~)/resource/STM32CubeF1
+CUBE_PATH ?= $(wildcard ~)/resource/STM32Cube_FW_F0_V1.9.0
CMSIS_PATH ?= $(CUBE_PATH)/Drivers/CMSIS
-CMSIS_DEV_PATH ?= $(CMSIS_PATH)/Device/ST/STM32F1xx
-HAL_PATH ?= $(CUBE_PATH)/Drivers/STM32F1xx_HAL_Driver
+CMSIS_DEV_PATH ?= $(CMSIS_PATH)/Device/ST/STM32F0xx
+HAL_PATH ?= $(CUBE_PATH)/Drivers/STM32F0xx_HAL_Driver
CC := arm-none-eabi-gcc
LD := arm-none-eabi-ld
@@ -10,7 +10,7 @@ OBJDUMP := arm-none-eabi-objdump
SIZE := arm-none-eabi-size
CFLAGS = -g -Wall -std=gnu11 -O0 -fdump-rtl-expand -Wno-discarded-qualifiers
-CFLAGS += -mlittle-endian -mcpu=cortex-m3 -mthumb
+CFLAGS += -mlittle-endian -mcpu=cortex-m0 -mthumb
#CFLAGS += -ffunction-sections -fdata-sections
LDFLAGS = -nostartfiles
#LDFLAGS += -specs=rdimon.specs -DSEMIHOSTING
@@ -19,7 +19,10 @@ LDFLAGS += -Wl,-Map=main.map -nostdlib
LIBS = -lgcc
#LIBS += -lrdimon
-CFLAGS += -DSTM32F103xB -DHSE_VALUE=8000000
+# 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 -DHSE_VALUE=8000000
LDFLAGS += -Tstm32_flash.ld
CFLAGS += -I$(CMSIS_DEV_PATH)/Include -I$(CMSIS_PATH)/Include -I$(HAL_PATH)/Inc -Iconfig -I../common
@@ -31,7 +34,7 @@ CFLAGS += -I$(CMSIS_DEV_PATH)/Include -I$(CMSIS_PATH)/Include -I$(HAL_PATH)/Inc
all: main.elf main.pdf
-cmsis_exports.c: $(CMSIS_DEV_PATH)/Include/stm32f103xb.h $(CMSIS_PATH)/Include/core_cm3.h
+cmsis_exports.c: $(CMSIS_DEV_PATH)/Include/stm32f030x6.h $(CMSIS_PATH)/Include/core_cm0.h
python3 gen_cmsis_exports.py $^ > $@
%.o: %.c
@@ -45,7 +48,7 @@ cmsis_exports.c: $(CMSIS_DEV_PATH)/Include/stm32f103xb.h $(CMSIS_PATH)/Include/c
%.dot: %.elf
r2 -a arm -qc 'aa;agC' $< 2>/dev/null >$@
-main.elf: main.o startup_stm32f103xb.o system_stm32f1xx.o $(HAL_PATH)/Src/stm32f1xx_ll_utils.o cmsis_exports.o ../common/8b10b.o
+main.elf: main.o startup_stm32f030x6.o system_stm32f0xx.o $(HAL_PATH)/Src/stm32f0xx_ll_utils.o cmsis_exports.o ../common/8b10b.o
$(CC) $(CFLAGS) $(LDFLAGS) -o $@ $^ $(LIBS)
$(OBJCOPY) -O ihex $@ $(@:.elf=.hex)
$(OBJCOPY) -O binary $@ $(@:.elf=.bin)
diff --git a/driver_fw/cmsis_exports.c b/driver_fw/cmsis_exports.c
index a43fbcf..39874b5 100644
--- a/driver_fw/cmsis_exports.c
+++ b/driver_fw/cmsis_exports.c
@@ -1,62 +1,48 @@
#ifndef __GENERATED_CMSIS_HEADER_EXPORTS__
#define __GENERATED_CMSIS_HEADER_EXPORTS__
-#include <stm32f103xb.h>
+#include <stm32f030x6.h>
-/* stm32f103xb.h */
-TIM_TypeDef *tim2 = TIM2;
+/* stm32f030x6.h */
TIM_TypeDef *tim3 = TIM3;
-TIM_TypeDef *tim4 = TIM4;
+TIM_TypeDef *tim14 = TIM14;
RTC_TypeDef *rtc = RTC;
WWDG_TypeDef *wwdg = WWDG;
IWDG_TypeDef *iwdg = IWDG;
-SPI_TypeDef *spi2 = SPI2;
-USART_TypeDef *usart2 = USART2;
-USART_TypeDef *usart3 = USART3;
I2C_TypeDef *i2c1 = I2C1;
-I2C_TypeDef *i2c2 = I2C2;
-USB_TypeDef *usb = USB;
-CAN_TypeDef *can1 = CAN1;
-BKP_TypeDef *bkp = BKP;
PWR_TypeDef *pwr = PWR;
-AFIO_TypeDef *afio = AFIO;
+SYSCFG_TypeDef *syscfg = SYSCFG;
EXTI_TypeDef *exti = EXTI;
-GPIO_TypeDef *gpioa = GPIOA;
-GPIO_TypeDef *gpiob = GPIOB;
-GPIO_TypeDef *gpioc = GPIOC;
-GPIO_TypeDef *gpiod = GPIOD;
-GPIO_TypeDef *gpioe = GPIOE;
ADC_TypeDef *adc1 = ADC1;
-ADC_TypeDef *adc2 = ADC2;
-ADC_Common_TypeDef *adc12_common = ADC12_COMMON;
+ADC_Common_TypeDef *adc1_common = ADC1_COMMON;
+ADC_Common_TypeDef *adc = ADC;
TIM_TypeDef *tim1 = TIM1;
SPI_TypeDef *spi1 = SPI1;
USART_TypeDef *usart1 = USART1;
-SDIO_TypeDef *sdio = SDIO;
+TIM_TypeDef *tim16 = TIM16;
+TIM_TypeDef *tim17 = TIM17;
+DBGMCU_TypeDef *dbgmcu = DBGMCU;
DMA_TypeDef *dma1 = DMA1;
DMA_Channel_TypeDef *dma1_channel1 = DMA1_Channel1;
DMA_Channel_TypeDef *dma1_channel2 = DMA1_Channel2;
DMA_Channel_TypeDef *dma1_channel3 = DMA1_Channel3;
DMA_Channel_TypeDef *dma1_channel4 = DMA1_Channel4;
DMA_Channel_TypeDef *dma1_channel5 = DMA1_Channel5;
-DMA_Channel_TypeDef *dma1_channel6 = DMA1_Channel6;
-DMA_Channel_TypeDef *dma1_channel7 = DMA1_Channel7;
-RCC_TypeDef *rcc = RCC;
-CRC_TypeDef *crc = CRC;
FLASH_TypeDef *flash = FLASH;
OB_TypeDef *ob = OB;
-DBGMCU_TypeDef *dbgmcu = DBGMCU;
+RCC_TypeDef *rcc = RCC;
+CRC_TypeDef *crc = CRC;
+GPIO_TypeDef *gpioa = GPIOA;
+GPIO_TypeDef *gpiob = GPIOB;
+GPIO_TypeDef *gpioc = GPIOC;
+GPIO_TypeDef *gpiod = GPIOD;
+GPIO_TypeDef *gpiof = GPIOF;
-#include <core_cm3.h>
+#include <core_cm0.h>
-/* core_cm3.h */
-SCnSCB_Type *scnscb = SCnSCB;
+/* core_cm0.h */
SCB_Type *scb = SCB;
SysTick_Type *systick = SysTick;
NVIC_Type *nvic = NVIC;
-ITM_Type *itm = ITM;
-DWT_Type *dwt = DWT;
-TPI_Type *tpi = TPI;
-CoreDebug_Type *coredebug = CoreDebug;
#endif//__GENERATED_CMSIS_HEADER_EXPORTS__
diff --git a/driver_fw/main.c b/driver_fw/main.c
index 730065c..c16d200 100644
--- a/driver_fw/main.c
+++ b/driver_fw/main.c
@@ -2,10 +2,11 @@
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wstrict-aliasing"
-#include <stm32f1xx.h>
+#include <stm32f0xx.h>
#pragma GCC diagnostic pop
-#include <system_stm32f1xx.h>
+#include <system_stm32f0xx.h>
+#include <stm32f0xx_ll_spi.h>
#include <stdint.h>
#include <stdbool.h>
@@ -29,48 +30,120 @@ static volatile struct {
#define NO_SYMBOL (DECODER_RETURN_CODE_LAST + 1)
+unsigned char random() {
+ static unsigned char x, a, b, c;
+ x++; //x is incremented every round and is not affected by any other variable
+ a = (a ^ c ^ x); //note the mix of addition and XOR
+ b = (b + a); //And the use of very few instructions
+ c = ((c + ((b >> 1) ^ a))); // the AES S-Box Operation ensures an even distributon of entropy
+ return c;
+}
+
+enum STATUS_LEDS {
+ STATUS_LED_COMM = 1,
+ STATUS_LED_ERROR = 2,
+ STATUS_LED_LOAD = 4,
+ STATUS_LED_OPERATION = 8,
+ STATUS_LED_J5_GREEN = 16,
+ STATUS_LED_J5_YELLOW = 32,
+ STATUS_LED_J4_GREEN = 64,
+ STATUS_LED_J4_YELLOW = 128
+};
+
+static void set_status_leds(uint8_t val) {
+ /* Workaround for *nasty* hardware behavior: If SPI data width is configured as 8 bit but DR is written as 16
+ * bit, SPI actually sends 16 clock cycles. Thus, we have to make sure the compiler emits a 8-bit write here.
+ * Thanks, TI! */
+ *((volatile uint8_t *)&(SPI1->DR)) = val ^ 0x0f; /* Invert LEDs connected to VCC instead of GND */
+}
+
+
int main(void) {
- /* External crystal: 8MHz */
RCC->CR |= RCC_CR_HSEON;
while (!(RCC->CR&RCC_CR_HSERDY));
-
- /* Sysclk = HCLK = 48MHz */
- RCC->CFGR = (RCC->CFGR & (~RCC_CFGR_PLLMULL_Msk & ~RCC_CFGR_SW_Msk & ~RCC_CFGR_PPRE1_Msk & ~RCC_CFGR_PPRE2_Msk &
- ~RCC_CFGR_HPRE_Msk))
- | (10<<RCC_CFGR_PLLMULL_Pos) | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | (4<<RCC_CFGR_PPRE1_Pos) |
- (4<<RCC_CFGR_PPRE2_Pos);
-
+ RCC->CFGR &= ~RCC_CFGR_PLLMUL_Msk & ~RCC_CFGR_SW_Msk & ~RCC_CFGR_PPRE_Msk & ~RCC_CFGR_HPRE_Msk;
+ RCC->CFGR |= ((6-2)<<RCC_CFGR_PLLMUL_Pos) | RCC_CFGR_PLLSRC_HSE_PREDIV; /* PLL x6 -> 48.0MHz */
RCC->CR |= RCC_CR_PLLON;
while (!(RCC->CR&RCC_CR_PLLRDY));
-
- /* Switch to PLL */
RCC->CFGR |= (2<<RCC_CFGR_SW_Pos);
- //RCC->CFGR = (RCC->CFGR & (~RCC_CFGR_PPRE1_Msk & ~RCC_CFGR_PPRE2_Msk))
- // | (4<<RCC_CFGR_PPRE1_Pos) | (4<<RCC_CFGR_PPRE2_Pos);
- SystemCoreClockUpdate();
-
- RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_TIM1EN;
+ RCC->AHBENR |= RCC_AHBENR_DMAEN | RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_FLITFEN;
+ RCC->APB1ENR |= RCC_APB1ENR_TIM3EN | RCC_APB1ENR_PWREN | RCC_APB1ENR_I2C1EN;
+ RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN | RCC_APB2ENR_ADCEN| RCC_APB2ENR_DBGMCUEN | RCC_APB2ENR_USART1EN | RCC_APB2ENR_SPI1EN;
- GPIOA->CRH =
- (2<<GPIO_CRH_CNF8_Pos) | (1<<GPIO_CRH_MODE8_Pos); /* PA8 - low side */
-
- GPIOB->CRH =
- (2<<GPIO_CRH_CNF13_Pos) | (1<<GPIO_CRH_MODE13_Pos); /* PB13 - high side */
-
- GPIOC->CRH =
- (0<<GPIO_CRH_CNF13_Pos) | (1<<GPIO_CRH_MODE13_Pos); /* PC13 - LED */
-
- /* TIM1 running off 24MHz APB2 clk, T=41.667ns */
- TIM1->CR1 = 0; /* Disable ARR preload (double-buffering) */
- TIM1->PSC = 24-1; /* Prescaler 24 -> f=1MHz/T=1us */
- TIM1->DIER = TIM_DIER_UIE; /* Enable update (overflow) interrupt */
- TIM1->CCMR1 = 6<<TIM_CCMR1_OC1M_Pos | TIM_CCMR1_OC1PE; /* Configure output compare unit 1 to PWM mode 1, enable CCR1
+ SystemCoreClockUpdate();
+ SysTick_Config(SystemCoreClock/100); /* 10ms interval */
+ NVIC_EnableIRQ(SysTick_IRQn);
+ NVIC_SetPriority(SysTick_IRQn, 3<<5);
+
+ GPIOA->MODER |=
+ (3<<GPIO_MODER_MODER0_Pos) /* PA0 - Vboot to ADC */
+ | (2<<GPIO_MODER_MODER1_Pos) /* PA1 - RS485 DE */
+ | (2<<GPIO_MODER_MODER2_Pos) /* PA2 - RS485 TX */
+ | (2<<GPIO_MODER_MODER3_Pos) /* PA3 - RS485 RX */
+ | (1<<GPIO_MODER_MODER4_Pos) /* PA4 - Strobe/Vin to ADC. CAUTION: This pin is dual-use */
+ | (2<<GPIO_MODER_MODER5_Pos) /* PA5 - SCK */
+ | (2<<GPIO_MODER_MODER6_Pos) /* PA6 - CTRL_A to TIM 3 ch 1 */
+ | (2<<GPIO_MODER_MODER7_Pos) /* PA7 - MOSI */
+ | (2<<GPIO_MODER_MODER9_Pos) /* PA9 - SCL */
+ | (2<<GPIO_MODER_MODER10_Pos);/* PA10 - SDA */
+
+ GPIOA->AFR[0] =
+ (1<<GPIO_AFRL_AFSEL1_Pos) /* PA1 */
+ | (1<<GPIO_AFRL_AFSEL2_Pos) /* PA2 */
+ | (1<<GPIO_AFRL_AFSEL3_Pos) /* PA3 */
+ | (1<<GPIO_AFRL_AFSEL6_Pos); /* PA6 */
+ GPIOA->AFR[1] =
+ (4<<GPIO_AFRH_AFSEL9_Pos) /* PA9 */
+ | (4<<GPIO_AFRH_AFSEL10_Pos);/* PA10 */
+
+ GPIOA->ODR = 0; /* Set PA4 ODR to 0 */
+
+ GPIOB->MODER |=
+ (2<<GPIO_MODER_MODER1_Pos); /* PB1 - CTRL_B to TIM 3 ch 4 */
+
+ GPIOB->AFR[0] = (1<<GPIO_AFRL_AFSEL1_Pos); /* PB1 */
+
+ /* FIXME USART config */
+ /* FIXME ADC config */
+ /* FIXME I2C config */
+
+ /* SPI config. SPI1 is used to control the shift register controlling the eight status LEDs. */
+ SPI1->CR2 = (7<<SPI_CR2_DS_Pos);
+
+ /* Baud rate PCLK/128 -> 375.0kHz */
+ SPI1->CR1 =
+ SPI_CR1_SSM
+ | SPI_CR1_SSI
+ | (6<<SPI_CR1_BR_Pos)
+ | SPI_CR1_MSTR
+ | SPI_CR1_CPHA;
+ SPI1->CR1 |= SPI_CR1_SPE;
+
+ /* FIXME debug code */
+ for (;;) {
+ set_status_leds((sys_time & (1<<6)) ? STATUS_LED_OPERATION : 0);
+
+ /* Toggle strobe */
+ GPIOA->BSRR = 1<<4;
+ for (int j = 0; j<100; j++)
+ asm volatile ("nop");
+ GPIOA->BRR = 1<<4;
+
+ for (int j = 0; j<100000; j++)
+ asm volatile ("nop");
+ }
+#if 0
+ /* TIM3 running off 48MHz APB1 clk, T=20.833ns */
+ TIM3->CR1 = 0; /* Disable ARR preload (double-buffering) */
+ TIM3->PSC = 48-1; /* Prescaler 48 -> f=1MHz/T=1us */
+ TIM3->DIER = TIM_DIER_UIE; /* Enable update (overflow) interrupt */
+ TIM3->CCMR1 = 6<<TIM_CCMR1_OC1M_Pos | TIM_CCMR1_OC1PE; /* Configure output compare unit 1 to PWM mode 1, enable CCR1
preload */
- TIM1->CCER = TIM_CCER_CC1NE | TIM_CCER_CC1E; /* Confiugre CH1 to complementary outputs */
- TIM1->BDTR = TIM_BDTR_MOE | (0xc0 | (63-32))<<TIM_BDTR_DTG_Pos; /* Enable MOE on next update event, i.e. on initial timer load.
+ TIM3->CCER = TIM_CCER_CC1NE | TIM_CCER_CC1E; /* Confiugre CH1 to complementary outputs */
+ TIM3->BDTR = TIM_BDTR_MOE | (0xc0 | (63-32))<<TIM_BDTR_DTG_Pos; /* Enable MOE on next update event, i.e. on initial timer load.
Set dead-time to 100us. */
- TIM1->CR1 |= TIM_CR1_CEN;
- TIM1->ARR = 400-1; /* Set f=2.5kHz/T=0.4ms */
+ TIM3->CR1 |= TIM_CR1_CEN;
+ TIM3->ARR = 800-1; /* Set f=2.5kHz/T=0.4ms */
xfr_8b10b_encode_reset(&txstate.st);
txstate.current_symbol = txstate.next_symbol = xfr_8b10b_encode(&txstate.st, K28_1) | 1<<10;
@@ -79,17 +152,6 @@ int main(void) {
NVIC_EnableIRQ(TIM1_UP_IRQn);
NVIC_SetPriority(TIM1_UP_IRQn, 3<<4);
-
-unsigned char x, a, b, c;
-unsigned char random() {
- x++; //x is incremented every round and is not affected by any other variable
- a = (a ^ c ^ x); //note the mix of addition and XOR
- b = (b + a); //And the use of very few instructions
- c = ((c + (b >> 1) ^ a)); // the AES S-Box Operation ensures an even distributon of entropy
- return (c);
-}
-
-
uint8_t txbuf[3] = {0x01, 0x05, 0x01};
int txpos = -1;
/* FIXME test code */
@@ -119,6 +181,7 @@ unsigned char random() {
}
}
}
+#endif
}
int flipbits(int in) {
diff --git a/driver_fw/openocd.cfg b/driver_fw/openocd.cfg
index f8b4766..97a3a05 100644
--- a/driver_fw/openocd.cfg
+++ b/driver_fw/openocd.cfg
@@ -5,7 +5,7 @@ source [find interface/stlink-v2.cfg]
#hla_serial "000000000001"
transport select hla_swd
-source [find target/stm32f1x.cfg]
+source [find target/stm32f0x.cfg]
#adapter_khz 10000
init
diff --git a/driver_fw/startup_stm32f103xb.s b/driver_fw/startup_stm32f103xb.s
deleted file mode 100644
index 1bdd524..0000000
--- a/driver_fw/startup_stm32f103xb.s
+++ /dev/null
@@ -1,379 +0,0 @@
-/**
- *************** (C) COPYRIGHT 2017 STMicroelectronics ************************
- * @file startup_stm32f103xb.s
- * @author MCD Application Team
- * @version V4.2.0
- * @date 31-March-2017
- * @brief STM32F103xB Devices vector table for Atollic toolchain.
- * This module performs:
- * - Set the initial SP
- * - Set the initial PC == Reset_Handler,
- * - Set the vector table entries with the exceptions ISR address
- * - Configure the clock system
- * - Branches to main in the C library (which eventually
- * calls main()).
- * After Reset the Cortex-M3 processor is in Thread mode,
- * priority is Privileged, and the Stack is set to Main.
- ******************************************************************************
- *
- * <h2><center>&copy; COPYRIGHT(c) 2017 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.
- *
- ******************************************************************************
- */
-
- .syntax unified
- .cpu cortex-m3
- .fpu softvfp
- .thumb
-
-.global g_pfnVectors
-.global Default_Handler
-
-/* start address for the initialization values of the .data section.
-defined in linker script */
-.word _sidata
-/* start address for the .data section. defined in linker script */
-.word _sdata
-/* end address for the .data section. defined in linker script */
-.word _edata
-/* start address for the .bss section. defined in linker script */
-.word _sbss
-/* end address for the .bss section. defined in linker script */
-.word _ebss
-
-.equ BootRAM, 0xF108F85F
-/**
- * @brief This is the code that gets called when the processor first
- * starts execution following a reset event. Only the absolutely
- * necessary set is performed, after which the application
- * supplied main() routine is called.
- * @param None
- * @retval : None
-*/
-
- .section .text.Reset_Handler
- .weak Reset_Handler
- .type Reset_Handler, %function
-Reset_Handler:
-
-/* Copy the data segment initializers from flash to SRAM */
- movs r1, #0
- b LoopCopyDataInit
-
-CopyDataInit:
- ldr r3, =_sidata
- ldr r3, [r3, r1]
- str r3, [r0, r1]
- adds r1, r1, #4
-
-LoopCopyDataInit:
- ldr r0, =_sdata
- ldr r3, =_edata
- adds r2, r0, r1
- cmp r2, r3
- bcc CopyDataInit
- ldr r2, =_sbss
- b LoopFillZerobss
-/* Zero fill the bss segment. */
-FillZerobss:
- movs r3, #0
- str r3, [r2], #4
-
-LoopFillZerobss:
- ldr r3, = _ebss
- cmp r2, r3
- bcc FillZerobss
-
-/* Call the clock system intitialization function.*/
- bl SystemInit
-/* Call static constructors */
- bl __libc_init_array
-/* Call the application's entry point.*/
- bl main
- bx lr
-.size Reset_Handler, .-Reset_Handler
-
-/**
- * @brief This is the code that gets called when the processor receives an
- * unexpected interrupt. This simply enters an infinite loop, preserving
- * the system state for examination by a debugger.
- *
- * @param None
- * @retval : None
-*/
- .section .text.Default_Handler,"ax",%progbits
-Default_Handler:
-Infinite_Loop:
- b Infinite_Loop
- .size Default_Handler, .-Default_Handler
-/******************************************************************************
-*
-* The minimal vector table for a Cortex M3. Note that the proper constructs
-* must be placed on this to ensure that it ends up at physical address
-* 0x0000.0000.
-*
-******************************************************************************/
- .section .isr_vector,"a",%progbits
- .type g_pfnVectors, %object
- .size g_pfnVectors, .-g_pfnVectors
-
-
-g_pfnVectors:
-
- .word _estack
- .word Reset_Handler
- .word NMI_Handler
- .word HardFault_Handler
- .word MemManage_Handler
- .word BusFault_Handler
- .word UsageFault_Handler
- .word 0
- .word 0
- .word 0
- .word 0
- .word SVC_Handler
- .word DebugMon_Handler
- .word 0
- .word PendSV_Handler
- .word SysTick_Handler
- .word WWDG_IRQHandler
- .word PVD_IRQHandler
- .word TAMPER_IRQHandler
- .word RTC_IRQHandler
- .word FLASH_IRQHandler
- .word RCC_IRQHandler
- .word EXTI0_IRQHandler
- .word EXTI1_IRQHandler
- .word EXTI2_IRQHandler
- .word EXTI3_IRQHandler
- .word EXTI4_IRQHandler
- .word DMA1_Channel1_IRQHandler
- .word DMA1_Channel2_IRQHandler
- .word DMA1_Channel3_IRQHandler
- .word DMA1_Channel4_IRQHandler
- .word DMA1_Channel5_IRQHandler
- .word DMA1_Channel6_IRQHandler
- .word DMA1_Channel7_IRQHandler
- .word ADC1_2_IRQHandler
- .word USB_HP_CAN1_TX_IRQHandler
- .word USB_LP_CAN1_RX0_IRQHandler
- .word CAN1_RX1_IRQHandler
- .word CAN1_SCE_IRQHandler
- .word EXTI9_5_IRQHandler
- .word TIM1_BRK_IRQHandler
- .word TIM1_UP_IRQHandler
- .word TIM1_TRG_COM_IRQHandler
- .word TIM1_CC_IRQHandler
- .word TIM2_IRQHandler
- .word TIM3_IRQHandler
- .word TIM4_IRQHandler
- .word I2C1_EV_IRQHandler
- .word I2C1_ER_IRQHandler
- .word I2C2_EV_IRQHandler
- .word I2C2_ER_IRQHandler
- .word SPI1_IRQHandler
- .word SPI2_IRQHandler
- .word USART1_IRQHandler
- .word USART2_IRQHandler
- .word USART3_IRQHandler
- .word EXTI15_10_IRQHandler
- .word RTC_Alarm_IRQHandler
- .word USBWakeUp_IRQHandler
- .word 0
- .word 0
- .word 0
- .word 0
- .word 0
- .word 0
- .word 0
- .word BootRAM /* @0x108. This is for boot in RAM mode for
- STM32F10x Medium Density devices. */
-
-/*******************************************************************************
-*
-* Provide weak aliases for each Exception handler to the Default_Handler.
-* As they are weak aliases, any function with the same name will override
-* this definition.
-*
-*******************************************************************************/
-
- .weak NMI_Handler
- .thumb_set NMI_Handler,Default_Handler
-
- .weak HardFault_Handler
- .thumb_set HardFault_Handler,Default_Handler
-
- .weak MemManage_Handler
- .thumb_set MemManage_Handler,Default_Handler
-
- .weak BusFault_Handler
- .thumb_set BusFault_Handler,Default_Handler
-
- .weak UsageFault_Handler
- .thumb_set UsageFault_Handler,Default_Handler
-
- .weak SVC_Handler
- .thumb_set SVC_Handler,Default_Handler
-
- .weak DebugMon_Handler
- .thumb_set DebugMon_Handler,Default_Handler
-
- .weak PendSV_Handler
- .thumb_set PendSV_Handler,Default_Handler
-
- .weak SysTick_Handler
- .thumb_set SysTick_Handler,Default_Handler
-
- .weak WWDG_IRQHandler
- .thumb_set WWDG_IRQHandler,Default_Handler
-
- .weak PVD_IRQHandler
- .thumb_set PVD_IRQHandler,Default_Handler
-
- .weak TAMPER_IRQHandler
- .thumb_set TAMPER_IRQHandler,Default_Handler
-
- .weak RTC_IRQHandler
- .thumb_set RTC_IRQHandler,Default_Handler
-
- .weak FLASH_IRQHandler
- .thumb_set FLASH_IRQHandler,Default_Handler
-
- .weak RCC_IRQHandler
- .thumb_set RCC_IRQHandler,Default_Handler
-
- .weak EXTI0_IRQHandler
- .thumb_set EXTI0_IRQHandler,Default_Handler
-
- .weak EXTI1_IRQHandler
- .thumb_set EXTI1_IRQHandler,Default_Handler
-
- .weak EXTI2_IRQHandler
- .thumb_set EXTI2_IRQHandler,Default_Handler
-
- .weak EXTI3_IRQHandler
- .thumb_set EXTI3_IRQHandler,Default_Handler
-
- .weak EXTI4_IRQHandler
- .thumb_set EXTI4_IRQHandler,Default_Handler
-
- .weak DMA1_Channel1_IRQHandler
- .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
-
- .weak DMA1_Channel2_IRQHandler
- .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
-
- .weak DMA1_Channel3_IRQHandler
- .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
-
- .weak DMA1_Channel4_IRQHandler
- .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
-
- .weak DMA1_Channel5_IRQHandler
- .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
-
- .weak DMA1_Channel6_IRQHandler
- .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
-
- .weak DMA1_Channel7_IRQHandler
- .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
-
- .weak ADC1_2_IRQHandler
- .thumb_set ADC1_2_IRQHandler,Default_Handler
-
- .weak USB_HP_CAN1_TX_IRQHandler
- .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
-
- .weak USB_LP_CAN1_RX0_IRQHandler
- .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
-
- .weak CAN1_RX1_IRQHandler
- .thumb_set CAN1_RX1_IRQHandler,Default_Handler
-
- .weak CAN1_SCE_IRQHandler
- .thumb_set CAN1_SCE_IRQHandler,Default_Handler
-
- .weak EXTI9_5_IRQHandler
- .thumb_set EXTI9_5_IRQHandler,Default_Handler
-
- .weak TIM1_BRK_IRQHandler
- .thumb_set TIM1_BRK_IRQHandler,Default_Handler
-
- .weak TIM1_UP_IRQHandler
- .thumb_set TIM1_UP_IRQHandler,Default_Handler
-
- .weak TIM1_TRG_COM_IRQHandler
- .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
-
- .weak TIM1_CC_IRQHandler
- .thumb_set TIM1_CC_IRQHandler,Default_Handler
-
- .weak TIM2_IRQHandler
- .thumb_set TIM2_IRQHandler,Default_Handler
-
- .weak TIM3_IRQHandler
- .thumb_set TIM3_IRQHandler,Default_Handler
-
- .weak TIM4_IRQHandler
- .thumb_set TIM4_IRQHandler,Default_Handler
-
- .weak I2C1_EV_IRQHandler
- .thumb_set I2C1_EV_IRQHandler,Default_Handler
-
- .weak I2C1_ER_IRQHandler
- .thumb_set I2C1_ER_IRQHandler,Default_Handler
-
- .weak I2C2_EV_IRQHandler
- .thumb_set I2C2_EV_IRQHandler,Default_Handler
-
- .weak I2C2_ER_IRQHandler
- .thumb_set I2C2_ER_IRQHandler,Default_Handler
-
- .weak SPI1_IRQHandler
- .thumb_set SPI1_IRQHandler,Default_Handler
-
- .weak SPI2_IRQHandler
- .thumb_set SPI2_IRQHandler,Default_Handler
-
- .weak USART1_IRQHandler
- .thumb_set USART1_IRQHandler,Default_Handler
-
- .weak USART2_IRQHandler
- .thumb_set USART2_IRQHandler,Default_Handler
-
- .weak USART3_IRQHandler
- .thumb_set USART3_IRQHandler,Default_Handler
-
- .weak EXTI15_10_IRQHandler
- .thumb_set EXTI15_10_IRQHandler,Default_Handler
-
- .weak RTC_Alarm_IRQHandler
- .thumb_set RTC_Alarm_IRQHandler,Default_Handler
-
- .weak USBWakeUp_IRQHandler
- .thumb_set USBWakeUp_IRQHandler,Default_Handler
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
-
diff --git a/driver_fw/stm32_flash.ld b/driver_fw/stm32_flash.ld
index ec1b5a7..cba7577 100644
--- a/driver_fw/stm32_flash.ld
+++ b/driver_fw/stm32_flash.ld
@@ -1,137 +1,136 @@
-/* Entry Point */
-ENTRY(Reset_Handler)
-
-/* Highest address of the user mode stack */
-_estack = 0x20004FFF; /* end of RAM */
-/* Generate a link error if heap and stack don't fit into RAM */
-_Min_Heap_Size = 0x200; /* required amount of heap */
-_Min_Stack_Size = 0x400; /* required amount of stack */
+ENTRY(Reset_Handler)
-/* Specify the memory areas */
-MEMORY
-{
-FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 64K
-RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K
+MEMORY {
+ FLASH (rx): ORIGIN = 0x08000000, LENGTH = 0x3C00
+ CONFIGFLASH (rw): ORIGIN = 0x08003C00, LENGTH = 0x400
+ RAM (xrw): ORIGIN = 0x20000000, LENGTH = 4K
}
-/* Define output sections */
-SECTIONS
-{
- /* The startup code goes first into FLASH */
- .isr_vector :
- {
- . = ALIGN(4);
- KEEP(*(.isr_vector)) /* Startup code */
- . = ALIGN(4);
- } >FLASH
-
- /* The program code and other data goes into FLASH */
- .text :
- {
- . = ALIGN(4);
- *(.text) /* .text sections (code) */
- *(.text*) /* .text* sections (code) */
- *(.glue_7) /* glue arm to thumb code */
- *(.glue_7t) /* glue thumb to arm code */
- *(.eh_frame)
-
- KEEP (*(.init))
- KEEP (*(.fini))
-
- . = ALIGN(4);
- _etext = .; /* define a global symbols at end of code */
- } >FLASH
-
- /* Constant data goes into FLASH */
- .rodata :
- {
- . = ALIGN(4);
- *(.rodata) /* .rodata sections (constants, strings, etc.) */
- *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
- . = ALIGN(4);
- } >FLASH
-
- .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
- .ARM : {
+/* 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 ? */
+
+ *(.source_tarball)
+
+ /* Necessary KEEP sections (see http://sourceware.org/ml/newlib/2005/msg00255.html) */
+ KEEP (*(.init))
+ KEEP (*(.fini))
+ KEEP (*(.source_tarball))
+
+ . = ALIGN(4);
+ _etext = .;
+ /* This is used by the startup in order to initialize the .data section */
+ _sidata = _etext;
+ } >FLASH
+
+ /*
+ .configflash : {
+ . = ALIGN(0x400);
+ *(.configdata)
+ _econfig = .;
+ } >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 = .;
- *(.ARM.exidx*)
__exidx_end = .;
- } >FLASH
-
- .preinit_array :
- {
- PROVIDE_HIDDEN (__preinit_array_start = .);
- KEEP (*(.preinit_array*))
- PROVIDE_HIDDEN (__preinit_array_end = .);
- } >FLASH
- .init_array :
- {
- PROVIDE_HIDDEN (__init_array_start = .);
- KEEP (*(SORT(.init_array.*)))
- KEEP (*(.init_array*))
- PROVIDE_HIDDEN (__init_array_end = .);
- } >FLASH
- .fini_array :
- {
- PROVIDE_HIDDEN (__fini_array_start = .);
- KEEP (*(SORT(.fini_array.*)))
- KEEP (*(.fini_array*))
- PROVIDE_HIDDEN (__fini_array_end = .);
- } >FLASH
-
- /* used by the startup to initialize data */
- _sidata = LOADADDR(.data);
-
- /* Initialized data sections goes into RAM, load LMA copy after code */
- .data :
- {
- . = ALIGN(4);
- _sdata = .; /* create a global symbol at data start */
- *(.data) /* .data sections */
- *(.data*) /* .data* sections */
-
- . = ALIGN(4);
- _edata = .; /* define a global symbol at data end */
- } >RAM AT> FLASH
-
-
- /* Uninitialized data section */
- . = ALIGN(4);
- .bss :
- {
- /* This is used by the startup in order to initialize the .bss secion */
- _sbss = .; /* define a global symbol at bss start */
- __bss_start__ = _sbss;
- *(.bss)
- *(.bss*)
- *(COMMON)
-
- . = ALIGN(4);
- _ebss = .; /* define a global symbol at bss end */
- __bss_end__ = _ebss;
- } >RAM
-
- /* User_heap_stack section, used to check that there is enough RAM left */
- ._user_heap_stack :
- {
- . = ALIGN(4);
- PROVIDE ( end = . );
- PROVIDE ( _end = . );
- . = . + _Min_Heap_Size;
- . = . + _Min_Stack_Size;
- . = ALIGN(4);
- } >RAM
-
-
-
- /* Remove information from the standard libraries */
- /DISCARD/ :
- {
- libc.a ( * )
- libm.a ( * )
- libgcc.a ( * )
- }
-
- .ARM.attributes 0 : { *(.ARM.attributes) }
+
+ /* 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/driver_fw/system_stm32f1xx.c b/driver_fw/system_stm32f1xx.c
deleted file mode 100644
index ff7aa57..0000000
--- a/driver_fw/system_stm32f1xx.c
+++ /dev/null
@@ -1,438 +0,0 @@
-/**
- ******************************************************************************
- * @file system_stm32f1xx.c
- * @author MCD Application Team
- * @version V1.5.0
- * @date 14-April-2017
- * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Source File.
- *
- * 1. This file provides two functions and one global variable to be called from
- * user application:
- * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
- * factors, AHB/APBx prescalers and Flash settings).
- * This function is called at startup just after reset and
- * before branch to main program. This call is made inside
- * the "startup_stm32f1xx_xx.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_stm32f1xx_xx.s" file, to
- * configure the system clock before to branch to main program.
- *
- * 4. The default value of HSE crystal is set to 8 MHz (or 25 MHz, depending on
- * the product used), refer to "HSE_VALUE".
- * When HSE is used as system clock source, directly or through PLL, and you
- * are using different crystal you have to adapt the HSE value to your own
- * configuration.
- *
- ******************************************************************************
- * @attention
- *
- * <h2><center>&copy; 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 stm32f1xx_system
- * @{
- */
-
-/** @addtogroup STM32F1xx_System_Private_Includes
- * @{
- */
-
-#include "stm32f1xx.h"
-
-/**
- * @}
- */
-
-/** @addtogroup STM32F1xx_System_Private_TypesDefinitions
- * @{
- */
-
-/**
- * @}
- */
-
-/** @addtogroup STM32F1xx_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 */
-
-/*!< Uncomment the following line if you need to use external SRAM */
-#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
-/* #define DATA_IN_ExtSRAM */
-#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */
-
-/*!< Uncomment the following line if you need to relocate your vector Table in
- Internal SRAM. */
-/* #define VECT_TAB_SRAM */
-#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
- This value must be a multiple of 0x200. */
-
-
-/**
- * @}
- */
-
-/** @addtogroup STM32F1xx_System_Private_Macros
- * @{
- */
-
-/**
- * @}
- */
-
-/** @addtogroup STM32F1xx_System_Private_Variables
- * @{
- */
-
-/*******************************************************************************
-* Clock Definitions
-*******************************************************************************/
-#if defined(STM32F100xB) ||defined(STM32F100xE)
- uint32_t SystemCoreClock = 24000000; /*!< System Clock Frequency (Core Clock) */
-#else /*!< HSI Selected as System Clock source */
- uint32_t SystemCoreClock = 72000000; /*!< System Clock Frequency (Core Clock) */
-#endif
-
-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 STM32F1xx_System_Private_FunctionPrototypes
- * @{
- */
-
-#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
-#ifdef DATA_IN_ExtSRAM
- static void SystemInit_ExtMemCtl(void);
-#endif /* DATA_IN_ExtSRAM */
-#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */
-
-/**
- * @}
- */
-
-/** @addtogroup STM32F1xx_System_Private_Functions
- * @{
- */
-
-/**
- * @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) */
- /* Set HSION bit */
- RCC->CR |= (uint32_t)0x00000001;
-
- /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
-#if !defined(STM32F105xC) && !defined(STM32F107xC)
- RCC->CFGR &= (uint32_t)0xF8FF0000;
-#else
- RCC->CFGR &= (uint32_t)0xF0FF0000;
-#endif /* STM32F105xC */
-
- /* Reset HSEON, CSSON and PLLON bits */
- RCC->CR &= (uint32_t)0xFEF6FFFF;
-
- /* Reset HSEBYP bit */
- RCC->CR &= (uint32_t)0xFFFBFFFF;
-
- /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */
- RCC->CFGR &= (uint32_t)0xFF80FFFF;
-
-#if defined(STM32F105xC) || defined(STM32F107xC)
- /* Reset PLL2ON and PLL3ON bits */
- RCC->CR &= (uint32_t)0xEBFFFFFF;
-
- /* Disable all interrupts and clear pending bits */
- RCC->CIR = 0x00FF0000;
-
- /* Reset CFGR2 register */
- RCC->CFGR2 = 0x00000000;
-#elif defined(STM32F100xB) || defined(STM32F100xE)
- /* Disable all interrupts and clear pending bits */
- RCC->CIR = 0x009F0000;
-
- /* Reset CFGR2 register */
- RCC->CFGR2 = 0x00000000;
-#else
- /* Disable all interrupts and clear pending bits */
- RCC->CIR = 0x009F0000;
-#endif /* STM32F105xC */
-
-#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
- #ifdef DATA_IN_ExtSRAM
- SystemInit_ExtMemCtl();
- #endif /* DATA_IN_ExtSRAM */
-#endif
-
-#ifdef VECT_TAB_SRAM
- SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
-#else
- SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
-#endif
-}
-
-/**
- * @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, depending 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;
-
-#if defined(STM32F105xC) || defined(STM32F107xC)
- uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0;
-#endif /* STM32F105xC */
-
-#if defined(STM32F100xB) || defined(STM32F100xE)
- uint32_t prediv1factor = 0;
-#endif /* STM32F100xB or STM32F100xE */
-
- /* 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 ----------------------*/
- pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
- pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
-
-#if !defined(STM32F105xC) && !defined(STM32F107xC)
- pllmull = ( pllmull >> 18) + 2;
-
- if (pllsource == 0x00)
- {
- /* HSI oscillator clock divided by 2 selected as PLL clock entry */
- SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
- }
- else
- {
- #if defined(STM32F100xB) || defined(STM32F100xE)
- prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
- /* HSE oscillator clock selected as PREDIV1 clock entry */
- SystemCoreClock = (HSE_VALUE / prediv1factor) * 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;
- }
- #endif
- }
-#else
- pllmull = pllmull >> 18;
-
- if (pllmull != 0x0D)
- {
- pllmull += 2;
- }
- else
- { /* PLL multiplication factor = PLL input clock * 6.5 */
- pllmull = 13 / 2;
- }
-
- if (pllsource == 0x00)
- {
- /* HSI oscillator clock divided by 2 selected as PLL clock entry */
- SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
- }
- else
- {/* PREDIV1 selected as PLL clock entry */
-
- /* Get PREDIV1 clock source and division factor */
- prediv1source = RCC->CFGR2 & RCC_CFGR2_PREDIV1SRC;
- prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
-
- if (prediv1source == 0)
- {
- /* HSE oscillator clock selected as PREDIV1 clock entry */
- SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
- }
- else
- {/* PLL2 clock selected as PREDIV1 clock entry */
-
- /* Get PREDIV2 division factor and PLL2 multiplication factor */
- prediv2factor = ((RCC->CFGR2 & RCC_CFGR2_PREDIV2) >> 4) + 1;
- pll2mull = ((RCC->CFGR2 & RCC_CFGR2_PLL2MUL) >> 8 ) + 2;
- SystemCoreClock = (((HSE_VALUE / prediv2factor) * pll2mull) / prediv1factor) * pllmull;
- }
- }
-#endif /* STM32F105xC */
- 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;
-}
-
-#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
-/**
- * @brief Setup the external memory controller. Called in startup_stm32f1xx.s
- * before jump to __main
- * @param None
- * @retval None
- */
-#ifdef DATA_IN_ExtSRAM
-/**
- * @brief Setup the external memory controller.
- * Called in startup_stm32f1xx_xx.s/.c before jump to main.
- * This function configures the external SRAM mounted on STM3210E-EVAL
- * board (STM32 High density devices). This SRAM will be used as program
- * data memory (including heap and stack).
- * @param None
- * @retval None
- */
-void SystemInit_ExtMemCtl(void)
-{
-/*!< FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is
- required, then adjust the Register Addresses */
-
- /* Enable FSMC clock */
- RCC->AHBENR = 0x00000114;
-
- /* Enable GPIOD, GPIOE, GPIOF and GPIOG clocks */
- RCC->APB2ENR = 0x000001E0;
-
-/* --------------- SRAM Data lines, NOE and NWE configuration ---------------*/
-/*---------------- SRAM Address lines configuration -------------------------*/
-/*---------------- NOE and NWE configuration --------------------------------*/
-/*---------------- NE3 configuration ----------------------------------------*/
-/*---------------- NBL0, NBL1 configuration ---------------------------------*/
-
- GPIOD->CRL = 0x44BB44BB;
- GPIOD->CRH = 0xBBBBBBBB;
-
- GPIOE->CRL = 0xB44444BB;
- GPIOE->CRH = 0xBBBBBBBB;
-
- GPIOF->CRL = 0x44BBBBBB;
- GPIOF->CRH = 0xBBBB4444;
-
- GPIOG->CRL = 0x44BBBBBB;
- GPIOG->CRH = 0x44444B44;
-
-/*---------------- FSMC Configuration ---------------------------------------*/
-/*---------------- Enable FSMC Bank1_SRAM Bank ------------------------------*/
-
- FSMC_Bank1->BTCR[4] = 0x00001011;
- FSMC_Bank1->BTCR[5] = 0x00000200;
-}
-#endif /* DATA_IN_ExtSRAM */
-#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */
-
-/**
- * @}
- */
-
-/**
- * @}
- */
-
-/**
- * @}
- */
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/