From d501ca6b0b8d58d666cfbee87731e409b55dd902 Mon Sep 17 00:00:00 2001 From: Kevin O'Connor Date: Tue, 23 Jul 2019 23:51:31 -0400 Subject: [PATCH] stm32f4: Add initial support for STM32F446 chip Signed-off-by: Kevin O'Connor --- src/Kconfig | 3 ++ src/stm32f4/Kconfig | 21 ++++++++ src/stm32f4/Makefile | 46 +++++++++++++++++ src/stm32f4/clock.c | 74 ++++++++++++++++++++++++++++ src/stm32f4/gpio.c | 27 ++++++++++ src/stm32f4/internal.h | 21 ++++++++ src/stm32f4/main.c | 28 +++++++++++ src/stm32f4/serial.c | 55 +++++++++++++++++++++ src/stm32f4/stm32f4.ld | 109 +++++++++++++++++++++++++++++++++++++++++ 9 files changed, 384 insertions(+) create mode 100644 src/stm32f4/Kconfig create mode 100644 src/stm32f4/Makefile create mode 100644 src/stm32f4/clock.c create mode 100644 src/stm32f4/gpio.c create mode 100644 src/stm32f4/internal.h create mode 100644 src/stm32f4/main.c create mode 100644 src/stm32f4/serial.c create mode 100644 src/stm32f4/stm32f4.ld diff --git a/src/Kconfig b/src/Kconfig index 61518a0bf..40bf427b5 100644 --- a/src/Kconfig +++ b/src/Kconfig @@ -23,6 +23,8 @@ choice bool "STMicroelectronics STM32F042" config MACH_STM32F1 bool "STMicroelectronics STM32F103" + config MACH_STM32F4 + bool "STMicroelectronics STM32F446" config MACH_PRU bool "Beaglebone PRU" config MACH_LINUX @@ -37,6 +39,7 @@ source "src/atsamd/Kconfig" source "src/lpc176x/Kconfig" source "src/stm32f0/Kconfig" source "src/stm32f1/Kconfig" +source "src/stm32f4/Kconfig" source "src/pru/Kconfig" source "src/linux/Kconfig" source "src/simulator/Kconfig" diff --git a/src/stm32f4/Kconfig b/src/stm32f4/Kconfig new file mode 100644 index 000000000..4194254a6 --- /dev/null +++ b/src/stm32f4/Kconfig @@ -0,0 +1,21 @@ +# Kconfig settings for STM32F4 processors + +if MACH_STM32F4 + +config STM32F4_SELECT + bool + default y + +config BOARD_DIRECTORY + string + default "stm32f4" + +config CLOCK_FREQ + int + default 180000000 + +config SERIAL + bool + default y + +endif diff --git a/src/stm32f4/Makefile b/src/stm32f4/Makefile new file mode 100644 index 000000000..4263208f3 --- /dev/null +++ b/src/stm32f4/Makefile @@ -0,0 +1,46 @@ +# Additional STM32F4 build rules + +# Setup the toolchain +CROSS_PREFIX=arm-none-eabi- + +dirs-y += src/stm32f4 src/generic +dirs-y += lib/stm32f4 lib/stm32f4/gcc + +CFLAGS += -mthumb -mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard +CFLAGS += -Ilib/cmsis-core -Ilib/stm32f4/include +CFLAGS += -DSTM32F446xx + +# Add source files +src-y += stm32f4/main.c stm32f4/clock.c stm32f4/gpio.c +src-y += generic/crc16_ccitt.c generic/alloc.c +src-y += generic/armcm_irq.c generic/armcm_timer.c +src-y += ../lib/stm32f4/system_stm32f4xx.c +src-$(CONFIG_SERIAL) += stm32f4/serial.c generic/serial_irq.c + +# Add assembler build rules +$(OUT)%.o: %.s $(OUT)autoconf.h $(OUT)board-link + @echo " Assembling $@" + $(Q)$(AS) $< -o $@ + +asmsrc-y = ../lib/stm32f4/gcc/startup_stm32f446xx.s +OBJS_klipper.elf += $(patsubst %.s, $(OUT)src/%.o,$(asmsrc-y)) + +# Build the linker script +$(OUT)stm32f4.ld: src/stm32f4/stm32f4.ld $(OUT)board-link + @echo " Preprocessing $@" + $(Q)$(CPP) -P -MD -MT $@ -DFLASH_START=0 $< -o $@ + +CFLAGS_klipper.elf += -T $(OUT)stm32f4.ld +CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs +$(OUT)klipper.elf : $(OUT)stm32f4.ld + +# Binary output file rules +target-y += $(OUT)klipper.bin + +$(OUT)klipper.bin: $(OUT)klipper.elf + @echo " Creating hex file $@" + $(Q)$(OBJCOPY) -O binary $< $@ + +flash: $(OUT)klipper.bin + @echo " Flashing $< to $(FLASH_DEVICE) via stm32flash" + $(Q)stm32flash -w $< -v -g 0 $(FLASH_DEVICE) diff --git a/src/stm32f4/clock.c b/src/stm32f4/clock.c new file mode 100644 index 000000000..339a7fde6 --- /dev/null +++ b/src/stm32f4/clock.c @@ -0,0 +1,74 @@ +// Code to setup clocks on stm32f446 +// +// Copyright (C) 2019 Kevin O'Connor +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "internal.h" // enable_pclock + +#define FREQ_PERIPH 45000000 + +// Enable a peripheral clock +void +enable_pclock(uint32_t periph_base) +{ + if (periph_base < APB2PERIPH_BASE) { + uint32_t pos = (periph_base - APB1PERIPH_BASE) / 0x400; + RCC->APB1ENR |= (1<APB1ENR; + } else if (periph_base < AHB1PERIPH_BASE) { + uint32_t pos = (periph_base - APB2PERIPH_BASE) / 0x400; + RCC->APB2ENR |= (1<APB2ENR; + } else if (periph_base < AHB2PERIPH_BASE) { + uint32_t pos = (periph_base - AHB1PERIPH_BASE) / 0x400; + RCC->AHB1ENR |= (1<AHB1ENR; + } +} + +// Return the frequency of the given peripheral clock +uint32_t +get_pclock_frequency(uint32_t periph_base) +{ + return FREQ_PERIPH; +} + +// Main clock setup called at chip startup +void +clock_setup(void) +{ + // Configure 180Mhz PLL from internal oscillator (HSI) + RCC->PLLCFGR = ( + RCC_PLLCFGR_PLLSRC_HSI | (16 << RCC_PLLCFGR_PLLM_Pos) + | (360 << RCC_PLLCFGR_PLLN_Pos) | (0 << RCC_PLLCFGR_PLLP_Pos) + | (7 << RCC_PLLCFGR_PLLQ_Pos) | (6 << RCC_PLLCFGR_PLLR_Pos)); + RCC->CR |= RCC_CR_PLLON; + + // Enable "over drive" + enable_pclock(PWR_BASE); + PWR->CR = (3 << PWR_CR_VOS_Pos) | PWR_CR_ODEN; + while (!(PWR->CSR & PWR_CSR_ODRDY)) + ; + PWR->CR = (3 << PWR_CR_VOS_Pos) | PWR_CR_ODEN | PWR_CR_ODSWEN; + while (!(PWR->CSR & PWR_CSR_ODSWRDY)) + ; + + // Set flash latency + FLASH->ACR = (FLASH_ACR_LATENCY_5WS | FLASH_ACR_ICEN | FLASH_ACR_DCEN + | FLASH_ACR_PRFTEN); + + // Wait for PLL lock + while (!(RCC->CR & RCC_CR_PLLRDY)) + ; + + // Switch system clock to PLL + RCC->CFGR = RCC_CFGR_PPRE1_DIV4 | RCC_CFGR_PPRE2_DIV4 | RCC_CFGR_SW_PLL; + while ((RCC->CFGR & RCC_CFGR_SWS_Msk) != RCC_CFGR_SWS_PLL) + ; + + // Enable GPIO clocks + enable_pclock(GPIOA_BASE); + enable_pclock(GPIOB_BASE); + enable_pclock(GPIOC_BASE); +} diff --git a/src/stm32f4/gpio.c b/src/stm32f4/gpio.c new file mode 100644 index 000000000..370aba1fc --- /dev/null +++ b/src/stm32f4/gpio.c @@ -0,0 +1,27 @@ +// GPIO functions on stm32f4 +// +// Copyright (C) 2019 Kevin O'Connor +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "internal.h" // gpio_peripheral + +static GPIO_TypeDef * const digital_regs[] = { + GPIOA, GPIOB, GPIOC +}; + +// Set the mode and extended function of a pin +void +gpio_peripheral(uint32_t gpio, uint32_t mode, uint32_t func, int pullup) +{ + GPIO_TypeDef *regs = digital_regs[GPIO2PORT(gpio)]; + uint32_t pup = pullup ? (pullup > 0 ? 1 : 2) : 0; + uint32_t pos = gpio % 16, af_reg = pos / 8; + uint32_t af_shift = (pos % 8) * 4, af_msk = 0x0f << af_shift; + uint32_t m_shift = pos * 2, m_msk = 0x03 << m_shift; + + regs->AFR[af_reg] = (regs->AFR[af_reg] & ~af_msk) | (func << af_shift); + regs->MODER = (regs->MODER & ~m_msk) | (mode << m_shift); + regs->PUPDR = (regs->PUPDR & ~m_msk) | (pup << m_shift); + regs->OSPEEDR = (regs->OSPEEDR & ~m_msk) | (0x02 << m_shift); +} diff --git a/src/stm32f4/internal.h b/src/stm32f4/internal.h new file mode 100644 index 000000000..0cfb26645 --- /dev/null +++ b/src/stm32f4/internal.h @@ -0,0 +1,21 @@ +#ifndef __STM32F4_INTERNAL_H +#define __STM32F4_INTERNAL_H +// Local definitions for STM32F4 code + +#include "stm32f4xx.h" + +#define GPIO(PORT, NUM) (((PORT)-'A') * 16 + (NUM)) +#define GPIO2PORT(PIN) ((PIN) / 16) +#define GPIO2BIT(PIN) (1<<((PIN) % 16)) + +#define GPIO_INPUT 0 +#define GPIO_OUTPUT 1 +#define GPIO_FUNCTION 2 +#define GPIO_ANALOG 3 + +void enable_pclock(uint32_t periph_base); +uint32_t get_pclock_frequency(uint32_t periph_base); +void clock_setup(void); +void gpio_peripheral(uint32_t gpio, uint32_t mode, uint32_t func, int pullup); + +#endif // internal.h diff --git a/src/stm32f4/main.c b/src/stm32f4/main.c new file mode 100644 index 000000000..a1a605786 --- /dev/null +++ b/src/stm32f4/main.c @@ -0,0 +1,28 @@ +// Main starting point for STM32F4 boards. +// +// Copyright (C) 2019 Kevin O'Connor +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "command.h" // DECL_CONSTANT_STR +#include "internal.h" // clock_setup +#include "sched.h" // sched_main + +DECL_CONSTANT_STR("MCU", "stm32f446"); + +void +command_reset(uint32_t *args) +{ + NVIC_SystemReset(); +} +DECL_COMMAND_FLAGS(command_reset, HF_IN_SHUTDOWN, "reset"); + +// Main entry point +int +main(void) +{ + clock_setup(); + + sched_main(); + return 0; +} diff --git a/src/stm32f4/serial.c b/src/stm32f4/serial.c new file mode 100644 index 000000000..951a82979 --- /dev/null +++ b/src/stm32f4/serial.c @@ -0,0 +1,55 @@ +// STM32F4 serial +// +// Copyright (C) 2019 Kevin O'Connor +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "autoconf.h" // CONFIG_SERIAL_BAUD +#include "board/serial_irq.h" // serial_rx_byte +#include "command.h" // DECL_CONSTANT_STR +#include "internal.h" // enable_pclock +#include "sched.h" // DECL_INIT + +DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA3,PA2"); + +#define CR1_FLAGS (USART_CR1_UE | USART_CR1_RE | USART_CR1_TE \ + | USART_CR1_RXNEIE) + +void +serial_init(void) +{ + enable_pclock(USART2_BASE); + + uint32_t pclk = get_pclock_frequency(USART2_BASE); + uint32_t div = pclk / (CONFIG_SERIAL_BAUD * 16); + USART2->BRR = div << USART_BRR_DIV_Mantissa_Pos; + USART2->CR1 = CR1_FLAGS; + NVIC_SetPriority(USART2_IRQn, 0); + NVIC_EnableIRQ(USART2_IRQn); + + gpio_peripheral(GPIO('A', 2), GPIO_FUNCTION, 7, 0); + gpio_peripheral(GPIO('A', 3), GPIO_FUNCTION, 7, 1); +} +DECL_INIT(serial_init); + +void __visible +USART2_IRQHandler(void) +{ + uint32_t sr = USART2->SR; + if (sr & (USART_SR_RXNE | USART_SR_ORE)) + serial_rx_byte(USART2->DR); + if (sr & USART_SR_TXE && USART2->CR1 & USART_CR1_TXEIE) { + uint8_t data; + int ret = serial_get_tx_byte(&data); + if (ret) + USART2->CR1 = CR1_FLAGS; + else + USART2->DR = data; + } +} + +void +serial_enable_tx_irq(void) +{ + USART2->CR1 = CR1_FLAGS | USART_CR1_TXEIE; +} diff --git a/src/stm32f4/stm32f4.ld b/src/stm32f4/stm32f4.ld new file mode 100644 index 000000000..84df83fcd --- /dev/null +++ b/src/stm32f4/stm32f4.ld @@ -0,0 +1,109 @@ +/* Cortex-M linker script */ + +ENTRY(Reset_Handler) + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000 + FLASH_START, LENGTH = 512K - FLASH_START + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +} + +/* highest address of the user mode stack */ +_estack = 0x20005000; + +SECTIONS +{ + /* Interrupt vector table */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) + . = ALIGN(4); + } >FLASH + + /* Program code and constant data */ + .text : + { + . = ALIGN(4); + *(.text) + *(.text*) + *(.rodata) + *(.rodata*) + KEEP (*(.init)) + KEEP (*(.fini)) + . = ALIGN(4); + _etext = .; + } >FLASH + + /* Exception handling */ + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + /* Static constructor initialization (C++) */ + .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 + + + /* Initialized data, needs to be handled by startup code */ + _sidata = .; + .data : AT (_sidata) + { + . = ALIGN(4); + _sdata = . ; + _data = . ; + *(.data) + *(.data*) + *(.RAMtext) + . = ALIGN(4); + _edata = . ; + } >RAM + + /* Uninitialized data */ + .bss (NOLOAD) : + { + . = ALIGN(4); + _sbss = .; + __bss_start__ = .; + _bss = .; + *(.bss) + *(.bss*) + *(COMMON) + . = ALIGN(4); + _ebss = .; + __bss_end__ = _ebss; + } >RAM + + /* Pointers to end of data for dynamic memory management */ + PROVIDE (end = _ebss); + PROVIDE (_end = _ebss); + + /* Remove debugging from standard libraries */ + /DISCARD/ : + { + libc.a (*) + libm.a (*) + libgcc.a (*) + } +}