commit
d3bba80288
@ -0,0 +1,39 @@ |
||||
# Temporary files |
||||
|
||||
*.bak |
||||
*.lnp |
||||
*.iex |
||||
*.hex |
||||
*.elf |
||||
*.axf |
||||
*.htm |
||||
*.lnp |
||||
*.lst |
||||
*.plg |
||||
*.tra |
||||
*.o |
||||
*.map |
||||
*.d |
||||
*.dep |
||||
*.disasm |
||||
*.bin |
||||
*.log |
||||
|
||||
*.pro.* |
||||
|
||||
# Backup files |
||||
|
||||
*.bak |
||||
*~ |
||||
|
||||
# Keil temporary files |
||||
|
||||
*.uvguix.* |
||||
/RTE/ |
||||
|
||||
# DS-5 temporary files |
||||
|
||||
/.externalToolBuilders |
||||
|
||||
|
||||
/trash/ |
@ -0,0 +1,143 @@ |
||||
DEFS = -DSTM32L1
|
||||
|
||||
FP_FLAGS ?= -msoft-float
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd
|
||||
|
||||
LDSCRIPT = stm32l100rc.ld
|
||||
|
||||
################################################################
|
||||
|
||||
# Main file
|
||||
BINARY = main
|
||||
|
||||
INCL_DIRS = . lib source
|
||||
SRC_DIR = source
|
||||
|
||||
STARTUP_SCRIPT = startup_stm32l100xc.s
|
||||
|
||||
OBJS += $(BINARY).o $(STARTUP_SCRIPT:.s=.o)
|
||||
OBJS += lib/gpio.o
|
||||
OBJS += lib/systick.o
|
||||
|
||||
################################################################
|
||||
|
||||
JUNK = *.o *.d *.elf *.bin *.hex *.srec *.list *.map *.dis *.disasm
|
||||
|
||||
###############################################################################
|
||||
###############################################################################
|
||||
###############################################################################
|
||||
|
||||
# Be silent per default, but 'make V=1' will show all compiler calls.
|
||||
ifneq ($(V),1) |
||||
Q := @
|
||||
NULL := 2>/dev/null
|
||||
endif |
||||
|
||||
###############################################################################
|
||||
# Executables
|
||||
|
||||
PREFIX ?= arm-none-eabi
|
||||
|
||||
CC := $(PREFIX)-gcc
|
||||
CXX := $(PREFIX)-g++
|
||||
LD := $(PREFIX)-gcc
|
||||
AR := $(PREFIX)-ar
|
||||
AS := $(PREFIX)-as
|
||||
OBJCOPY := $(PREFIX)-objcopy
|
||||
OBJDUMP := $(PREFIX)-objdump
|
||||
GDB := $(PREFIX)-gdb
|
||||
STFLASH := $(shell which st-flash)
|
||||
|
||||
###############################################################################
|
||||
|
||||
# For CMSIS compatibility
|
||||
DEFS += -D__weak="__attribute__((weak))" -D__packed="__attribute__((__packed__))"
|
||||
|
||||
###############################################################################
|
||||
# C flags
|
||||
|
||||
CFLAGS += -Os -ggdb -std=gnu99 -Wfatal-errors
|
||||
CFLAGS += -Wall -Wextra -Wshadow
|
||||
CFLAGS += -Wwrite-strings -Wold-style-definition -Winline -Wmissing-noreturn -Wstrict-prototypes
|
||||
CFLAGS += -Wredundant-decls -Wfloat-equal -Wsign-compare
|
||||
CFLAGS += -fno-common -ffunction-sections -fdata-sections -Wunused-function
|
||||
CFLAGS += -MD
|
||||
CFLAGS += $(INCL_DIRS:%=-I%) $(DEFS)
|
||||
|
||||
###############################################################################
|
||||
# Linker flags
|
||||
|
||||
LDFLAGS += --static -specs=nano.specs -lm -lc
|
||||
#LDFLAGS += -L$(OCM3_LIB_DIR)
|
||||
LDFLAGS += -T$(LDSCRIPT)
|
||||
LDFLAGS += -Wl,-Map=$(*).map
|
||||
LDFLAGS += -Wl,--gc-sections
|
||||
|
||||
###############################################################################
|
||||
# Used libraries
|
||||
|
||||
LDLIBS += -lm
|
||||
LDLIBS += -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group
|
||||
|
||||
###############################################################################
|
||||
###############################################################################
|
||||
###############################################################################
|
||||
|
||||
.SUFFIXES: .elf .bin .hex .srec .list .map .images |
||||
.SECONDEXPANSION: |
||||
.SECONDARY: |
||||
|
||||
all: elf |
||||
|
||||
ttyusb: |
||||
gtkterm -s 115200 -p /dev/ttyUSB0
|
||||
|
||||
ttyacm: |
||||
gtkterm -p /dev/ttyACM0
|
||||
|
||||
elf: $(BINARY).elf |
||||
bin: $(BINARY).bin |
||||
hex: $(BINARY).hex |
||||
srec: $(BINARY).srec |
||||
list: $(BINARY).list |
||||
|
||||
images: $(BINARY).images |
||||
flash: $(BINARY).flash |
||||
|
||||
dis: $(BINARY).elf |
||||
$(Q)$(OBJDUMP) -dS $(BINARY).elf -j .text -j .isr_vector > $(BINARY).dis
|
||||
|
||||
%.images: %.bin %.hex %.srec %.list %.map |
||||
|
||||
%.bin: %.elf |
||||
$(Q)$(OBJCOPY) -Obinary $(*).elf $(*).bin
|
||||
|
||||
%.hex: %.elf |
||||
$(Q)$(OBJCOPY) -Oihex $(*).elf $(*).hex
|
||||
|
||||
%.srec: %.elf |
||||
$(Q)$(OBJCOPY) -Osrec $(*).elf $(*).srec
|
||||
|
||||
%.list: %.elf |
||||
$(Q)$(OBJDUMP) -S $(*).elf > $(*).list
|
||||
|
||||
%.elf %.map: $(OBJS) |
||||
$(Q)$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(*).elf
|
||||
|
||||
%.o: %.c |
||||
$(Q)$(CC) $(CFLAGS) $(ARCH_FLAGS) -o $(*).o -c $(*).c
|
||||
|
||||
%.o: %.s |
||||
$(Q)$(CC) $(CFLAGS) $(ARCH_FLAGS) -o $(*).o -c $(*).s
|
||||
|
||||
clean: |
||||
$(Q)$(RM) $(JUNK)
|
||||
$(Q)cd lib && $(RM) $(JUNK)
|
||||
|
||||
%.flash: %.bin |
||||
@printf " FLASH $<\n"
|
||||
$(Q)$(STFLASH) write $(*).bin 0x8000000
|
||||
|
||||
.PHONY: images clean elf bin hex srec list dis ttyusb ttyacm |
||||
|
||||
-include $(OBJS:.o=.d) |
@ -0,0 +1,66 @@ |
||||
#pragma once |
||||
|
||||
/* Part of this file is based on libopencm3 */ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
|
||||
|
||||
/* Generic memory-mapped I/O accessor functions */ |
||||
#define MMIO8(addr) (*(volatile uint8_t *)(addr)) |
||||
#define MMIO16(addr) (*(volatile uint16_t *)(addr)) |
||||
#define MMIO32(addr) (*(volatile uint32_t *)(addr)) |
||||
#define MMIO64(addr) (*(volatile uint64_t *)(addr)) |
||||
|
||||
/* Generic bit-band I/O accessor functions */ |
||||
#define BBIO_SRAM(addr, bit) \ |
||||
MMIO32((((uint32_t)addr) & 0x0FFFFF) * 32 + 0x22000000 + (bit) * 4) |
||||
|
||||
#define BBIO_PERIPH(addr, bit) \ |
||||
MMIO32((((uint32_t)addr) & 0x0FFFFF) * 32 + 0x42000000 + (bit) * 4) |
||||
|
||||
// i...iterator, m...mask, count...nr of bits
|
||||
#define BitFieldLoop(i, m, count) for (uint32_t i = 0, m = 1; i < count; m <<= 1, i++) |
||||
|
||||
|
||||
#define BIT0 (1<<0) |
||||
#define BIT1 (1<<1) |
||||
#define BIT2 (1<<2) |
||||
#define BIT3 (1<<3) |
||||
#define BIT4 (1<<4) |
||||
#define BIT5 (1<<5) |
||||
#define BIT6 (1<<6) |
||||
#define BIT7 (1<<7) |
||||
#define BIT8 (1<<8) |
||||
#define BIT9 (1<<9) |
||||
#define BIT10 (1<<10) |
||||
#define BIT11 (1<<11) |
||||
#define BIT12 (1<<12) |
||||
#define BIT13 (1<<13) |
||||
#define BIT14 (1<<14) |
||||
#define BIT15 (1<<15) |
||||
#define BIT16 (1<<16) |
||||
#define BIT17 (1<<17) |
||||
#define BIT18 (1<<18) |
||||
#define BIT19 (1<<19) |
||||
#define BIT20 (1<<20) |
||||
#define BIT21 (1<<21) |
||||
#define BIT22 (1<<22) |
||||
#define BIT23 (1<<23) |
||||
#define BIT24 (1<<24) |
||||
#define BIT25 (1<<25) |
||||
#define BIT26 (1<<26) |
||||
#define BIT27 (1<<27) |
||||
#define BIT28 (1<<28) |
||||
#define BIT29 (1<<29) |
||||
#define BIT30 (1<<30) |
||||
#define BIT31 (1<<31) |
||||
|
||||
|
||||
|
||||
#include "defs_base.h" |
||||
#include "defs_gpio.h" |
||||
#include "defs_rcc.h" |
||||
#include "defs_flash.h" |
||||
#include "defs_systick.h" |
||||
#include "defs_usart.h" |
@ -0,0 +1,100 @@ |
||||
#pragma once |
||||
|
||||
#include "common.h" |
||||
|
||||
// AUTHOR : Ondrej Hruska
|
||||
// DATE : 12/2015
|
||||
// DESCR : Base library file. This file must be included before any other library
|
||||
// files. This file defines memory map and base addresses of peripherals.
|
||||
|
||||
|
||||
#define FLASH_BASE 0x08000000 // FLASH base address in the alias region
|
||||
#define SRAM_BASE 0x20000000 // SRAM base address in the alias region
|
||||
#define PERIPH_BASE 0x40000000 // Peripheral base address in the alias region
|
||||
|
||||
#define SRAM_BB_BASE (SRAM_BASE + 0x02000000) // SRAM base address in the bit-band region
|
||||
#define PERIPH_BB_BASE (PERIPH_BASE + 0x02000000) // Peripheral base address in the bit-band region
|
||||
|
||||
|
||||
// ------------------------- System Config Blocks -----------------------------
|
||||
|
||||
#define _SCS_BASE 0xE000E000 // System Control Space base
|
||||
#define _SCB (_SCS_BASE + 0x0D00) // System Control Block base
|
||||
#define _NVIC (_SCS_BASE + 0x0100) // Nested Interrupt Vector Controller base
|
||||
#define _OB 0x1FF80000 // FLASH Option Bytes base address
|
||||
#define _AES 0x50060000 // Encryption module
|
||||
#define _FSMC 0xA0000000 // External Memory Control base
|
||||
#define _DBGMCU 0xE0042000 // Debug MCU registers base address
|
||||
|
||||
|
||||
// ----------------------------- Peripherals ----------------------------------
|
||||
|
||||
// *** Peripheral bus bases ***
|
||||
#define _APB1 PERIPH_BASE // Advanced Peripheral Bus 1 base
|
||||
#define _APB2 (PERIPH_BASE + 0x10000) // Advanced Peripheral Bus 2 base
|
||||
#define _AHB (PERIPH_BASE + 0x20000) // Advanced High-speed Bus base
|
||||
|
||||
// *** Peripheral Bus 1 devices ***
|
||||
|
||||
#define _TIM2 (_APB1 + 0x0000) // Timer bases
|
||||
#define _TIM3 (_APB1 + 0x0400) |
||||
#define _TIM4 (_APB1 + 0x0800) |
||||
#define _TIM5 (_APB1 + 0x0C00) |
||||
#define _TIM6 (_APB1 + 0x1000) |
||||
#define _TIM7 (_APB1 + 0x1400) |
||||
|
||||
#define _LCD (_APB1 + 0x2400) // LCD controller base
|
||||
#define _RTC (_APB1 + 0x2800) // RTC base
|
||||
|
||||
#define _WWDG (_APB1 + 0x2C00) // Window Watchdog base
|
||||
#define _IWDG (_APB1 + 0x3000) // Independent Watchdog base
|
||||
|
||||
#define _SPI2 (_APB1 + 0x3800) // SPI base
|
||||
#define _SPI3 (_APB1 + 0x3C00) |
||||
|
||||
#define _USART2 (_APB1 + 0x4400) // USART base
|
||||
#define _USART3 (_APB1 + 0x4800) |
||||
|
||||
#define _UART4 (_APB1 + 0x4C00) // UART base (?)
|
||||
#define _UART5 (_APB1 + 0x5000) |
||||
|
||||
#define _I2C1 (_APB1 + 0x5400) // I2C base
|
||||
#define _I2C2 (_APB1 + 0x5800) |
||||
|
||||
#define _PWR (_APB1 + 0x7000) // Power Control block base
|
||||
#define _DAC (_APB1 + 0x7400) // D/A config base
|
||||
#define _COMP (_APB1 + 0x7C00) // Analog Comparator base
|
||||
#define _RI (_APB1 + 0x7C04) // Routing Interface base (analog pin connections)
|
||||
#define _OPAMP (_APB1 + 0x7C5C) // OpAmp config base
|
||||
|
||||
#define _USB (_APB1 + 0x5C00) // USB registers base
|
||||
|
||||
// *** Peripheral Bus 2 devices ***
|
||||
|
||||
#define _TIM9 (_APB2 + 0x0800) // Timer base
|
||||
#define _TIM10 (_APB2 + 0x0C00) |
||||
#define _TIM11 (_APB2 + 0x1000) |
||||
|
||||
#define _SYSCFG (_APB2 + 0x0000) // System config block base
|
||||
#define _EXTI (_APB2 + 0x0400) // External interrupt settings base
|
||||
|
||||
#define _ADC1 (_APB2 + 0x2400) // A/D 1
|
||||
#define _ADCC (_APB2 + 0x2700) // common A/D registers base
|
||||
|
||||
#define _SDIO (_APB2 + 0x2C00) // SD host
|
||||
#define _SPI1 (_APB2 + 0x3000) // SPI
|
||||
#define _USART1 (_APB2 + 0x3800) |
||||
|
||||
|
||||
|
||||
// *** High Speed Bus devices ***
|
||||
|
||||
#define _GPIO (_AHB + 0x0000) // GPIO block base
|
||||
|
||||
#define _CRC (_AHB + 0x3000) // CRC module base
|
||||
#define _RCC (_AHB + 0x3800) // Reset and Clock Config base
|
||||
|
||||
#define _DMA1 (_AHB + 0x6000) // DMA control base
|
||||
#define _DMA2 (_AHB + 0x6400) |
||||
|
||||
#define _FLASH (_AHB + 0x3C00) // FLASH control base
|
@ -0,0 +1,115 @@ |
||||
#pragma once |
||||
|
||||
#include "common.h" |
||||
|
||||
// AUTHOR : Ondrej Hruska
|
||||
// DATE : 12/2015
|
||||
// DESCR : Control registers and bit masks for FLASH control
|
||||
//
|
||||
// FLASH, DATA EEPROM and Option Bytes Registers
|
||||
|
||||
|
||||
//****************************************************************************
|
||||
//*
|
||||
//* REGISTERS
|
||||
//*
|
||||
//****************************************************************************
|
||||
|
||||
|
||||
// FLASH registers
|
||||
|
||||
#define FLASH_ACR MMIO32(_FLASH + 0x00) // Access control register,
|
||||
#define FLASH_PECR MMIO32(_FLASH + 0x04) // Program/erase control register,
|
||||
#define FLASH_PDKEYR MMIO32(_FLASH + 0x08) // Power down key register,
|
||||
#define FLASH_PEKEYR MMIO32(_FLASH + 0x0c) // Program/erase key register,
|
||||
#define FLASH_PRGKEYR MMIO32(_FLASH + 0x10) // Program memory key register,
|
||||
#define FLASH_OPTKEYR MMIO32(_FLASH + 0x14) // Option byte key register,
|
||||
#define FLASH_SR MMIO32(_FLASH + 0x18) // Status register,
|
||||
#define FLASH_OBR MMIO32(_FLASH + 0x1c) // Option byte register,
|
||||
#define FLASH_WRPR MMIO32(_FLASH + 0x20) // Write protection register,
|
||||
#define FLASH_WRPR1 MMIO32(_FLASH + 0x28) // Write protection register 1,
|
||||
#define FLASH_WRPR2 MMIO32(_FLASH + 0x2C) // Write protection register 2,
|
||||
|
||||
// FLASH option bytes (maybe incorrect, not tested)
|
||||
|
||||
#define OB_RDP MMIO32(_OB + 0x00) // Read protection register,
|
||||
#define OB_USER MMIO32(_OB + 0x04) // user register,
|
||||
#define OB_WRP01 MMIO32(_OB + 0x08) // write protection register 0 1,
|
||||
#define OB_WRP23 MMIO32(_OB + 0x0C) // write protection register 2 3,
|
||||
#define OB_WRP45 MMIO32(_OB + 0x10) // write protection register 4 5,
|
||||
#define OB_WRP67 MMIO32(_OB + 0x14) // write protection register 6 7,
|
||||
#define OB_WRP89 MMIO32(_OB + 0x18) // write protection register 8 9,
|
||||
#define OB_WRP1011 MMIO32(_OB + 0x1C) // write protection register 10 11,
|
||||
|
||||
|
||||
|
||||
//****************************************************************************
|
||||
//*
|
||||
//* BIT MASKS AND DEFINITIONS
|
||||
//*
|
||||
//****************************************************************************
|
||||
|
||||
|
||||
//****************** Bit definition for FLASH_ACR register *****************
|
||||
#define FLASH_ACR_LATENCY 0x00000001 // Latency
|
||||
#define FLASH_ACR_PRFTEN 0x00000002 // Prefetch Buffer Enable
|
||||
#define FLASH_ACR_ACC64 0x00000004 // Access 64 bits
|
||||
#define FLASH_ACR_SLEEP_PD 0x00000008 // Flash mode during sleep mode
|
||||
#define FLASH_ACR_RUN_PD 0x00000010 // Flash mode during RUN mode
|
||||
|
||||
//****************** Bit definition for FLASH_PECR register *****************
|
||||
#define FLASH_PECR_PELOCK 0x00000001 // FLASH_PECR and Flash data Lock
|
||||
#define FLASH_PECR_PRGLOCK 0x00000002 // Program matrix Lock
|
||||
#define FLASH_PECR_OPTLOCK 0x00000004 // Option byte matrix Lock
|
||||
#define FLASH_PECR_PROG 0x00000008 // Program matrix selection
|
||||
#define FLASH_PECR_DATA 0x00000010 // Data matrix selection
|
||||
#define FLASH_PECR_FTDW 0x00000100 // Fixed Time Data write for Word/Half Word/Byte programming
|
||||
#define FLASH_PECR_ERASE 0x00000200 // Page erasing mode
|
||||
#define FLASH_PECR_FPRG 0x00000400 // Fast Page/Half Page programming mode
|
||||
#define FLASH_PECR_PARALLBANK 0x00008000 // Parallel Bank mode
|
||||
#define FLASH_PECR_EOPIE 0x00010000 // End of programming interrupt
|
||||
#define FLASH_PECR_ERRIE 0x00020000 // Error interrupt
|
||||
#define FLASH_PECR_OBL_LAUNCH 0x00040000 // Launch the option byte loading
|
||||
|
||||
//***************** Bit definition for FLASH_PDKEYR register *****************
|
||||
#define FLASH_PDKEYR_PDKEYR 0xFFFFFFFF // FLASH_PEC and data matrix Key
|
||||
|
||||
//***************** Bit definition for FLASH_PEKEYR register *****************
|
||||
#define FLASH_PEKEYR_PEKEYR 0xFFFFFFFF // FLASH_PEC and data matrix Key
|
||||
|
||||
//***************** Bit definition for FLASH_PRGKEYR register *****************
|
||||
#define FLASH_PRGKEYR_PRGKEYR 0xFFFFFFFF // Program matrix Key
|
||||
|
||||
//***************** Bit definition for FLASH_OPTKEYR register *****************
|
||||
#define FLASH_OPTKEYR_OPTKEYR 0xFFFFFFFF // Option bytes matrix Key
|
||||
|
||||
//***************** Bit definition for FLASH_SR register ******************
|
||||
#define FLASH_SR_BSY 0x00000001 // Busy
|
||||
#define FLASH_SR_EOP 0x00000002 // End Of Programming
|
||||
#define FLASH_SR_ENHV 0x00000004 // End of high voltage
|
||||
#define FLASH_SR_READY 0x00000008 // Flash ready after low power mode
|
||||
|
||||
#define FLASH_SR_WRPERR 0x00000100 // Write protected error
|
||||
#define FLASH_SR_PGAERR 0x00000200 // Programming Alignment Error
|
||||
#define FLASH_SR_SIZERR 0x00000400 // Size error
|
||||
#define FLASH_SR_OPTVERR 0x00000800 // Option validity error
|
||||
#define FLASH_SR_OPTVERRUSR 0x00001000 // Option User validity error
|
||||
#define FLASH_SR_RDERR 0x00002000 // Read protected error
|
||||
|
||||
//***************** Bit definition for FLASH_OBR register ******************
|
||||
#define FLASH_OBR_RDPRT 0x000000AA // Read Protection
|
||||
#define FLASH_OBR_SPRMOD 0x00000100 // Selection of protection mode of WPRi bits (available only in STM32L1xx Medium-density Plus devices)
|
||||
#define FLASH_OBR_BOR_LEV 0x000F0000 // BOR_LEV[3:0] Brown Out Reset Threshold Level
|
||||
#define FLASH_OBR_IWDG_SW 0x00100000 // IWDG_SW
|
||||
#define FLASH_OBR_nRST_STOP 0x00200000 // nRST_STOP
|
||||
#define FLASH_OBR_nRST_STDBY 0x00400000 // nRST_STDBY
|
||||
#define FLASH_OBR_BFB2 0x00800000 // BFB2(available only in STM32L1xx High-density devices)
|
||||
|
||||
//***************** Bit definition for FLASH_WRPR register *****************
|
||||
#define FLASH_WRPR_WRP 0xFFFFFFFF // Write Protection bits
|
||||
|
||||
//***************** Bit definition for FLASH_WRPR1 register ****************
|
||||
#define FLASH_WRPR1_WRP 0xFFFFFFFF // Write Protection bits (available only in STM32L1xx Medium-density Plus and High-density devices)
|
||||
|
||||
//***************** Bit definition for FLASH_WRPR2 register ****************
|
||||
#define FLASH_WRPR2_WRP 0xFFFFFFFF // Write Protection bits (available only in STM32L1xx High-density devices)
|
@ -0,0 +1,117 @@ |
||||
#pragma once |
||||
|
||||
#include "common.h" |
||||
|
||||
// AUTHOR : Ondrej Hruska
|
||||
// DATE : 10/2015
|
||||
// DESCR : Control registers and bit masks for GPIO
|
||||
|
||||
|
||||
// offsets
|
||||
#define GPIO_MODER_offs 0x00 // GPIOA pin mode register,
|
||||
#define GPIO_OTYPER_offs 0x04 // GPIOA output type register,
|
||||
#define GPIO_OSPEEDR_offs 0x08 // GPIOA output speed register,
|
||||
#define GPIO_PUPDR_offs 0x0C // GPIOA pull-up/pull-down register,
|
||||
#define GPIO_IDR_offs 0x10 // GPIOA input data register,
|
||||
#define GPIO_ODR_offs 0x14 // GPIOA output data register,
|
||||
#define GPIO_BSRR_offs 0x18 // GPIOA bit set/reset register,
|
||||
#define GPIO_LCKR_offs 0x1C // GPIOA configuration lock register,
|
||||
#define GPIO_AFR_offs 0x20 // GPIOA alternate function register,
|
||||
#define GPIO_BRR_offs 0x28 // GPIOA bit reset register,
|
||||
|
||||
#define GPIOA (_GPIO + 0x0000) |
||||
#define GPIOB (_GPIO + 0x0400) |
||||
#define GPIOC (_GPIO + 0x0800) |
||||
#define GPIOD (_GPIO + 0x0C00) |
||||
#define GPIOE (_GPIO + 0x1000) |
||||
#define GPIOH (_GPIO + 0x1400) |
||||
#define GPIOF (_GPIO + 0x1800) |
||||
#define GPIOG (_GPIO + 0x1C00) |
||||
|
||||
#define GPIOA_MODER MMIO32(GPIOA + 0x00) // GPIOA pin mode register,
|
||||
#define GPIOA_OTYPER MMIO32(GPIOA + 0x04) // GPIOA output type register,
|
||||
#define GPIOA_OSPEEDR MMIO32(GPIOA + 0x08) // GPIOA output speed register,
|
||||
#define GPIOA_PUPDR MMIO32(GPIOA + 0x0C) // GPIOA pull-up/pull-down register,
|
||||
#define GPIOA_IDR MMIO32(GPIOA + 0x10) // GPIOA input data register,
|
||||
#define GPIOA_ODR MMIO32(GPIOA + 0x14) // GPIOA output data register,
|
||||
#define GPIOA_BSRR MMIO32(GPIOA + 0x18) // GPIOA bit set/reset register,
|
||||
#define GPIOA_LCKR MMIO32(GPIOA + 0x1C) // GPIOA configuration lock register,
|
||||
#define GPIOA_AFR MMIO64(GPIOA + 0x20) // GPIOA alternate function register,
|
||||
#define GPIOA_BRR MMIO32(GPIOA + 0x28) // GPIOA bit reset register,
|
||||
|
||||
#define GPIOB_MODER MMIO32(GPIOB + 0x00) // GPIOB pin mode register,
|
||||
#define GPIOB_OTYPER MMIO32(GPIOB + 0x04) // GPIOB output type register,
|
||||
#define GPIOB_OSPEEDR MMIO32(GPIOB + 0x08) // GPIOB output speed register,
|
||||
#define GPIOB_PUPDR MMIO32(GPIOB + 0x0C) // GPIOB pull-up/pull-down register,
|
||||
#define GPIOB_IDR MMIO32(GPIOB + 0x10) // GPIOB input data register,
|
||||
#define GPIOB_ODR MMIO32(GPIOB + 0x14) // GPIOB output data register,
|
||||
#define GPIOB_BSRR MMIO32(GPIOB + 0x18) // GPIOB bit set/reset register,
|
||||
#define GPIOB_LCKR MMIO32(GPIOB + 0x1C) // GPIOB configuration lock register,
|
||||
#define GPIOB_AFR MMIO64(GPIOB + 0x20) // GPIOB alternate function low register,
|
||||
#define GPIOB_BRR MMIO32(GPIOB + 0x28) // GPIOB bit reset register,
|
||||
|
||||
#define GPIOC_MODER MMIO32(GPIOC + 0x00) // GPIOC pin mode register,
|
||||
#define GPIOC_OTYPER MMIO32(GPIOC + 0x04) // GPIOC output type register,
|
||||
#define GPIOC_OSPEEDR MMIO32(GPIOC + 0x08) // GPIOC output speed register,
|
||||
#define GPIOC_PUPDR MMIO32(GPIOC + 0x0C) // GPIOC pull-up/pull-down register,
|
||||
#define GPIOC_IDR MMIO32(GPIOC + 0x10) // GPIOC input data register,
|
||||
#define GPIOC_ODR MMIO32(GPIOC + 0x14) // GPIOC output data register,
|
||||
#define GPIOC_BSRR MMIO32(GPIOC + 0x18) // GPIOC bit set/reset register,
|
||||
#define GPIOC_LCKR MMIO32(GPIOC + 0x1C) // GPIOC configuration lock register,
|
||||
#define GPIOC_AFR MMIO64(GPIOC + 0x20) // GPIOC alternate function low register,
|
||||
#define GPIOC_BRR MMIO32(GPIOC + 0x28) // GPIOC bit reset register,
|
||||
|
||||
#define GPIOD_MODER MMIO32(GPIOD + 0x00) // GPIOD pin mode register,
|
||||
#define GPIOD_OTYPER MMIO32(GPIOD + 0x04) // GPIOD output type register,
|
||||
#define GPIOD_OSPEEDR MMIO32(GPIOD + 0x08) // GPIOD output speed register,
|
||||
#define GPIOD_PUPDR MMIO32(GPIOD + 0x0C) // GPIOD pull-up/pull-down register,
|
||||
#define GPIOD_IDR MMIO32(GPIOD + 0x10) // GPIOD input data register,
|
||||
#define GPIOD_ODR MMIO32(GPIOD + 0x14) // GPIOD output data register,
|
||||
#define GPIOD_BSRR MMIO32(GPIOD + 0x18) // GPIOD bit set/reset register,
|
||||
#define GPIOD_LCKR MMIO32(GPIOD + 0x1C) // GPIOD configuration lock register,
|
||||
#define GPIOD_AFR MMIO64(GPIOD + 0x20) // GPIOD alternate function low register,
|
||||
#define GPIOD_BRR MMIO32(GPIOD + 0x28) // GPIOD bit reset register,
|
||||
|
||||
#define GPIOE_MODER MMIO32(GPIOE + 0x00) // GPIOE pin mode register,
|
||||
#define GPIOE_OTYPER MMIO32(GPIOE + 0x04) // GPIOE output type register,
|
||||
#define GPIOE_OSPEEDR MMIO32(GPIOE + 0x08) // GPIOE output speed register,
|
||||
#define GPIOE_PUPDR MMIO32(GPIOE + 0x0C) // GPIOE pull-up/pull-down register,
|
||||
#define GPIOE_IDR MMIO32(GPIOE + 0x10) // GPIOE input data register,
|
||||
#define GPIOE_ODR MMIO32(GPIOE + 0x14) // GPIOE output data register,
|
||||
#define GPIOE_BSRR MMIO32(GPIOE + 0x18) // GPIOE bit set/reset register,
|
||||
#define GPIOE_LCKR MMIO32(GPIOE + 0x1C) // GPIOE configuration lock register,
|
||||
#define GPIOE_AFR MMIO64(GPIOE + 0x20) // GPIOE alternate function low register,
|
||||
#define GPIOE_BRR MMIO32(GPIOE + 0x28) // GPIOE bit reset register,
|
||||
|
||||
#define GPIOF_MODER MMIO32(GPIOF + 0x00) // GPIOF pin mode register,
|
||||
#define GPIOF_OTYPER MMIO32(GPIOF + 0x04) // GPIOF output type register,
|
||||
#define GPIOF_OSPEEDR MMIO32(GPIOF + 0x08) // GPIOF output speed register,
|
||||
#define GPIOF_PUPDR MMIO32(GPIOF + 0x0C) // GPIOF pull-up/pull-down register,
|
||||
#define GPIOF_IDR MMIO32(GPIOF + 0x10) // GPIOF input data register,
|
||||
#define GPIOF_ODR MMIO32(GPIOF + 0x14) // GPIOF output data register,
|
||||
#define GPIOF_BSRR MMIO32(GPIOF + 0x18) // GPIOF bit set/reset register,
|
||||
#define GPIOF_LCKR MMIO32(GPIOF + 0x1C) // GPIOF configuration lock register,
|
||||
#define GPIOF_AFR MMIO64(GPIOF + 0x20) // GPIOF alternate function low register,
|
||||
#define GPIOF_BRR MMIO32(GPIOF + 0x28) // GPIOF bit reset register,
|
||||
|
||||
#define GPIOG_MODER MMIO32(GPIOG + 0x00) // GPIOG pin mode register,
|
||||
#define GPIOG_OTYPER MMIO32(GPIOG + 0x04) // GPIOG output type register,
|
||||
#define GPIOG_OSPEEDR MMIO32(GPIOG + 0x08) // GPIOG output speed register,
|
||||
#define GPIOG_PUPDR MMIO32(GPIOG + 0x0C) // GPIOG pull-up/pull-down register,
|
||||
#define GPIOG_IDR MMIO32(GPIOG + 0x10) // GPIOG input data register,
|
||||
#define GPIOG_ODR MMIO32(GPIOG + 0x14) // GPIOG output data register,
|
||||
#define GPIOG_BSRR MMIO32(GPIOG + 0x18) // GPIOG bit set/reset register,
|
||||
#define GPIOG_LCKR MMIO32(GPIOG + 0x1C) // GPIOG configuration lock register,
|
||||
#define GPIOG_AFR MMIO64(GPIOG + 0x20) // GPIOG alternate function low register,
|
||||
#define GPIOG_BRR MMIO32(GPIOG + 0x28) // GPIOG bit reset register,
|
||||
|
||||
#define GPIOH_MODER MMIO32(GPIOH + 0x00) // GPIOH pin mode register,
|
||||
#define GPIOH_OTYPER MMIO32(GPIOH + 0x04) // GPIOH output type register,
|
||||
#define GPIOH_OSPEEDR MMIO32(GPIOH + 0x08) // GPIOH output speed register,
|
||||
#define GPIOH_PUPDR MMIO32(GPIOH + 0x0C) // GPIOH pull-up/pull-down register,
|
||||
#define GPIOH_IDR MMIO32(GPIOH + 0x10) // GPIOH input data register,
|
||||
#define GPIOH_ODR MMIO32(GPIOH + 0x14) // GPIOH output data register,
|
||||
#define GPIOH_BSRR MMIO32(GPIOH + 0x18) // GPIOH bit set/reset register,
|
||||
#define GPIOH_LCKR MMIO32(GPIOH + 0x1C) // GPIOH configuration lock register,
|
||||
#define GPIOH_AFR MMIO64(GPIOH + 0x20) // GPIOH alternate function low register,
|
||||
#define GPIOH_BRR MMIO32(GPIOH + 0x28) // GPIOH bit reset register,
|
@ -0,0 +1,373 @@ |
||||
#pragma once |
||||
|
||||
#include "common.h" |
||||
|
||||
// RCC registers
|
||||
|
||||
#define RCC_CR MMIO32(_RCC + 0x00) // RCC clock control register,
|
||||
#define RCC_ICSCR MMIO32(_RCC + 0x04) // RCC Internal clock sources calibration register,
|
||||
#define RCC_CFGR MMIO32(_RCC + 0x08) // RCC Clock configuration register,
|
||||
#define RCC_CIR MMIO32(_RCC + 0x0C) // RCC Clock interrupt register,
|
||||
#define RCC_AHBRSTR MMIO32(_RCC + 0x10) // RCC AHB peripheral reset register,
|
||||
#define RCC_APB2RSTR MMIO32(_RCC + 0x14) // RCC APB2 peripheral reset register,
|
||||
#define RCC_APB1RSTR MMIO32(_RCC + 0x18) // RCC APB1 peripheral reset register,
|
||||
#define RCC_AHBENR MMIO32(_RCC + 0x1C) // RCC AHB peripheral clock enable register,
|
||||
#define RCC_APB2ENR MMIO32(_RCC + 0x20) // RCC APB2 peripheral clock enable register,
|
||||
#define RCC_APB1ENR MMIO32(_RCC + 0x24) // RCC APB1 peripheral clock enable register,
|
||||
#define RCC_AHBLPENR MMIO32(_RCC + 0x28) // RCC AHB peripheral clock enable in low power mode register,
|
||||
#define RCC_APB2LPENR MMIO32(_RCC + 0x2C) // RCC APB2 peripheral clock enable in low power mode register,
|
||||
#define RCC_APB1LPENR MMIO32(_RCC + 0x30) // RCC APB1 peripheral clock enable in low power mode register,
|
||||
#define RCC_CSR MMIO32(_RCC + 0x34) // RCC Control/status register,
|
||||
|
||||
|
||||
|
||||
//****************************************************************************
|
||||
//*
|
||||
//* BIT MASKS AND DEFINITIONS
|
||||
//*
|
||||
//****************************************************************************
|
||||
|
||||
|
||||
//******************* Bit definition for RCC_CR register *******************
|
||||
#define RCC_CR_HSION 0x00000001 // Internal High Speed clock enable
|
||||
#define RCC_CR_HSIRDY 0x00000002 // Internal High Speed clock ready flag
|
||||
|
||||
#define RCC_CR_MSION 0x00000100 // Internal Multi Speed clock enable
|
||||
#define RCC_CR_MSIRDY 0x00000200 // Internal Multi Speed clock ready flag
|
||||
|
||||
#define RCC_CR_HSEON 0x00010000 // External High Speed clock enable
|
||||
#define RCC_CR_HSERDY 0x00020000 // External High Speed clock ready flag
|
||||
#define RCC_CR_HSEBYP 0x00040000 // External High Speed clock Bypass
|
||||
|
||||
#define RCC_CR_PLLON 0x01000000 // PLL enable
|
||||
#define RCC_CR_PLLRDY 0x02000000 // PLL clock ready flag
|
||||
#define RCC_CR_CSSON 0x10000000 // Clock Security System enable
|
||||
|
||||
#define RCC_CR_RTCPRE 0x60000000 // RTC/LCD Prescaler
|
||||
|
||||
// prescaler levels
|
||||
#define RCC_CR_RTCPRE_DIV2 0x00000000 |
||||
#define RCC_CR_RTCPRE_DIV4 0x20000000 |
||||
#define RCC_CR_RTCPRE_DIV8 0x40000000 |
||||
#define RCC_CR_RTCPRE_DIV16 0x60000000 |
||||
|
||||
//******************* Bit definition for RCC_ICSCR register ****************
|
||||
#define RCC_ICSCR_HSICAL 0x000000FF // Internal High Speed clock Calibration
|
||||
#define RCC_ICSCR_HSITRIM 0x00001F00 // Internal High Speed clock trimming
|
||||
|
||||
#define RCC_ICSCR_MSIRANGE 0x0000E000 // Internal Multi Speed clock Range
|
||||
#define RCC_ICSCR_MSIRANGE_0 0x00000000 // Internal Multi Speed clock Range 65.536 KHz
|
||||
#define RCC_ICSCR_MSIRANGE_1 0x00002000 // Internal Multi Speed clock Range 131.072 KHz
|
||||
#define RCC_ICSCR_MSIRANGE_2 0x00004000 // Internal Multi Speed clock Range 262.144 KHz
|
||||
#define RCC_ICSCR_MSIRANGE_3 0x00006000 // Internal Multi Speed clock Range 524.288 KHz
|
||||
#define RCC_ICSCR_MSIRANGE_4 0x00008000 // Internal Multi Speed clock Range 1.048 MHz
|
||||
#define RCC_ICSCR_MSIRANGE_5 0x0000A000 // Internal Multi Speed clock Range 2.097 MHz
|
||||
#define RCC_ICSCR_MSIRANGE_6 0x0000C000 // Internal Multi Speed clock Range 4.194 MHz
|
||||
#define RCC_ICSCR_MSICAL 0x00FF0000 // Internal Multi Speed clock Calibration
|
||||
#define RCC_ICSCR_MSITRIM 0xFF000000 // Internal Multi Speed clock trimming
|
||||
|
||||
//******************* Bit definition for RCC_CFGR register *****************
|
||||
#define RCC_CFGR_SW 0x00000003 // SW[1:0] bits (System clock Switch)
|
||||
|
||||
// SW configuration
|
||||
#define RCC_CFGR_SW_MSI 0x00000000 // MSI selected as system clock
|
||||
#define RCC_CFGR_SW_HSI 0x00000001 // HSI selected as system clock
|
||||
#define RCC_CFGR_SW_HSE 0x00000002 // HSE selected as system clock
|
||||
#define RCC_CFGR_SW_PLL 0x00000003 // PLL selected as system clock
|
||||
|
||||
#define RCC_CFGR_SWS 0x0000000C // SWS[1:0] bits (System Clock Switch Status)
|
||||
|
||||
// SWS configuration
|
||||
#define RCC_CFGR_SWS_MSI 0x00000000 // MSI oscillator used as system clock
|
||||
#define RCC_CFGR_SWS_HSI 0x00000004 // HSI oscillator used as system clock
|
||||
#define RCC_CFGR_SWS_HSE 0x00000008 // HSE oscillator used as system clock
|
||||
#define RCC_CFGR_SWS_PLL 0x0000000C // PLL used as system clock
|
||||
|
||||
#define RCC_CFGR_HPRE 0x000000F0 // HPRE[3:0] bits (AHB prescaler)
|
||||
|
||||
// HPRE configuration
|
||||
#define RCC_CFGR_HPRE_DIV1 0x00000000 // SYSCLK not divided
|
||||
#define RCC_CFGR_HPRE_DIV2 0x00000080 // SYSCLK divided by 2
|
||||
#define RCC_CFGR_HPRE_DIV4 0x00000090 // SYSCLK divided by 4
|
||||
#define RCC_CFGR_HPRE_DIV8 0x000000A0 // SYSCLK divided by 8
|
||||
#define RCC_CFGR_HPRE_DIV16 0x000000B0 // SYSCLK divided by 16
|
||||
#define RCC_CFGR_HPRE_DIV64 0x000000C0 // SYSCLK divided by 64
|
||||
#define RCC_CFGR_HPRE_DIV128 0x000000D0 // SYSCLK divided by 128
|
||||
#define RCC_CFGR_HPRE_DIV256 0x000000E0 // SYSCLK divided by 256
|
||||
#define RCC_CFGR_HPRE_DIV512 0x000000F0 // SYSCLK divided by 512
|
||||
|
||||
#define RCC_CFGR_PPRE1 0x00000700 // PRE1[2:0] bits (APB1 prescaler)
|
||||
|
||||
// PPRE1 configuration
|
||||
#define RCC_CFGR_PPRE1_DIV1 0x00000000 // HCLK not divided
|
||||
#define RCC_CFGR_PPRE1_DIV2 0x00000400 // HCLK divided by 2
|
||||
#define RCC_CFGR_PPRE1_DIV4 0x00000500 // HCLK divided by 4
|
||||
#define RCC_CFGR_PPRE1_DIV8 0x00000600 // HCLK divided by 8
|
||||
#define RCC_CFGR_PPRE1_DIV16 0x00000700 // HCLK divided by 16
|
||||
|
||||
#define RCC_CFGR_PPRE2 0x00003800 // PRE2[2:0] bits (APB2 prescaler)
|
||||
|
||||
// PPRE2 configuration
|
||||
#define RCC_CFGR_PPRE2_DIV1 0x00000000 // HCLK not divided
|
||||
#define RCC_CFGR_PPRE2_DIV2 0x00002000 // HCLK divided by 2
|
||||
#define RCC_CFGR_PPRE2_DIV4 0x00002800 // HCLK divided by 4
|
||||
#define RCC_CFGR_PPRE2_DIV8 0x00003000 // HCLK divided by 8
|
||||
#define RCC_CFGR_PPRE2_DIV16 0x00003800 // HCLK divided by 16
|
||||
|
||||
// PLL entry clock source
|
||||
#define RCC_CFGR_PLLSRC 0x00010000 // PLL entry clock source
|
||||
|
||||
#define RCC_CFGR_PLLSRC_HSI 0x00000000 // HSI as PLL entry clock source
|
||||
#define RCC_CFGR_PLLSRC_HSE 0x00010000 // HSE as PLL entry clock source
|
||||
|
||||
|
||||
#define RCC_CFGR_PLLMUL 0x003C0000 // PLLMUL[3:0] bits (PLL multiplication factor)
|
||||
|
||||
// PLLMUL configuration
|
||||
#define RCC_CFGR_PLLMUL3 0x00000000 // PLL input clock * 3
|
||||
#define RCC_CFGR_PLLMUL4 0x00040000 // PLL input clock * 4
|
||||
#define RCC_CFGR_PLLMUL6 0x00080000 // PLL input clock * 6
|
||||
#define RCC_CFGR_PLLMUL8 0x000C0000 // PLL input clock * 8
|
||||
#define RCC_CFGR_PLLMUL12 0x00100000 // PLL input clock * 12
|
||||
#define RCC_CFGR_PLLMUL16 0x00140000 // PLL input clock * 16
|
||||
#define RCC_CFGR_PLLMUL24 0x00180000 // PLL input clock * 24
|
||||
#define RCC_CFGR_PLLMUL32 0x001C0000 // PLL input clock * 32
|
||||
#define RCC_CFGR_PLLMUL48 0x00200000 // PLL input clock * 48
|
||||
|
||||
// PLLDIV configuration
|
||||
#define RCC_CFGR_PLLDIV 0x00C00000 // PLLDIV[1:0] bits (PLL Output Division)
|
||||
|
||||
// PLLDIV configuration
|
||||
#define RCC_CFGR_PLLDIV1 0x00000000 // PLL clock output = CKVCO / 1
|
||||
#define RCC_CFGR_PLLDIV2 0x00400000 // PLL clock output = CKVCO / 2
|
||||
#define RCC_CFGR_PLLDIV3 0x00800000 // PLL clock output = CKVCO / 3
|
||||
#define RCC_CFGR_PLLDIV4 0x00C00000 // PLL clock output = CKVCO / 4
|
||||
|
||||
|
||||
#define RCC_CFGR_MCOSEL 0x07000000 // MCO[2:0] bits (Microcontroller Clock Output)
|
||||
|
||||
// MCO configuration
|
||||
#define RCC_CFGR_MCO_NOCLOCK 0x00000000 // No clock
|
||||
#define RCC_CFGR_MCO_SYSCLK 0x01000000 // System clock selected
|
||||
#define RCC_CFGR_MCO_HSI 0x02000000 // Internal 16 MHz RC oscillator clock selected
|
||||
#define RCC_CFGR_MCO_MSI 0x03000000 // Internal Medium Speed RC oscillator clock selected
|
||||
#define RCC_CFGR_MCO_HSE 0x04000000 // External 1-25 MHz oscillator clock selected
|
||||
#define RCC_CFGR_MCO_PLL 0x05000000 // PLL clock divided
|
||||
#define RCC_CFGR_MCO_LSI 0x06000000 // LSI selected
|
||||
#define RCC_CFGR_MCO_LSE 0x07000000 // LSE selected
|
||||
|
||||
#define RCC_CFGR_MCOPRE 0x70000000 // MCOPRE[2:0] bits (Microcontroller Clock Output Prescaler)
|
||||
|
||||
// MCO Prescaler configuration
|
||||
#define RCC_CFGR_MCO_DIV1 0x00000000 // MCO Clock divided by 1
|
||||
#define RCC_CFGR_MCO_DIV2 0x10000000 // MCO Clock divided by 2
|
||||
#define RCC_CFGR_MCO_DIV4 0x20000000 // MCO Clock divided by 4
|
||||
#define RCC_CFGR_MCO_DIV8 0x30000000 // MCO Clock divided by 8
|
||||
#define RCC_CFGR_MCO_DIV16 0x40000000 // MCO Clock divided by 16
|
||||
|
||||
// ****************** Bit definition for RCC_CIR register *******************
|
||||
#define RCC_CIR_LSIRDYF 0x00000001 // LSI Ready Interrupt flag
|
||||
#define RCC_CIR_LSERDYF 0x00000002 // LSE Ready Interrupt flag
|
||||
#define RCC_CIR_HSIRDYF 0x00000004 // HSI Ready Interrupt flag
|
||||
#define RCC_CIR_HSERDYF 0x00000008 // HSE Ready Interrupt flag
|
||||
#define RCC_CIR_PLLRDYF 0x00000010 // PLL Ready Interrupt flag
|
||||
#define RCC_CIR_MSIRDYF 0x00000020 // MSI Ready Interrupt flag
|
||||
#define RCC_CIR_LSECSS 0x00000040 // LSE CSS Interrupt flag
|
||||
#define RCC_CIR_CSSF 0x00000080 // Clock Security System Interrupt flag
|
||||
|
||||
#define RCC_CIR_LSIRDYIE 0x00000100 // LSI Ready Interrupt Enable
|
||||
#define RCC_CIR_LSERDYIE 0x00000200 // LSE Ready Interrupt Enable
|
||||
#define RCC_CIR_HSIRDYIE 0x00000400 // HSI Ready Interrupt Enable
|
||||
#define RCC_CIR_HSERDYIE 0x00000800 // HSE Ready Interrupt Enable
|
||||
#define RCC_CIR_PLLRDYIE 0x00001000 // PLL Ready Interrupt Enable
|
||||
#define RCC_CIR_MSIRDYIE 0x00002000 // MSI Ready Interrupt Enable
|
||||
#define RCC_CIR_LSECSSIE 0x00004000 // LSE CSS Interrupt Enable
|
||||
|
||||
#define RCC_CIR_LSIRDYC 0x00010000 // LSI Ready Interrupt Clear
|
||||
#define RCC_CIR_LSERDYC 0x00020000 // LSE Ready Interrupt Clear
|
||||
#define RCC_CIR_HSIRDYC 0x00040000 // HSI Ready Interrupt Clear
|
||||
#define RCC_CIR_HSERDYC 0x00080000 // HSE Ready Interrupt Clear
|
||||
#define RCC_CIR_PLLRDYC 0x00100000 // PLL Ready Interrupt Clear
|
||||
#define RCC_CIR_MSIRDYC 0x00200000 // MSI Ready Interrupt Clear
|
||||
#define RCC_CIR_LSECSSC 0x00400000 // LSE CSS Interrupt Clear
|
||||
#define RCC_CIR_CSSC 0x00800000 // Clock Security System Interrupt Clear
|
||||
|
||||
|
||||
//**************** Bit definition for RCC_AHBRSTR register *****************
|
||||
#define RCC_AHBRSTR_GPIOARST 0x00000001 // GPIO port A reset
|
||||
#define RCC_AHBRSTR_GPIOBRST 0x00000002 // GPIO port B reset
|
||||
#define RCC_AHBRSTR_GPIOCRST 0x00000004 // GPIO port C reset
|
||||
#define RCC_AHBRSTR_GPIODRST 0x00000008 // GPIO port D reset
|
||||
#define RCC_AHBRSTR_GPIOERST 0x00000010 // GPIO port E reset
|
||||
#define RCC_AHBRSTR_GPIOHRST 0x00000020 // GPIO port H reset
|
||||
#define RCC_AHBRSTR_GPIOFRST 0x00000040 // GPIO port F reset
|
||||
#define RCC_AHBRSTR_GPIOGRST 0x00000080 // GPIO port G reset
|
||||
#define RCC_AHBRSTR_CRCRST 0x00001000 // CRC reset
|
||||
#define RCC_AHBRSTR_FLITFRST 0x00008000 // FLITF reset
|
||||
#define RCC_AHBRSTR_DMA1RST 0x01000000 // DMA1 reset
|
||||
#define RCC_AHBRSTR_DMA2RST 0x02000000 // DMA2 reset
|
||||
#define RCC_AHBRSTR_AESRST 0x08000000 // AES reset
|
||||
#define RCC_AHBRSTR_FSMCRST 0x40000000 // FSMC reset
|
||||
|
||||
//**************** Bit definition for RCC_APB2RSTR register ****************
|
||||
#define RCC_APB2RSTR_SYSCFGRST 0x00000001 // System Configuration SYSCFG reset
|
||||
#define RCC_APB2RSTR_TIM9RST 0x00000004 // TIM9 reset
|
||||
#define RCC_APB2RSTR_TIM10RST 0x00000008 // TIM10 reset
|
||||
#define RCC_APB2RSTR_TIM11RST 0x00000010 // TIM11 reset
|
||||
#define RCC_APB2RSTR_ADC1RST 0x00000200 // ADC1 reset
|
||||
#define RCC_APB2RSTR_SDIORST 0x00000800 // SDIO reset
|
||||
#define RCC_APB2RSTR_SPI1RST 0x00001000 // SPI1 reset
|
||||
#define RCC_APB2RSTR_USART1RST 0x00004000 // USART1 reset
|
||||
|
||||
//**************** Bit definition for RCC_APB1RSTR register ****************
|
||||
#define RCC_APB1RSTR_TIM2RST 0x00000001 // Timer 2 reset
|
||||
#define RCC_APB1RSTR_TIM3RST 0x00000002 // Timer 3 reset
|
||||
#define RCC_APB1RSTR_TIM4RST 0x00000004 // Timer 4 reset
|
||||
#define RCC_APB1RSTR_TIM5RST 0x00000008 // Timer 5 reset
|
||||
#define RCC_APB1RSTR_TIM6RST 0x00000010 // Timer 6 reset
|
||||
#define RCC_APB1RSTR_TIM7RST 0x00000020 // Timer 7 reset
|
||||
#define RCC_APB1RSTR_LCDRST 0x00000200 // LCD reset
|
||||
#define RCC_APB1RSTR_WWDGRST 0x00000800 // Window Watchdog reset
|
||||
#define RCC_APB1RSTR_SPI2RST 0x00004000 // SPI 2 reset
|
||||
#define RCC_APB1RSTR_SPI3RST 0x00008000 // SPI 3 reset
|
||||
#define RCC_APB1RSTR_USART2RST 0x00020000 // USART 2 reset
|
||||
#define RCC_APB1RSTR_USART3RST 0x00040000 // USART 3 reset
|
||||
#define RCC_APB1RSTR_UART4RST 0x00080000 // UART 4 reset
|
||||
#define RCC_APB1RSTR_UART5RST 0x00100000 // UART 5 reset
|
||||
#define RCC_APB1RSTR_I2C1RST 0x00200000 // I2C 1 reset
|
||||
#define RCC_APB1RSTR_I2C2RST 0x00400000 // I2C 2 reset
|
||||
#define RCC_APB1RSTR_USBRST 0x00800000 // USB reset
|
||||
#define RCC_APB1RSTR_PWRRST 0x10000000 // Power interface reset
|
||||
#define RCC_APB1RSTR_DACRST 0x20000000 // DAC interface reset
|
||||
#define RCC_APB1RSTR_COMPRST 0x80000000 // Comparator interface reset
|
||||
|
||||
//***************** Bit definition for RCC_AHBENR register *****************
|
||||
#define RCC_AHBENR_GPIOAEN 0x00000001 // GPIO port A clock enable
|
||||
#define RCC_AHBENR_GPIOBEN 0x00000002 // GPIO port B clock enable
|
||||
#define RCC_AHBENR_GPIOCEN 0x00000004 // GPIO port C clock enable
|
||||
#define RCC_AHBENR_GPIODEN 0x00000008 // GPIO port D clock enable
|
||||
#define RCC_AHBENR_GPIOEEN 0x00000010 // GPIO port E clock enable
|
||||
#define RCC_AHBENR_GPIOHEN 0x00000020 // GPIO port H clock enable
|
||||
#define RCC_AHBENR_GPIOFEN 0x00000040 // GPIO port F clock enable
|
||||
#define RCC_AHBENR_GPIOGEN 0x00000080 // GPIO port G clock enable
|
||||
#define RCC_AHBENR_CRCEN 0x00001000 // CRC clock enable
|
||||
#define RCC_AHBENR_FLITFEN 0x00008000 // FLITF clock enable (has effect only when the Flash memory is in power down mode)
|
||||
#define RCC_AHBENR_DMA1EN 0x01000000 // DMA1 clock enable
|
||||
#define RCC_AHBENR_DMA2EN 0x02000000 // DMA2 clock enable
|
||||
#define RCC_AHBENR_AESEN 0x08000000 // AES clock enable
|
||||
#define RCC_AHBENR_FSMCEN 0x40000000 // FSMC clock enable
|
||||
|
||||
|
||||
//***************** Bit definition for RCC_APB2ENR register ****************
|
||||
#define RCC_APB2ENR_SYSCFGEN 0x00000001 // System Configuration SYSCFG clock enable
|
||||
#define RCC_APB2ENR_TIM9EN 0x00000004 // TIM9 interface clock enable
|
||||
#define RCC_APB2ENR_TIM10EN 0x00000008 // TIM10 interface clock enable
|
||||
#define RCC_APB2ENR_TIM11EN 0x00000010 // TIM11 Timer clock enable
|
||||
#define RCC_APB2ENR_ADC1EN 0x00000200 // ADC1 clock enable
|
||||
#define RCC_APB2ENR_SDIOEN 0x00000800 // SDIO clock enable
|
||||
#define RCC_APB2ENR_SPI1EN 0x00001000 // SPI1 clock enable
|
||||
#define RCC_APB2ENR_USART1EN 0x00004000 // USART1 clock enable
|
||||
|
||||
|
||||
//**************** Bit definition for RCC_APB1ENR register *****************
|
||||
#define RCC_APB1ENR_TIM2EN 0x00000001 // Timer 2 clock enabled
|
||||
#define RCC_APB1ENR_TIM3EN 0x00000002 // Timer 3 clock enable
|
||||
#define RCC_APB1ENR_TIM4EN 0x00000004 // Timer 4 clock enable
|
||||
#define RCC_APB1ENR_TIM5EN 0x00000008 // Timer 5 clock enable
|
||||
#define RCC_APB1ENR_TIM6EN 0x00000010 // Timer 6 clock enable
|
||||
#define RCC_APB1ENR_TIM7EN 0x00000020 // Timer 7 clock enable
|
||||
#define RCC_APB1ENR_LCDEN 0x00000200 // LCD clock enable
|
||||
#define RCC_APB1ENR_WWDGEN 0x00000800 // Window Watchdog clock enable
|
||||
#define RCC_APB1ENR_SPI2EN 0x00004000 // SPI 2 clock enable
|
||||
#define RCC_APB1ENR_SPI3EN 0x00008000 // SPI 3 clock enable
|
||||
#define RCC_APB1ENR_USART2EN 0x00020000 // USART 2 clock enable
|
||||
#define RCC_APB1ENR_USART3EN 0x00040000 // USART 3 clock enable
|
||||
#define RCC_APB1ENR_UART4EN 0x00080000 // UART 4 clock enable
|
||||
#define RCC_APB1ENR_UART5EN 0x00100000 // UART 5 clock enable
|
||||
#define RCC_APB1ENR_I2C1EN 0x00200000 // I2C 1 clock enable
|
||||
#define RCC_APB1ENR_I2C2EN 0x00400000 // I2C 2 clock enable
|
||||
#define RCC_APB1ENR_USBEN 0x00800000 // USB clock enable
|
||||
#define RCC_APB1ENR_PWREN 0x10000000 // Power interface clock enable
|
||||
#define RCC_APB1ENR_DACEN 0x20000000 // DAC interface clock enable
|
||||
#define RCC_APB1ENR_COMPEN 0x80000000 // Comparator interface clock enable
|
||||
|
||||
//***************** Bit definition for RCC_AHBLPENR register ***************
|
||||
#define RCC_AHBLPENR_GPIOALPEN 0x00000001 // GPIO port A clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_GPIOBLPEN 0x00000002 // GPIO port B clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_GPIOCLPEN 0x00000004 // GPIO port C clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_GPIODLPEN 0x00000008 // GPIO port D clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_GPIOELPEN 0x00000010 // GPIO port E clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_GPIOHLPEN 0x00000020 // GPIO port H clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_GPIOFLPEN 0x00000040 // GPIO port F clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_GPIOGLPEN 0x00000080 // GPIO port G clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_CRCLPEN 0x00001000 // CRC clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_FLITFLPEN 0x00008000 // Flash Interface clock enabled in sleep mode (has effect only when the Flash memory is in power down mode)
|
||||
#define RCC_AHBLPENR_SRAMLPEN 0x00010000 // SRAM clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_DMA1LPEN 0x01000000 // DMA1 clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_DMA2LPEN 0x02000000 // DMA2 clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_AESLPEN 0x08000000 // AES clock enabled in sleep mode
|
||||
#define RCC_AHBLPENR_FSMCLPEN 0x40000000 // FSMC clock enabled in sleep mode
|
||||
|
||||
//***************** Bit definition for RCC_APB2LPENR register **************
|
||||
#define RCC_APB2LPENR_SYSCFGLPEN 0x00000001 // System Configuration SYSCFG clock enabled in sleep mode
|
||||
#define RCC_APB2LPENR_TIM9LPEN 0x00000004 // TIM9 interface clock enabled in sleep mode
|
||||
#define RCC_APB2LPENR_TIM10LPEN 0x00000008 // TIM10 interface clock enabled in sleep mode
|
||||
#define RCC_APB2LPENR_TIM11LPEN 0x00000010 // TIM11 Timer clock enabled in sleep mode
|
||||
#define RCC_APB2LPENR_ADC1LPEN 0x00000200 // ADC1 clock enabled in sleep mode
|
||||
#define RCC_APB2LPENR_SDIOLPEN 0x00000800 // SDIO clock enabled in sleep mode
|
||||
#define RCC_APB2LPENR_SPI1LPEN 0x00001000 // SPI1 clock enabled in sleep mode
|
||||
#define RCC_APB2LPENR_USART1LPEN 0x00004000 // USART1 clock enabled in sleep mode
|
||||
|
||||
//**************** Bit definition for RCC_APB1LPENR register ***************
|
||||
#define RCC_APB1LPENR_TIM2LPEN 0x00000001 // Timer 2 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_TIM3LPEN 0x00000002 // Timer 3 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_TIM4LPEN 0x00000004 // Timer 4 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_TIM5LPEN 0x00000008 // Timer 5 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_TIM6LPEN 0x00000010 // Timer 6 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_TIM7LPEN 0x00000020 // Timer 7 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_LCDLPEN 0x00000200 // LCD clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_WWDGLPEN 0x00000800 // Window Watchdog clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_SPI2LPEN 0x00004000 // SPI 2 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_SPI3LPEN 0x00008000 // SPI 3 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_USART2LPEN 0x00020000 // USART 2 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_USART3LPEN 0x00040000 // USART 3 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_UART4LPEN 0x00080000 // UART 4 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_UART5LPEN 0x00100000 // UART 5 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_I2C1LPEN 0x00200000 // I2C 1 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_I2C2LPEN 0x00400000 // I2C 2 clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_USBLPEN 0x00800000 // USB clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_PWRLPEN 0x10000000 // Power interface clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_DACLPEN 0x20000000 // DAC interface clock enabled in sleep mode
|
||||
#define RCC_APB1LPENR_COMPLPEN 0x80000000 // Comparator interface clock enabled in sleep mode
|
||||
|
||||
//****************** Bit definition for RCC_CSR register *******************
|
||||
#define RCC_CSR_LSION 0x00000001 // Internal Low Speed oscillator enable
|
||||
#define RCC_CSR_LSIRDY 0x00000002 // Internal Low Speed oscillator Ready
|
||||
|
||||
#define RCC_CSR_LSEON 0x00000100 // External Low Speed oscillator enable
|
||||
#define RCC_CSR_LSERDY 0x00000200 // External Low Speed oscillator Ready
|
||||
#define RCC_CSR_LSEBYP 0x00000400 // External Low Speed oscillator Bypass
|
||||
#define RCC_CSR_LSECSSON 0x00000800 // External Low Speed oscillator CSS Enable
|
||||
#define RCC_CSR_LSECSSD 0x00001000 // External Low Speed oscillator CSS Detected
|
||||
|
||||
#define RCC_CSR_RTCSEL 0x00030000 // RTCSEL[1:0] bits (RTC clock source selection)
|
||||
#define RCC_CSR_RTCSEL_0 0x00010000 // Bit 0
|
||||
#define RCC_CSR_RTCSEL_1 0x00020000 // Bit 1
|
||||
|
||||
// RTC congiguration
|
||||
#define RCC_CSR_RTCSEL_NOCLOCK 0x00000000 // No clock
|
||||
#define RCC_CSR_RTCSEL_LSE 0x00010000 // LSE oscillator clock used as RTC clock
|
||||
#define RCC_CSR_RTCSEL_LSI 0x00020000 // LSI oscillator clock used as RTC clock
|
||||
#define RCC_CSR_RTCSEL_HSE 0x00030000 // HSE oscillator clock divided by 2, 4, 8 or 16 by RTCPRE used as RTC clock
|
||||
|
||||
#define RCC_CSR_RTCEN 0x00400000 // RTC clock enable
|
||||
#define RCC_CSR_RTCRST 0x00800000 // RTC reset
|
||||
|
||||
#define RCC_CSR_RMVF 0x01000000 // Remove reset flag
|
||||
#define RCC_CSR_OBLRSTF 0x02000000 // Option Bytes Loader reset flag
|
||||
#define RCC_CSR_PINRSTF 0x04000000 // PIN reset flag
|
||||
#define RCC_CSR_PORRSTF 0x08000000 // POR/PDR reset flag
|
||||
#define RCC_CSR_SFTRSTF 0x10000000 // Software Reset flag
|
||||
#define RCC_CSR_IWDGRSTF 0x20000000 // Independent Watchdog reset flag
|
||||
#define RCC_CSR_WWDGRSTF 0x40000000 // Window watchdog reset flag
|
||||
#define RCC_CSR_LPWRRSTF 0x80000000 // Low-Power reset flag
|
@ -0,0 +1,57 @@ |
||||
#pragma once |
||||
|
||||
#include "common.h" |
||||
|
||||
// AUTHOR : Ondrej Hruska
|
||||
// DATE : 12/2015
|
||||
// DESCR : Control registers and bit masks for SysTick
|
||||
|
||||
|
||||
//****************************************************************************
|
||||
//*
|
||||
//* REGISTERS
|
||||
//*
|
||||
//****************************************************************************
|
||||
|
||||
|
||||
#define SysTick_CSR MMIO32(_SCS_BASE + 0x010) // (R/W) SysTick Control and Status Register
|
||||
#define SysTick_RELOAD MMIO32(_SCS_BASE + 0x014) // (R/W) SysTick Reload Value Register
|
||||
#define SysTick_VAL MMIO32(_SCS_BASE + 0x018) // (R/W) SysTick Current Value Register
|
||||
#define SysTick_CALIB MMIO32(_SCS_BASE + 0x01C) // (R/ ) SysTick Calibration Value Register
|
||||
|
||||
|
||||
|
||||
//****************************************************************************
|
||||
//*
|
||||
//* BIT MASKS AND DEFINITIONS
|
||||
//*
|
||||
//****************************************************************************
|
||||
|
||||
|
||||
//**************** Bit definition for SysTick_CSR register ****************
|
||||
|
||||
#define SysTick_CSR_ENABLE 0x00000001 // Counter enable
|
||||
#define SysTick_CSR_TICKINT 0x00000002 // Enable interrupt when counter reaches zero
|
||||
#define SysTick_CSR_CLKSOURCE 0x00000004 // Clock source (0 - external, 1 - core clock)
|
||||
|
||||
#define SysTick_CSR_CLKSOURCE_CORE 0x00000004 // Clock source - core clock
|
||||
#define SysTick_CSR_CLKSOURCE_DIV8 0x00000000 // Clock source - core clock / 8
|
||||
|
||||
#define SysTick_CSR_COUNTFLAG 0x00010000 // Count Flag (only if interrupt is disabled)
|
||||
|
||||
|
||||
//**************** Bit definition for SysTick_LOAD register ****************
|
||||
|
||||
#define SysTick_RELOAD_MASK 0x00FFFFFF // Reload value used when the counter reaches 0
|
||||
|
||||
|
||||
//**************** Bit definition for SysTick_VAL register *****************
|
||||
|
||||
#define SysTick_VAL_MASK 0x00FFFFFF // Current value at the time the register is accessed
|
||||
|
||||
|
||||
//**************** Bit definition for SysTick_CALIB register ***************
|
||||
|
||||
#define SysTick_CALIB_TENMS 0x00FFFFFF // Reload value to use for 10ms timing
|
||||
#define SysTick_CALIB_SKEW 0x40000000 // Calibration value is not exactly 10 ms
|
||||
#define SysTick_CALIB_NOREF 0x80000000 // The reference clock is not provided
|
@ -0,0 +1,149 @@ |
||||
// AUTHOR : Ondrej Hruska
|
||||
// DATE : 12/2015
|
||||
// DESCR : Control registers and bit masks for USART
|
||||
//
|
||||
// Universal Synchronous Asynchronous Receiver Transmitter (USART)
|
||||
|
||||
|
||||
//****************************************************************************
|
||||
//*
|
||||
//* REGISTERS
|
||||
//*
|
||||
//****************************************************************************
|
||||
|
||||
// USART 1
|
||||
|
||||
#define USART1_SR MMIO32(_USART1 + 0x00) // USART1 Status register,
|
||||
#define USART1_DR MMIO32(_USART1 + 0x04) // USART1 Data register,
|
||||
#define USART1_BRR MMIO32(_USART1 + 0x08) // USART1 Baud rate register,
|
||||
#define USART1_CR1 MMIO32(_USART1 + 0x0C) // USART1 Control register 1,
|
||||
#define USART1_CR2 MMIO32(_USART1 + 0x10) // USART1 Control register 2,
|
||||
#define USART1_CR3 MMIO32(_USART1 + 0x14) // USART1 Control register 3,
|
||||
#define USART1_GTPR MMIO32(_USART1 + 0x18) // USART1 Guard time and prescaler register,
|
||||
|
||||
// USART 2
|
||||
|
||||
#define USART2_SR MMIO32(_USART2 + 0x00) // USART2 Status register,
|
||||
#define USART2_DR MMIO32(_USART2 + 0x04) // USART2 Data register,
|
||||
#define USART2_BRR MMIO32(_USART2 + 0x08) // USART2 Baud rate register,
|
||||
#define USART2_CR1 MMIO32(_USART2 + 0x0C) // USART2 Control register 1,
|
||||
#define USART2_CR2 MMIO32(_USART2 + 0x10) // USART2 Control register 2,
|
||||
#define USART2_CR3 MMIO32(_USART2 + 0x14) // USART2 Control register 3,
|
||||
#define USART2_GTPR MMIO32(_USART2 + 0x18) // USART2 Guard time and prescaler register,
|
||||
|
||||
// USART 3
|
||||
|
||||
#define USART3_SR MMIO32(_USART3 + 0x00) // USART3 Status register,
|
||||
#define USART3_DR MMIO32(_USART3 + 0x04) // USART3 Data register,
|
||||
#define USART3_BRR MMIO32(_USART3 + 0x08) // USART3 Baud rate register,
|
||||
#define USART3_CR1 MMIO32(_USART3 + 0x0C) // USART3 Control register 1,
|
||||
#define USART3_CR2 MMIO32(_USART3 + 0x10) // USART3 Control register 2,
|
||||
#define USART3_CR3 MMIO32(_USART3 + 0x14) // USART3 Control register 3,
|
||||
#define USART3_GTPR MMIO32(_USART3 + 0x18) // USART3 Guard time and prescaler register,
|
||||
|
||||
// USART 4
|
||||
|
||||
#define UART4_SR MMIO32(_UART4 + 0x00) // UART4 Status register,
|
||||
#define UART4_DR MMIO32(_UART4 + 0x04) // UART4 Data register,
|
||||
#define UART4_BRR MMIO32(_UART4 + 0x08) // UART4 Baud rate register,
|
||||
#define UART4_CR1 MMIO32(_UART4 + 0x0C) // UART4 Control register 1,
|
||||
#define UART4_CR2 MMIO32(_UART4 + 0x10) // UART4 Control register 2,
|
||||
#define UART4_CR3 MMIO32(_UART4 + 0x14) // UART4 Control register 3,
|
||||
#define UART4_GTPR MMIO32(_UART4 + 0x18) // UART4 Guard time and prescaler register,
|
||||
|
||||
// USART 5
|
||||
|
||||
#define UART5_SR MMIO32(_UART5 + 0x00) // UART5 Status register,
|
||||
#define UART5_DR MMIO32(_UART5 + 0x04) // UART5 Data register,
|
||||
#define UART5_BRR MMIO32(_UART5 + 0x08) // UART5 Baud rate register,
|
||||
#define UART5_CR1 MMIO32(_UART5 + 0x0C) // UART5 Control register 1,
|
||||
#define UART5_CR2 MMIO32(_UART5 + 0x10) // UART5 Control register 2,
|
||||
#define UART5_CR3 MMIO32(_UART5 + 0x14) // UART5 Control register 3,
|
||||
#define UART5_GTPR MMIO32(_UART5 + 0x18) // UART5 Guard time and prescaler register,
|
||||
|
||||
|
||||
|
||||
//****************************************************************************
|
||||
//*
|
||||
//* BIT MASKS AND DEFINITIONS
|
||||
//*
|
||||
//****************************************************************************
|
||||
|
||||
|
||||
//****************** Bit definition for USART_SR register ******************
|
||||
#define USART_SR_PE 0x0001 // Parity Error
|
||||
#define USART_SR_FE 0x0002 // Framing Error
|
||||
#define USART_SR_NE 0x0004 // Noise Error Flag
|
||||
#define USART_SR_ORE 0x0008 // OverRun Error
|
||||
#define USART_SR_IDLE 0x0010 // IDLE line detected
|
||||
#define USART_SR_RXNE 0x0020 // Read Data Register Not Empty
|
||||
#define USART_SR_TC 0x0040 // Transmission Complete
|
||||
#define USART_SR_TXE 0x0080 // Transmit Data Register Empty
|
||||
#define USART_SR_LBD 0x0100 // LIN Break Detection Flag
|
||||
#define USART_SR_CTS 0x0200 // CTS Flag
|
||||
|
||||
//****************** Bit definition for USART_DR register ******************
|
||||
#define USART_DR_DR 0x01FF // Data value
|
||||
|
||||
//***************** Bit definition for USART_BRR register ******************
|
||||
#define USART_BRR_DIV_FRACTION 0x000F // Fraction of USARTDIV
|
||||
#define USART_BRR_DIV_MANTISSA 0xFFF0 // Mantissa of USARTDIV
|
||||
|
||||
//***************** Bit definition for USART_CR1 register ******************
|
||||
#define USART_CR1_SBK 0x0001 // Send Break
|
||||
#define USART_CR1_RWU 0x0002 // Receiver wakeup
|
||||
#define USART_CR1_RE 0x0004 // Receiver Enable
|
||||
#define USART_CR1_TE 0x0008 // Transmitter Enable
|
||||
#define USART_CR1_IDLEIE 0x0010 // IDLE Interrupt Enable
|
||||
#define USART_CR1_RXNEIE 0x0020 // RXNE Interrupt Enable
|
||||
#define USART_CR1_TCIE 0x0040 // Transmission Complete Interrupt Enable
|
||||
#define USART_CR1_TXEIE 0x0080 // PE Interrupt Enable
|
||||
#define USART_CR1_PEIE 0x0100 // PE Interrupt Enable
|
||||
#define USART_CR1_PS 0x0200 // Parity Selection
|
||||
#define USART_CR1_PCE 0x0400 // Parity Control Enable
|
||||
#define USART_CR1_WAKE 0x0800 // Wakeup method
|
||||
#define USART_CR1_M 0x1000 // Word length
|
||||
#define USART_CR1_UE 0x2000 // USART Enable
|
||||
#define USART_CR1_OVER8 0x8000 // Oversampling by 8-bit mode
|
||||
|
||||
//***************** Bit definition for USART_CR2 register ******************
|
||||
#define USART_CR2_ADD 0x000F // Address of the USART node
|
||||
#define USART_CR2_LBDL 0x0020 // LIN Break Detection Length
|
||||
#define USART_CR2_LBDIE 0x0040 // LIN Break Detection Interrupt Enable
|
||||
#define USART_CR2_LBCL 0x0100 // Last Bit Clock pulse
|
||||
#define USART_CR2_CPHA 0x0200 // Clock Phase
|
||||
#define USART_CR2_CPOL 0x0400 // Clock Polarity
|
||||
#define USART_CR2_CLKEN 0x0800 // Clock Enable
|
||||
|
||||
#define USART_CR2_STOP 0x3000 // STOP[1:0] bits (STOP bits)
|
||||
#define USART_CR2_STOP_0 0x1000 // Bit 0
|
||||
#define USART_CR2_STOP_1 0x2000 // Bit 1
|
||||
|
||||
#define USART_CR2_LINEN 0x4000 // LIN mode enable
|
||||
|
||||
//***************** Bit definition for USART_CR3 register ******************
|
||||
#define USART_CR3_EIE 0x0001 // Error Interrupt Enable
|
||||
#define USART_CR3_IREN 0x0002 // IrDA mode Enable
|
||||
#define USART_CR3_IRLP 0x0004 // IrDA Low-Power
|
||||
#define USART_CR3_HDSEL 0x0008 // Half-Duplex Selection
|
||||
#define USART_CR3_NACK 0x0010 // Smartcard NACK enable
|
||||
#define USART_CR3_SCEN 0x0020 // Smartcard mode enable
|
||||
#define USART_CR3_DMAR 0x0040 // DMA Enable Receiver
|
||||
#define USART_CR3_DMAT 0x0080 // DMA Enable Transmitter
|
||||
#define USART_CR3_RTSE 0x0100 // RTS Enable
|
||||
#define USART_CR3_CTSE 0x0200 // CTS Enable
|
||||
#define USART_CR3_CTSIE 0x0400 // CTS Interrupt Enable
|
||||
#define USART_CR3_ONEBIT 0x0800 // One sample bit method enable
|
||||
|
||||
//***************** Bit definition for USART_GTPR register *****************
|
||||
#define USART_GTPR_PSC 0x00FF // PSC[7:0] bits (Prescaler value)
|
||||
#define USART_GTPR_PSC_0 0x0001 // Bit 0
|
||||
#define USART_GTPR_PSC_1 0x0002 // Bit 1
|
||||
#define USART_GTPR_PSC_2 0x0004 // Bit 2
|
||||
#define USART_GTPR_PSC_3 0x0008 // Bit 3
|
||||
#define USART_GTPR_PSC_4 0x0010 // Bit 4
|
||||
#define USART_GTPR_PSC_5 0x0020 // Bit 5
|
||||
#define USART_GTPR_PSC_6 0x0040 // Bit 6
|
||||
#define USART_GTPR_PSC_7 0x0080 // Bit 7
|
||||
|
||||
#define USART_GTPR_GT 0xFF00 // Guard time value
|
@ -0,0 +1,61 @@ |
||||
#include "common.h" |
||||
#include "gpio.h" |
||||
|
||||
static uint32_t rcc_gpio_mask(uint32_t gpio) |
||||
{ |
||||
switch (gpio) { |
||||
case GPIOA: return RCC_AHBENR_GPIOAEN; |
||||
case GPIOB: return RCC_AHBENR_GPIOBEN; |
||||
case GPIOC: return RCC_AHBENR_GPIOCEN; |
||||
case GPIOD: return RCC_AHBENR_GPIODEN; |
||||
case GPIOE: return RCC_AHBENR_GPIOEEN; |
||||
case GPIOF: return RCC_AHBENR_GPIOFEN; |
||||
case GPIOG: return RCC_AHBENR_GPIOGEN; |
||||
case GPIOH: return RCC_AHBENR_GPIOHEN; |
||||
default: return 0; |
||||
} |
||||
} |
||||
|
||||
|
||||
void gpio_enable(uint32_t gpio) |
||||
{ |
||||
RCC_AHBENR |= rcc_gpio_mask(gpio); |
||||
} |
||||
|
||||
|
||||
void gpio_disable(uint32_t gpio) |
||||
{ |
||||
RCC_AHBENR &= ~rcc_gpio_mask(gpio); |
||||
} |
||||
|
||||
|
||||
void gpio_set_af(uint32_t gpio, uint32_t pins, enum GPIO_AF af) |
||||
{ |
||||
gpio_enable(gpio); |
||||
|
||||
volatile uint32_t *moder = (uint32_t *) gpio + GPIO_MODER_offs; |
||||
volatile uint64_t *afr = (uint64_t *) gpio + GPIO_AFR_offs; |
||||
|
||||
BitFieldLoop(i, m, 16) { |
||||
if (pins & m) { |
||||
*moder &= ~(0b11 << i * 2); |
||||
*moder |= 0b10 << i * 2; |
||||
|
||||
*afr &= ~(0xF << i * 4); |
||||
*afr |= af << i * 4; |
||||
} |
||||
}; |
||||
} |
||||
|
||||
|
||||
void gpio_set_mode(uint32_t gpio, uint32_t pins, enum GPIO_MODE mode) |
||||
{ |
||||
volatile uint32_t *moder = (uint32_t *) gpio + GPIO_MODER_offs; |
||||
|
||||
BitFieldLoop(i, m, 16) { |
||||
if (pins & m) { |
||||
*moder &= ~(0b11 << i * 2); |
||||
*moder |= mode << i * 2; |
||||
} |
||||
}; |
||||
} |
@ -0,0 +1,60 @@ |
||||
#pragma once |
||||
|
||||
#include "common.h" |
||||
|
||||
enum GPIO_MODE { |
||||
MODER_INPUT = 0, |
||||
MODER_OUTPUT = 1, |
||||
MODER_AF = 2, |
||||
MODER_ANALOG = 3, |
||||
}; |
||||
|
||||
enum GPIO_AF { |
||||
AF0 = 0, |
||||
AF1 = 1, |
||||
AF2 = 2, |
||||
AF3 = 3, |
||||
AF4 = 4, |
||||
AF5 = 5, |
||||
AF6 = 6, |
||||
AF7 = 7, |
||||
AF8 = 8, |
||||
AF9 = 9, |
||||
AF10 = 10, |
||||
AF11 = 11, |
||||
AF12 = 12, |
||||
AF13 = 13, |
||||
AF14 = 14, |
||||
AF15 = 15, |
||||
}; |
||||
|
||||
|
||||
/**
|
||||
* Enable GPIO in RCC |
||||
* @param gpio GPIO base |
||||
*/ |
||||
void gpio_enable(uint32_t gpio); |
||||
|
||||
/**
|
||||
* Disable GPIO in RCC |
||||
* @param gpio GPIO base |
||||
*/ |
||||
void gpio_disable(uint32_t gpio); |
||||
|
||||
/**
|
||||
* Set GPIO AF (writes MODER and AFR). |
||||
* Also enables the port if disabled in RCC. |
||||
* @param gpio GPIO base |
||||
* @param pins pins bitmask |
||||
* @param af alternate function 0..15 |
||||
*/ |
||||
void gpio_set_af(uint32_t gpio, uint32_t pins, enum GPIO_AF af); |
||||
|
||||
|
||||
/**
|
||||
* Set pins mode (writes MODER) |
||||
* @param gpio GPIO base |
||||
* @param pins pins bitmask |
||||
* @param mode mode to set |
||||
*/ |
||||
void gpio_set_mode(uint32_t gpio, uint32_t pins, enum GPIO_MODE mode); |
@ -0,0 +1,20 @@ |
||||
#include "systick.h" |
||||
|
||||
void systick_setup(uint32_t prescaller) |
||||
{ |
||||
SysTick_CSR = (SysTick_CSR & ~SysTick_CSR_CLKSOURCE) | SysTick_CSR_CLKSOURCE_CORE; |
||||
SysTick_RELOAD = prescaller; |
||||
SysTick_CSR |= SysTick_CSR_TICKINT | SysTick_CSR_ENABLE; |
||||
} |
||||
|
||||
|
||||
void systick_enable(void) |
||||
{ |
||||
SysTick_CSR |= SysTick_CSR_ENABLE; |
||||
} |
||||
|
||||
|
||||
void systick_disable(void) |
||||
{ |
||||
SysTick_CSR &= ~SysTick_CSR_ENABLE; |
||||
} |
@ -0,0 +1,20 @@ |
||||
#pragma once |
||||
#include "common.h" |
||||
|
||||
// don't forget to implement the handler:
|
||||
// void SysTick_Handler(void)
|
||||
|
||||
|
||||
/**
|
||||
* Set up and start systick |
||||
* @param prescaller divider (eg. for 1ms @ 16MHz: 16000) |
||||
*/ |
||||
void systick_setup(uint32_t prescaller); |
||||
|
||||
|
||||
/** Enable (start) systick */ |
||||
void systick_enable(void); |
||||
|
||||
|
||||
/** Disable (stop) systick */ |
||||
void systick_disable(void); |
@ -0,0 +1,89 @@ |
||||
#include <common.h> |
||||
#include <gpio.h> |
||||
#include <systick.h> |
||||
|
||||
|
||||
static void init_gpios(void) |
||||
{ |
||||
gpio_enable(GPIOA); |
||||
gpio_enable(GPIOB); |
||||
gpio_enable(GPIOC); |
||||
|
||||
gpio_set_mode(GPIOC, BIT8 | BIT9, MODER_OUTPUT); |
||||
} |
||||
|
||||
|
||||
static void init_clock(void) |
||||
{ |
||||
// Flash timing - 64-bit access, pre-fetch, latency = 1
|
||||
FLASH_ACR |= FLASH_ACR_ACC64; // Cannot write both at once
|
||||
FLASH_ACR |= FLASH_ACR_PRFTEN | FLASH_ACR_LATENCY; |
||||
|
||||
// Power on HSI (runs from MSI on start)
|
||||
RCC_CR |= RCC_CR_HSION; |
||||
|
||||
// Wait for HSIRDY
|
||||
while (!(RCC_CR & RCC_CR_HSIRDY)); |
||||
|
||||
// Select HSI as the core clock source
|
||||
RCC_CFGR &= ~RCC_CFGR_SW; |
||||
RCC_CFGR |= RCC_CFGR_SW_HSI; |
||||
} |
||||
|
||||
|
||||
static void init_usart(void) |
||||
{ |
||||
gpio_set_af(GPIOC, BIT10 | BIT11, AF7); |
||||
|
||||
// USART at C11, C12
|
||||
RCC_APB1ENR |= RCC_APB1ENR_USART3EN; |
||||
|
||||
// RATE 9600Bd 104.1875 (see datasheet for reference)8.6875
|
||||
// 0x00683 ... 9600
|
||||
USART3_BRR = 0x0008A; // 115200
|
||||
|
||||
// USART enable
|
||||
USART3_CR1 = USART_CR1_UE | USART_CR1_RE | USART_CR1_TE; |
||||
} |
||||
|
||||
|
||||
/** Called before main() */ |
||||
void SystemInit(void) |
||||
{ |
||||
init_clock(); |
||||
systick_setup(16000); |
||||
init_gpios(); |
||||
init_usart(); |
||||
} |
||||
|
||||
|
||||
|
||||
static uint32_t time = 0; |
||||
|
||||
/** IRQ */ |
||||
void SysTick_Handler(void) |
||||
{ |
||||
time++; |
||||
if (time == 500) { |
||||
time = 0; |
||||
GPIOC_ODR ^= BIT9; |
||||
} |
||||
} |
||||
|
||||
|
||||
|
||||
void delay(void) |
||||
{ |
||||
for (int i = 0; i < 100000; i++) { |
||||
__asm__("nop"); |
||||
} |
||||
} |
||||
|
||||
|
||||
int main(void) |
||||
{ |
||||
while (1) { |
||||
delay(); |
||||
GPIOC_ODR ^= BIT8; |
||||
} |
||||
} |
@ -0,0 +1,34 @@ |
||||
TEMPLATE = app |
||||
CONFIG += console |
||||
CONFIG -= app_bundle |
||||
CONFIG -= qt |
||||
|
||||
INCLUDEPATH += \ |
||||
lib \ |
||||
/usr/arm-none-eabi/include |
||||
|
||||
DEFINES += STM32F3 __ARM_ARCH_7M__ ARM_MATH_CM4 |
||||
|
||||
|
||||
DISTFILES += \ |
||||
Makefile \ |
||||
style.astylerc \ |
||||
startup_stm32l100xc.s \ |
||||
stm32l100rc.ld |
||||
|
||||
SOURCES += \ |
||||
main.c \ |
||||
lib/gpio.c \ |
||||
lib/systick.c |
||||
|
||||
HEADERS += \ |
||||
lib/common.h \ |
||||
lib/defs_base.h \ |
||||
lib/defs_flash.h \ |
||||
lib/defs_gpio.h \ |
||||
lib/defs_rcc.h \ |
||||
lib/gpio.h \ |
||||
lib/defs_systick.h \ |
||||
lib/systick.h \ |
||||
lib/defs_usart.h |
||||
|
@ -0,0 +1,418 @@ |
||||
/** |
||||
****************************************************************************** |
||||
* @file startup_stm32l100xc.s
|
||||
* @author MCD Application Team
|
||||
* @version V2.1.2
|
||||
* @date 09-October-2015
|
||||
* @brief STM32L100XC 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>© COPYRIGHT(c) 2015 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_STAMP_IRQHandler
|
||||
.word RTC_WKUP_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_IRQHandler
|
||||
.word USB_HP_IRQHandler
|
||||
.word USB_LP_IRQHandler
|
||||
.word DAC_IRQHandler
|
||||
.word COMP_IRQHandler
|
||||
.word EXTI9_5_IRQHandler
|
||||
.word LCD_IRQHandler
|
||||
.word TIM9_IRQHandler
|
||||
.word TIM10_IRQHandler
|
||||
.word TIM11_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 USB_FS_WKUP_IRQHandler
|
||||
.word TIM6_IRQHandler
|
||||
.word TIM7_IRQHandler
|
||||
.word 0
|
||||
.word 0
|
||||
.word SPI3_IRQHandler
|
||||
.word 0
|
||||
.word 0
|
||||
.word DMA2_Channel1_IRQHandler
|
||||
.word DMA2_Channel2_IRQHandler
|
||||
.word DMA2_Channel3_IRQHandler
|
||||
.word DMA2_Channel4_IRQHandler
|
||||
.word DMA2_Channel5_IRQHandler
|
||||
.word 0
|
||||
.word COMP_ACQ_IRQHandler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word BootRAM /* @0x108. This is for boot in RAM mode for
|
||||
STM32L100XC 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_STAMP_IRQHandler
|
||||
.thumb_set TAMPER_STAMP_IRQHandler,Default_Handler |
||||
|
||||
.weak RTC_WKUP_IRQHandler
|
||||
.thumb_set RTC_WKUP_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_IRQHandler
|
||||
.thumb_set ADC1_IRQHandler,Default_Handler |
||||
|
||||
.weak USB_HP_IRQHandler
|
||||
.thumb_set USB_HP_IRQHandler,Default_Handler |
||||
|
||||
.weak USB_LP_IRQHandler
|
||||
.thumb_set USB_LP_IRQHandler,Default_Handler |
||||
|
||||
.weak DAC_IRQHandler
|
||||
.thumb_set DAC_IRQHandler,Default_Handler |
||||
|
||||
.weak COMP_IRQHandler
|
||||
.thumb_set COMP_IRQHandler,Default_Handler |
||||
|
||||
.weak EXTI9_5_IRQHandler
|
||||
.thumb_set EXTI9_5_IRQHandler,Default_Handler |
||||
|
||||
.weak LCD_IRQHandler
|
||||
.thumb_set LCD_IRQHandler,Default_Handler |
||||
|
||||
.weak TIM9_IRQHandler
|
||||
.thumb_set TIM9_IRQHandler,Default_Handler |
||||
|
||||
.weak TIM10_IRQHandler
|
||||
.thumb_set TIM10_IRQHandler,Default_Handler |
||||
|
||||
.weak TIM11_IRQHandler
|
||||
.thumb_set TIM11_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 USB_FS_WKUP_IRQHandler
|
||||
.thumb_set USB_FS_WKUP_IRQHandler,Default_Handler |
||||
|
||||
.weak TIM6_IRQHandler
|
||||
.thumb_set TIM6_IRQHandler,Default_Handler |
||||
|
||||
.weak TIM7_IRQHandler
|
||||
.thumb_set TIM7_IRQHandler,Default_Handler |
||||
|
||||
.weak SPI3_IRQHandler
|
||||
.thumb_set SPI3_IRQHandler,Default_Handler |
||||
|
||||
.weak DMA2_Channel1_IRQHandler
|
||||
.thumb_set DMA2_Channel1_IRQHandler,Default_Handler |
||||
|
||||
.weak DMA2_Channel2_IRQHandler
|
||||
.thumb_set DMA2_Channel2_IRQHandler,Default_Handler |
||||
|
||||
.weak DMA2_Channel3_IRQHandler
|
||||
.thumb_set DMA2_Channel3_IRQHandler,Default_Handler |
||||
|
||||
.weak DMA2_Channel4_IRQHandler
|
||||
.thumb_set DMA2_Channel4_IRQHandler,Default_Handler |
||||
|
||||
.weak DMA2_Channel5_IRQHandler
|
||||
.thumb_set DMA2_Channel5_IRQHandler,Default_Handler |
||||
|
||||
.weak COMP_ACQ_IRQHandler
|
||||
.thumb_set COMP_ACQ_IRQHandler,Default_Handler |
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
||||
|
@ -0,0 +1,167 @@ |
||||
/* |
||||
***************************************************************************** |
||||
** |
||||
** File : stm32_flash.ld |
||||
** |
||||
** Abstract : Linker script for STM32L100RC Device with |
||||
** 256KByte FLASH, 16KByte RAM |
||||
** |
||||
** Set heap size, stack size and stack location according |
||||
** to application requirements. |
||||
** |
||||
** Set memory bank area and size if external memory is used. |
||||
** |
||||
** Target : STMicroelectronics STM32 |
||||
** |
||||
** Environment : Atollic TrueSTUDIO(R) |
||||
** |
||||
** Distribution: The file is distributed as is, without any warranty |
||||
** of any kind. |
||||
** |
||||
** (c)Copyright Atollic AB. |
||||
** You may use this file as-is or modify it according to the needs of your |
||||
** project. This file may only be built (assembled or compiled and linked) |
||||
** using the Atollic TrueSTUDIO(R) product. The use of this file together |
||||
** with other tools than Atollic TrueSTUDIO(R) is not permitted. |
||||
** |
||||
***************************************************************************** |
||||
*/ |
||||
|
||||
/* Entry Point */ |
||||
ENTRY(Reset_Handler) |
||||
|
||||
/* Highest address of the user mode stack */ |
||||
_estack = 0x20003FFF; /* end of RAM */ |
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */ |
||||
_Min_Heap_Size = 0x1000; /* required amount of heap */ |
||||
_Min_Stack_Size = 0x400; /* required amount of stack */ |
||||
|
||||
/* Specify the memory areas */ |
||||
MEMORY |
||||
{ |
||||
FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 256K |
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 16K |
||||
EEP (r) : ORIGIN = 0x08080000, 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 : { |
||||
__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) } |
||||
} |
@ -0,0 +1,13 @@ |
||||
style=kr |
||||
indent=tab |
||||
max-instatement-indent=60 |
||||
|
||||
convert-tabs |
||||
|
||||
indent-switches |
||||
|
||||
pad-oper |
||||
unpad-paren |
||||
pad-header |
||||
|
||||
verbose |
Loading…
Reference in new issue