diff --git a/Makefile b/Makefile index a9ace33..3c3d778 100644 --- a/Makefile +++ b/Makefile @@ -39,7 +39,22 @@ SIZE = $(BINPFX)size ### STM32F030F4P6 based board -PROJECT = f030f4 +PROJECT = f030f4.$(FLASHSTART) + +# In RAM Execution, Bootloader uses first 2K of RAM +#FLASHSTART = 0x20000800 +#FLASHSIZE = 2K +#RAMSTART = 0x20000000 +#RAMSIZE = 2K +#RAMISRV = 1 + +# In Flash Execution, ISR vector copied and mapped to RAM if RAMISRV is not 0 +FLASHSTART = 0x08000000 +FLASHSIZE = 16K +RAMSTART = 0x20000000 +RAMSIZE = 4K +#RAMISRV = 1 + #SRCS = boot.c #SRCS = ledon.c #SRCS = blink.c @@ -57,12 +72,21 @@ PROJECT = f030f4 #SRCS = startup.txeie.c gpioa.c dht11main.c dht11.c #SRCS = startup.txeie.c gpioa.c ds18b20main.c ds18b20.c #SRCS = startup.txeie.c adc.c adcmain.c -SRCS = startup.txeie.c adc.c adccalib.c ds18b20.c +#SRCS = startup.txeie.c adc.c adccalib.c ds18b20.c + SRCS = startup.ram.c txeie.c uptime.1.c OBJS = $(SRCS:.c=.o) -LIBOBJS = printf.o putchar.o puts.o memset.o +LIBOBJS = printf.o putchar.o puts.o memset.o memcpy.o + CPU = -mthumb -mcpu=cortex-m0 -CFLAGS = $(CPU) -g -Wall -Wextra -Os -LD_SCRIPT = $(PROJECT).ld +ifdef RAMISRV + CDEFINES = -DRAMISRV=$(RAMISRV) +endif +WARNINGS=-pedantic -Wall -Wextra -Wstrict-prototypes -Wno-unused-parameter +CFLAGS = $(CPU) -g $(WARNINGS) -Os $(CDEFINES) + +LD_SCRIPT = generic.ld +LDDEFS = --defsym,FLASHSTART=$(FLASHSTART),--defsym,FLASHSIZE=$(FLASHSIZE) +LDDEFINES = $(LDDEFS),--defsym,RAMSTART=$(RAMSTART),--defsym,RAMSIZE=$(RAMSIZE) LIBSTEM = stm32 LIBS = -l$(LIBSTEM) @@ -75,6 +99,7 @@ all: $(PROJECT).hex $(PROJECT).bin version: @echo make $(MAKE_VERSION) $(MAKE_HOST) @echo PATH="$(PATH)" + $(CC) --version clean: @echo CLEAN @@ -82,15 +107,15 @@ clean: $(PROJECT).elf: $(OBJS) lib$(LIBSTEM).a @echo $@ - $(CC) $(CPU) -T$(LD_SCRIPT) -L. -Wl,-Map=$(PROJECT).map,-cref \ - -nostartfiles -o $@ $(OBJS) $(LIBS) + $(CC) $(CPU) -T$(LD_SCRIPT) -L. -Wl,$(LDDEFINES),-Map=$(PROJECT).map,-cref \ +-nostartfiles -o $@ $(OBJS) $(LIBS) $(SIZE) $@ $(OBJDUMP) -hS $@ > $(PROJECT).lst %.elf: %.o lib$(LIBSTEM).a @echo $@ - $(CC) $(CPU) -T$(LD_SCRIPT) -L. -Wl,-Map=$*.map,-cref -nostartfiles \ - -o $@ $< $(LIBS) + $(CC) $(CPU) -T$(LD_SCRIPT) -L. -Wl,$(LDDEFINES),-Map=$*.map,-cref \ +-nostartfiles -o $@ $< $(LIBS) $(SIZE) $@ $(OBJDUMP) -hS $@ > $*.lst diff --git a/f030f4.ram.ld b/f030f4.ram.ld new file mode 100644 index 0000000..a698b0d --- /dev/null +++ b/f030f4.ram.ld @@ -0,0 +1,209 @@ +/* f030f4.ram.ld -- STM32F030F4 in RAM execution linker script */ +/* Copyright (c) 2021 Renaud Fivet */ + +/* Linker script to configure memory regions. + * Need modifying for a specific board. + * FLASH.ORIGIN: starting address of flash + * FLASH.LENGTH: length of flash + * RAM.ORIGIN: starting address of RAM bank 0 + * RAM.LENGTH: length of RAM bank 0 + */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x20000800, LENGTH = 2K + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 2K +} + +/* Linker script to place sections and symbol values. Should be used together + * with other linker script that defines memory regions FLASH and RAM. + * It references following symbols, which must be defined in code: + * Reset_Handler : Entry of reset handler + * + * It defines following symbols, which code can use without definition: + * __exidx_start + * __exidx_end + * __copy_table_start__ + * __copy_table_end__ + * __zero_table_start__ + * __zero_table_end__ + * __etext + * __data_start__ + * __preinit_array_start + * __preinit_array_end + * __init_array_start + * __init_array_end + * __fini_array_start + * __fini_array_end + * __data_end__ + * __bss_start__ + * __bss_end__ + * __end__ + * end + * __HeapLimit + * __StackLimit + * __StackTop + * __stack + */ +ENTRY(Reset_Handler) + +SECTIONS +{ + .text : + { + KEEP(*(.isr_vector)) + *(.text*) + + *(.init) + *(.fini) + + /* .ctors */ + *crtbegin.o(.ctors) + *crtbegin?.o(.ctors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors) + *(SORT(.ctors.*)) + *(.ctors) + + /* .dtors */ + *crtbegin.o(.dtors) + *crtbegin?.o(.dtors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors) + *(SORT(.dtors.*)) + *(.dtors) + + *(.rodata*) + + *(.eh_frame*) + . = ALIGN(4); + } > FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH + + __exidx_start = .; + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > FLASH + __exidx_end = .; + + /* To copy multiple ROM to RAM sections, + * uncomment .copy.table section and, + * define __STARTUP_COPY_MULTIPLE in startup_ARMCMx.S */ + /* + .copy.table : + { + . = ALIGN(4); + __copy_table_start__ = .; + LONG (__etext) + LONG (__data_start__) + LONG (__data_end__ - __data_start__) + LONG (__etext2) + LONG (__data2_start__) + LONG (__data2_end__ - __data2_start__) + __copy_table_end__ = .; + } > FLASH + */ + + /* To clear multiple BSS sections, + * uncomment .zero.table section and, + * define __STARTUP_CLEAR_BSS_MULTIPLE in startup_ARMCMx.S */ + /* + .zero.table : + { + . = ALIGN(4); + __zero_table_start__ = .; + LONG (__bss_start__) + LONG (__bss_end__ - __bss_start__) + LONG (__bss2_start__) + LONG (__bss2_end__ - __bss2_start__) + __zero_table_end__ = .; + } > FLASH + */ + + /* Location counter can end up 2byte aligned with narrow Thumb code but + __etext is assumed by startup code to be the LMA of a section in RAM + which must be 4byte aligned */ + __etext = ALIGN (4); + + /* In RAM isr vector reserved space at beginning of RAM */ + .isrdata : + { + ram_vector = . ; + . = . + 192 ; + } > RAM + + .data : AT (__etext) + { + __data_start__ = .; + *(vtable) + *(.data*) + + . = ALIGN(4); + /* preinit data */ + PROVIDE_HIDDEN (__preinit_array_start = .); + *(.preinit_array) + PROVIDE_HIDDEN (__preinit_array_end = .); + + . = ALIGN(4); + /* init data */ + PROVIDE_HIDDEN (__init_array_start = .); + *(SORT(.init_array.*)) + *(.init_array) + PROVIDE_HIDDEN (__init_array_end = .); + + + . = ALIGN(4); + /* finit data */ + PROVIDE_HIDDEN (__fini_array_start = .); + *(SORT(.fini_array.*)) + *(.fini_array) + PROVIDE_HIDDEN (__fini_array_end = .); + + *(.jcr) + . = ALIGN(4); + /* All data end */ + __data_end__ = .; + + } > RAM + + .bss : + { + . = ALIGN(4); + __bss_start__ = .; + *(.bss*) + *(COMMON) + . = ALIGN(4); + __bss_end__ = .; + } > RAM + + .heap (COPY): + { + __end__ = .; + PROVIDE(end = .); + *(.heap*) + __HeapLimit = .; + } > RAM + + /* .stack_dummy section doesn't contains any symbols. It is only + * used for linker to calculate size of stack sections, and assign + * values to stack symbols later */ + .stack_dummy (COPY): + { + *(.stack*) + } > RAM + + /* Set stack top to end of RAM, and stack limit move down by + * size of stack_dummy section */ + __StackTop = ORIGIN(RAM) + LENGTH(RAM); + __StackLimit = __StackTop - SIZEOF(.stack_dummy); + PROVIDE(__stack = __StackTop); + PROVIDE(__data_size = __bss_start__ - __data_start__); + PROVIDE(__bss_size = __bss_end__ - __bss_start__); + + /* Check if data + heap + stack exceeds RAM limit */ + ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack") +} + +/* end of f030f4.ram.ld */ diff --git a/generic.ld b/generic.ld new file mode 100644 index 0000000..d954ab0 --- /dev/null +++ b/generic.ld @@ -0,0 +1,209 @@ +/* generic.ld -- parametrized linker script */ +/* Copyright (c) 2021 Renaud Fivet */ + +/* Linker script to configure memory regions. + * Need modifying for a specific board. + * FLASH.ORIGIN: starting address of flash + * FLASH.LENGTH: length of flash + * RAM.ORIGIN: starting address of RAM bank 0 + * RAM.LENGTH: length of RAM bank 0 + */ +MEMORY +{ +/* FLASH means code, read only data and data initialization */ + FLASH (rx) : ORIGIN = FLASHSTART, LENGTH = FLASHSIZE + RAM (rwx) : ORIGIN = RAMSTART, LENGTH = RAMSIZE +} + +/* Linker script to place sections and symbol values. Should be used together + * with other linker script that defines memory regions FLASH and RAM. + * It references following symbols, which must be defined in code: + * Reset_Handler : Entry of reset handler + * + * It defines following symbols, which code can use without definition: + * __exidx_start + * __exidx_end + * __copy_table_start__ + * __copy_table_end__ + * __zero_table_start__ + * __zero_table_end__ + * __etext + * __data_start__ + * __preinit_array_start + * __preinit_array_end + * __init_array_start + * __init_array_end + * __fini_array_start + * __fini_array_end + * __data_end__ + * __bss_start__ + * __bss_end__ + * __end__ + * end + * __HeapLimit + * __StackLimit + * __StackTop + * __stack + */ +ENTRY(Reset_Handler) + +SECTIONS +{ + .text : + { + KEEP(*(.isr_vector)) + *(.text*) + + *(.init) + *(.fini) + + /* .ctors */ + *crtbegin.o(.ctors) + *crtbegin?.o(.ctors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors) + *(SORT(.ctors.*)) + *(.ctors) + + /* .dtors */ + *crtbegin.o(.dtors) + *crtbegin?.o(.dtors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors) + *(SORT(.dtors.*)) + *(.dtors) + + *(.rodata*) + + *(.eh_frame*) + . = ALIGN(4); + } > FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH + + __exidx_start = .; + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > FLASH + __exidx_end = .; + + /* To copy multiple ROM to RAM sections, + * uncomment .copy.table section and, + * define __STARTUP_COPY_MULTIPLE in startup_ARMCMx.S */ + /* + .copy.table : + { + . = ALIGN(4); + __copy_table_start__ = .; + LONG (__etext) + LONG (__data_start__) + LONG (__data_end__ - __data_start__) + LONG (__etext2) + LONG (__data2_start__) + LONG (__data2_end__ - __data2_start__) + __copy_table_end__ = .; + } > FLASH + */ + + /* To clear multiple BSS sections, + * uncomment .zero.table section and, + * define __STARTUP_CLEAR_BSS_MULTIPLE in startup_ARMCMx.S */ + /* + .zero.table : + { + . = ALIGN(4); + __zero_table_start__ = .; + LONG (__bss_start__) + LONG (__bss_end__ - __bss_start__) + LONG (__bss2_start__) + LONG (__bss2_end__ - __bss2_start__) + __zero_table_end__ = .; + } > FLASH + */ + + /* Location counter can end up 2byte aligned with narrow Thumb code but + __etext is assumed by startup code to be the LMA of a section in RAM + which must be 4byte aligned */ + __etext = ALIGN (4); + + /* In RAM isr vector reserved space at beginning of RAM */ + .isrdata (COPY): + { + KEEP(*(.ram_vector)) + } > RAM + + .data : AT (__etext) + { + __data_start__ = .; + *(vtable) + *(.data*) + + . = ALIGN(4); + /* preinit data */ + PROVIDE_HIDDEN (__preinit_array_start = .); + *(.preinit_array) + PROVIDE_HIDDEN (__preinit_array_end = .); + + . = ALIGN(4); + /* init data */ + PROVIDE_HIDDEN (__init_array_start = .); + *(SORT(.init_array.*)) + *(.init_array) + PROVIDE_HIDDEN (__init_array_end = .); + + + . = ALIGN(4); + /* finit data */ + PROVIDE_HIDDEN (__fini_array_start = .); + *(SORT(.fini_array.*)) + *(.fini_array) + PROVIDE_HIDDEN (__fini_array_end = .); + + *(.jcr) + . = ALIGN(4); + /* All data end */ + __data_end__ = .; + + } > RAM + + .bss : + { + . = ALIGN(4); + __bss_start__ = .; + *(.bss*) + *(COMMON) + . = ALIGN(4); + __bss_end__ = .; + } > RAM + + .heap (COPY): + { + __end__ = .; + PROVIDE(end = .); + *(.heap*) + __HeapLimit = .; + } > RAM + + /* .stack_dummy section doesn't contains any symbols. It is only + * used for linker to calculate size of stack sections, and assign + * values to stack symbols later */ + .stack_dummy (COPY): + { + *(.stack*) + } > RAM + + /* Set stack top to end of RAM, and stack limit move down by + * size of stack_dummy section */ + __StackTop = ORIGIN(RAM) + LENGTH(RAM); + __StackLimit = __StackTop - SIZEOF(.stack_dummy); + PROVIDE(__stack = __StackTop); + PROVIDE(__data_size = __bss_start__ - __data_start__); + PROVIDE(__bss_size = __bss_end__ - __bss_start__); + + /* Check if data + heap + stack exceeds RAM limit */ + ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack") +} + +/* end of generic.ld */ diff --git a/memcpy.c b/memcpy.c new file mode 100644 index 0000000..5b98714 --- /dev/null +++ b/memcpy.c @@ -0,0 +1,15 @@ +/* memcpy.c -- copy memory area */ +/* Copyright (c) 2021 Renaud Fivet */ + +#include + +void *memcpy( void *to, const void *from, size_t n) { + const char *s = from ; + char *d = to ; + while( n--) + *d++ = *s++ ; + + return to ; +} + +/* end of memcpy.c */ diff --git a/startup.ram.c b/startup.ram.c new file mode 100644 index 0000000..d4a8c04 --- /dev/null +++ b/startup.ram.c @@ -0,0 +1,160 @@ +/* startup.ram.c -- entry point at reset and C startup +** Copyright (c) 2020-2021 Renaud Fivet +** v7: isr vector mapped to RAM to enable in RAM execution +** v6: device specific interrupts mapped +** v5: System Exceptions mapped +** v4: calls to init() and main() +** v3: data and bss RAM memory initialization +** v2: SysTick System Exception mapped +** v1: stack and entry point +*/ + +#include "system.h" /* init() */ +#include "stm32f030xx.h" + +/* Memory locations defined by linker script */ +void __StackTop( void) ; /* __StackTop points after end of stack */ +void Reset_Handler( void) ; /* Entry point for execution */ +extern const long __etext[] ; /* start of initialized data copy in flash */ +extern long __data_start__[] ; +extern long __bss_start__[] ; +extern long __bss_end__ ; /* &__bss_end__ points after end of bss */ + +/* Stubs for System Exception Handler */ +void Default_Handler( void) ; +#define dflt_hndlr( fun) void fun##_Handler( void) \ + __attribute__((weak,alias("Default_Handler"))) +dflt_hndlr( NMI) ; +dflt_hndlr( HardFault) ; +dflt_hndlr( SVCall) ; +dflt_hndlr( PendSV) ; +dflt_hndlr( SysTick) ; + +dflt_hndlr( WWDG) ; +dflt_hndlr( RTC) ; +dflt_hndlr( FLASH) ; +dflt_hndlr( RCC) ; +dflt_hndlr( EXTI0_1) ; +dflt_hndlr( EXTI2_3) ; +dflt_hndlr( EXTI4_15) ; +dflt_hndlr( DMA_CH1) ; +dflt_hndlr( DMA_CH2_3) ; +dflt_hndlr( DMA_CH4_5) ; +dflt_hndlr( ADC) ; +dflt_hndlr( TIM1_BRK_UP_TRG_COM) ; +dflt_hndlr( TIM1_CC) ; +dflt_hndlr( TIM3) ; +dflt_hndlr( TIM6) ; +dflt_hndlr( TIM14) ; +dflt_hndlr( TIM15) ; +dflt_hndlr( TIM16) ; +dflt_hndlr( TIM17) ; +dflt_hndlr( I2C1) ; +dflt_hndlr( I2C2) ; +dflt_hndlr( SPI1) ; +dflt_hndlr( SPI2) ; +dflt_hndlr( USART1) ; +dflt_hndlr( USART2) ; +dflt_hndlr( USART3_4_5_6) ; +dflt_hndlr( USB) ; + +/* Interrupt vector table: + * 1 Stack Pointer reset value + * 15 System Exceptions + * 32 Device specific Interrupts + */ +typedef void (*isr_p)( void) ; +isr_p const isr_vector[ 16 + 32] __attribute__((section(".isr_vector"))) = { + __StackTop, +/* System Exceptions */ + Reset_Handler, + NMI_Handler, + HardFault_Handler, + 0, 0, 0, 0, 0, 0, 0, + SVCall_Handler, + 0, 0, + PendSV_Handler, + SysTick_Handler, +/* STM32F030xx specific Interrupts cf RM0360 */ + WWDG_Handler, + 0, + RTC_Handler, + FLASH_Handler, + RCC_Handler, + EXTI0_1_Handler, + EXTI2_3_Handler, + EXTI4_15_Handler, + 0, + DMA_CH1_Handler, + DMA_CH2_3_Handler, + DMA_CH4_5_Handler, + ADC_Handler, + TIM1_BRK_UP_TRG_COM_Handler, + TIM1_CC_Handler, + 0, + TIM3_Handler, + TIM6_Handler, + 0, + TIM14_Handler, + TIM15_Handler, + TIM16_Handler, + TIM17_Handler, + I2C1_Handler, + I2C2_Handler, + SPI1_Handler, + SPI2_Handler, + USART1_Handler, + USART2_Handler, + USART3_4_5_6_Handler, + 0, + USB_Handler +} ; + +#if RAMISRV +# define ISRV_SIZE (sizeof isr_vector / sizeof *isr_vector) +isr_p ram_vector[ ISRV_SIZE] __attribute__((section(".ram_vector"))) ; +#endif + +int main( void) ; + +void Reset_Handler( void) { + const long *f ; /* from, source constant data from FLASH */ + long *t ; /* to, destination in RAM */ + +#if RAMISRV +/* Copy isr vector to beginning of RAM */ + for( unsigned i = 0 ; i < ISRV_SIZE ; i++) + ram_vector[ i] = isr_vector[ i] ; +#endif + +/* Assume: +** __bss_start__ == __data_end__ +** All sections are 4 bytes aligned +*/ + f = __etext ; + for( t = __data_start__ ; t < __bss_start__ ; t += 1) + *t = *f++ ; + + while( t < &__bss_end__) + *t++ = 0 ; + +/* Make sure active isr vector is mapped at 0x0 before enabling interrupts */ + RCC_APB2ENR |= RCC_APB2ENR_SYSCFGEN ; /* Enable SYSCFG */ +#if RAMISRV + SYSCFG_CFGR1 |= 3 ; /* Map RAM at 0x0 */ +#else + SYSCFG_CFGR1 &= ~3 ; /* Map FLASH at 0x0 */ +#endif + + if( init() == 0) + main() ; + + for( ;;) + __asm( "WFI") ; /* Wait for interrupt */ +} + +void Default_Handler( void) { + for( ;;) ; +} + +/* end of startup.ram.c */ diff --git a/stm32f030xx.h b/stm32f030xx.h new file mode 100644 index 0000000..23daabe --- /dev/null +++ b/stm32f030xx.h @@ -0,0 +1,114 @@ +/* stm32f030xx.h -- STM32F030xx specific mapping */ +/* Copyright (c) 2021 Renaud Fivet */ + +/** CORE **********************************************************************/ + +#define SYSTICK ((volatile unsigned long *) 0xE000E010) +#define SYSTICK_CSR SYSTICK[ 0] +#define SYSTICK_RVR SYSTICK[ 1] +#define SYSTICK_CVR SYSTICK[ 2] + +#define NVIC ((volatile long *) 0xE000E100) +#define NVIC_ISER NVIC[ 0] +#define unmask_irq( idx) NVIC_ISER = 1 << idx +#define USART1_IRQ_IDX 27 + + +/** PERIPH ********************************************************************/ + +#define CAT( a, b) a##b +#define RCC ((volatile long *) 0x40021000) + +#define RCC_CR RCC[ 0] +#define RCC_CR_HSION 0x00000001 /* 1: Internal High Speed clock enable */ +#define RCC_CR_HSEON 0x00010000 /* 16: External High Speed clock enable */ +#define RCC_CR_HSERDY 0x00020000 /* 17: External High Speed clock ready flag */ +#define RCC_CR_PLLON 0x01000000 /* 24: PLL enable */ +#define RCC_CR_PLLRDY 0x02000000 /* 25: PLL clock ready flag */ + +#define RCC_CFGR RCC[ 1] +#define RCC_CFGR_SW_MSK 0x00000003 /* 1-0: System clock SWitch Mask */ +#define RCC_CFGR_SW_HSE 0x00000001 /* 1-0: Switch to HSE as system clock */ +#define RCC_CFGR_SW_PLL 0x00000002 /* 1-0: Switch to PLL as system clock */ +#define RCC_CFGR_SWS_MSK 0x0000000C /* 3-2: System clock SWitch Status Mask */ +#define RCC_CFGR_SWS_HSE 0x00000004 /* 3-2: HSE used as system clock */ +#define RCC_CFGR_SWS_PLL 0x00000008 /* 3-2: PLL used as system clock */ +#define RCC_CFGR_PLLSRC 0x00010000 +#define RCC_CFGR_PLLSRC_HSI 0x00000000 /* HSI / 2 */ +#define RCC_CFGR_PLLSRC_HSE 0x00010000 /* HSE */ +#define RCC_CFGR_PLLXTPRE 0x00020000 +#define RCC_CFGR_PLLXTPRE_DIV1 0x00000000 /* HSE */ +#define RCC_CFGR_PLLXTPRE_DIV2 0x00020000 /* HSE / 2 */ +#define RCC_CFGR_PLLMUL_MSK (0x00F << 18) +#define RCC_CFGR_PLLMUL( v) ((v - 2) << 18) + +#define RCC_AHBENR RCC[ 5] +#define RCC_AHBENR_IOPn( n) (1 << (17 + n)) +#define RCC_AHBENR_IOPh( h) RCC_AHBENR_IOPn( CAT( 0x, h) - 0xA) + +#define RCC_APB2ENR RCC[ 6] +#define RCC_APB2ENR_USART1EN 0x00004000 /* 14: USART1 clock enable */ +#define RCC_APB2ENR_ADCEN 0x00000200 /* 9: ADC clock enable */ +#define RCC_APB2ENR_SYSCFGEN 0x00000001 /* 1: SYSCFG clock enable */ + +#define RCC_CR2 RCC[ 13] +#define RCC_CR2_HSI14ON 0x00000001 /* 1: HSI14 clock enable */ +#define RCC_CR2_HSI14RDY 0x00000002 /* 2: HSI14 clock ready */ + + +#define GPIOA ((volatile long *) 0x48000000) +#define GPIOB ((volatile long *) 0x48000400) +#define GPIO( x) CAT( GPIO, x) +#define MODER 0 +#define IDR 4 +#define ODR 5 +#define AFRH 9 + +#define SYSCFG ((volatile long *) 0x40010000) +#define SYSCFG_CFGR1 SYSCFG[ 0] + +#define ADC ((volatile long *) 0x40012400) +#define ADC_ISR ADC[ 0] +#define ADC_ISR_ADRDY 1 /* 0: ADC Ready */ +#define ADC_ISR_EOC 4 /* 2: End Of Conversion flag */ + +#define ADC_CR ADC[ 2] +#define ADC_CR_ADEN 1 /* 0: ADc ENable command */ +#define ADC_CR_ADSTART 4 /* 2: ADC Start Conversion command */ +#define ADC_CR_ADCAL (1 << 31) /* 31: ADC Start Calibration cmd */ + +#define ADC_CFGR1 ADC[ 3] /* Configuration Register 1 */ +#define ADC_CFGR1_SCANDIR 4 /* 2: Scan sequence direction */ +#define ADC_CFGR1_DISCEN (1 << 16) /* 16: Enable Discontinuous mode */ + +#define ADC_CFGR2 ADC[ 4] /* Configuration Register 2 */ +#define ADC_CFGR2_CKMODE (3 << 30) /* 31-30: Clock Mode Mask */ + /* 31-30: Default 00 HSI14 */ +#define ADC_CFGR2_PCLK2 (1 << 30) /* 31-30: PCLK/2 */ +#define ADC_CFGR2_PCLK4 (2 << 30) /* 31-30: PCLK/4 */ + +#define ADC_SMPR ADC[ 5] /* Sampling Time Register */ +#define ADC_CHSELR ADC[ 10] /* Channel Selection Register */ +#define ADC_DR ADC[ 16] /* Data Register */ +#define ADC_CCR ADC[ 194] /* Common Configuration Register */ +#define ADC_CCR_VREFEN (1 << 22) /* 22: Vrefint Enable */ +#define ADC_CCR_TSEN (1 << 23) /* 23: Temperature Sensor Enable */ + +#define USART1 ((volatile long *) 0x40013800) +#define CR1 0 /* Config Register */ +#define BRR 3 /* BaudRate Register */ +#define ISR 7 /* Interrupt and Status Register */ +#define TDR 10 /* Transmit Data Register*/ +#define USART_CR1_TXEIE (1 << 7) /* 7: TDR Empty Interrupt Enable */ +#define USART_CR1_TE 8 /* 3: Transmit Enable */ +#define USART_CR1_RE 4 /* 2: Receive Enable */ +#define USART_CR1_UE 1 /* 0: USART Enable */ +#define USART_ISR_TXE (1 << 7) /* 7: Transmit Data Register Empty */ + + +/** SYSTEM MEMORY *************************************************************/ +/* STM32F030 calibration addresses (at 3.3V and 30C) */ +#define TS_CAL ((unsigned short *) 0x1FFFF7B8) +#define VREFINT_CAL ((unsigned short *) 0x1FFFF7BA) + +/* end of stm32f030xx.h */