STM32F7: Integrate into the build

This commit is contained in:
Keir Fraser
2019-11-25 12:14:37 +00:00
parent bf52a100b1
commit c5c81ce1ba
15 changed files with 420 additions and 144 deletions

View File

@@ -7,12 +7,12 @@ VER := v$(FW_MAJOR).$(FW_MINOR)
SUBDIRS += src bootloader blinky_test
.PHONY: all clean dist mrproper flash start serial
.PHONY: all blinky clean dist mrproper flash start serial
ifneq ($(RULES_MK),y)
export ROOT := $(CURDIR)
all:
all blinky:
$(MAKE) -f $(ROOT)/Rules.mk $@
clean:
@@ -27,7 +27,7 @@ dist:
mkdir -p $(PROJ)-$(VER)/scripts/greaseweazle/tools
mkdir -p $(PROJ)-$(VER)/alt
$(MAKE) clean
$(MAKE) all
stm32=f1 $(MAKE) all blinky
cp -a $(PROJ)-$(VER).hex $(PROJ)-$(VER)/
cp -a $(PROJ)-$(VER).upd $(PROJ)-$(VER)/
cp -a blinky_test/Blinky.hex $(PROJ)-$(VER)/alt/Blinky_Test-$(VER).hex
@@ -50,12 +50,14 @@ mrproper: clean
else
blinky:
debug=y $(MAKE) -C blinky_test -f $(ROOT)/Rules.mk \
Blinky.elf Blinky.bin Blinky.hex
all: scripts/greaseweazle/version.py
$(MAKE) -C src -f $(ROOT)/Rules.mk $(PROJ).elf $(PROJ).bin $(PROJ).hex
bootloader=y $(MAKE) -C bootloader -f $(ROOT)/Rules.mk \
Bootloader.elf Bootloader.bin Bootloader.hex
debug=y $(MAKE) -C blinky_test -f $(ROOT)/Rules.mk \
Blinky.elf Blinky.bin Blinky.hex
srec_cat bootloader/Bootloader.hex -Intel src/$(PROJ).hex -Intel \
-o $(PROJ)-$(VER).hex -Intel
$(PYTHON) ./scripts/mk_update.py src/$(PROJ).bin $(PROJ)-$(VER).upd

View File

@@ -13,9 +13,17 @@ FLAGS = -g -Os -nostdlib -std=gnu99 -iquote $(ROOT)/inc
FLAGS += -Wall -Werror -Wno-format -Wdeclaration-after-statement
FLAGS += -Wstrict-prototypes -Wredundant-decls -Wnested-externs
FLAGS += -fno-common -fno-exceptions -fno-strict-aliasing
FLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3 -mfloat-abi=soft
FLAGS += -mlittle-endian -mthumb -mfloat-abi=soft
FLAGS += -Wno-unused-value
ifeq ($(stm32),f1)
FLAGS += -mcpu=cortex-m3 -DSTM32F=1
stm32f1=y
else ifeq ($(stm32),f7)
FLAGS += -mcpu=cortex-m7 -DSTM32F=7
stm32f7=y
endif
ifneq ($(debug),y)
FLAGS += -DNDEBUG
endif

View File

@@ -1,7 +1,8 @@
RPATH = ../src
OBJS += vectors.o
OBJS += stm32f10x.o
OBJS += cortex.o
OBJS += stm32$(stm32).o
OBJS += blinky.o
OBJS += util.o
OBJS += fpec.o

View File

@@ -6,13 +6,14 @@ OBJS += crc.o
OBJS += vectors.o
OBJS += fw_update.o
OBJS += string.o
OBJS += stm32f10x.o
OBJS += cortex.o
OBJS += stm32$(stm32).o
OBJS += util.o
OBJS += fpec.o
OBJS-$(stm32f1) += fpec.o
OBJS-$(debug) += console.o
SUBDIRS += usb
SUBDIRS-$(stm32f1) += usb
.PHONY: $(RPATH)/build_info.c
build_info.o: CFLAGS += -DFW_MAJOR=$(FW_MAJOR) -DFW_MINOR=$(FW_MINOR)

View File

@@ -17,8 +17,14 @@
#include "util.h"
#include "stm32/common_regs.h"
#include "stm32/f1_regs.h"
#include "stm32/common.h"
#if STM32F == 1
#include "stm32/f1_regs.h"
#include "stm32/f1.h"
#elif STM32F == 7
#include "stm32/f7_regs.h"
#include "stm32/f7.h"
#endif
#include "intrinsics.h"
#include "time.h"

View File

@@ -159,6 +159,9 @@ static always_inline unsigned long __cmpxchg(
(unsigned long)(n), \
sizeof(*(ptr))))
/* Cortex initialisation */
void cortex_init(void);
/*
* Local variables:
* mode: C

View File

@@ -1,5 +1,5 @@
/*
* stm32f10x.h
* stm32/common.h
*
* Core and peripheral registers.
*
@@ -16,11 +16,9 @@
#define DBG volatile struct dbg * const
#define FLASH volatile struct flash * const
#define PWR volatile struct pwr * const
#define BKP volatile struct bkp * const
#define RCC volatile struct rcc * const
#define IWDG volatile struct iwdg * const
#define GPIO volatile struct gpio * const
#define AFIO volatile struct afio * const
#define EXTI volatile struct exti * const
#define DMA volatile struct dma * const
#define TIM volatile struct tim * const
@@ -32,46 +30,6 @@
#define USB_BUF volatile uint32_t * const
#define USB_OTG volatile struct usb_otg * const
/* C-accessible registers. */
static STK stk = (struct stk *)STK_BASE;
static SCB scb = (struct scb *)SCB_BASE;
static NVIC nvic = (struct nvic *)NVIC_BASE;
static DBG dbg = (struct dbg *)DBG_BASE;
static FLASH flash = (struct flash *)FLASH_BASE;
static PWR pwr = (struct pwr *)PWR_BASE;
static BKP bkp = (struct bkp *)BKP_BASE;
static RCC rcc = (struct rcc *)RCC_BASE;
static IWDG iwdg = (struct iwdg *)IWDG_BASE;
static GPIO gpioa = (struct gpio *)GPIOA_BASE;
static GPIO gpiob = (struct gpio *)GPIOB_BASE;
static GPIO gpioc = (struct gpio *)GPIOC_BASE;
static GPIO gpiod = (struct gpio *)GPIOD_BASE;
static GPIO gpioe = (struct gpio *)GPIOE_BASE;
static GPIO gpiof = (struct gpio *)GPIOF_BASE;
static GPIO gpiog = (struct gpio *)GPIOG_BASE;
static AFIO afio = (struct afio *)AFIO_BASE;
static EXTI exti = (struct exti *)EXTI_BASE;
static DMA dma1 = (struct dma *)DMA1_BASE;
static DMA dma2 = (struct dma *)DMA2_BASE;
static TIM tim1 = (struct tim *)TIM1_BASE;
static TIM tim2 = (struct tim *)TIM2_BASE;
static TIM tim3 = (struct tim *)TIM3_BASE;
static TIM tim4 = (struct tim *)TIM4_BASE;
static TIM tim5 = (struct tim *)TIM5_BASE;
static TIM tim6 = (struct tim *)TIM6_BASE;
static TIM tim7 = (struct tim *)TIM7_BASE;
static SPI spi1 = (struct spi *)SPI1_BASE;
static SPI spi2 = (struct spi *)SPI2_BASE;
static SPI spi3 = (struct spi *)SPI3_BASE;
static I2C i2c1 = (struct i2c *)I2C1_BASE;
static I2C i2c2 = (struct i2c *)I2C2_BASE;
static USART usart1 = (struct usart *)USART1_BASE;
static USART usart2 = (struct usart *)USART2_BASE;
static USART usart3 = (struct usart *)USART3_BASE;
static USB usb = (struct usb *)USB_BASE;
static USB_BUFD usb_bufd = (struct usb_bufd *)USB_BUF_BASE;
static USB_BUF usb_buf = (uint32_t *)USB_BUF_BASE;
/* NVIC table */
extern uint32_t vector_table[];
@@ -123,6 +81,7 @@ typedef uint32_t stk_time_t;
#define IRQx_get_prio(x) (nvic->ipr[x] >> 4)
/* GPIO */
struct gpio;
void gpio_configure_pin(GPIO gpio, unsigned int pin, unsigned int mode);
#define gpio_write_pin(gpio, pin, level) \
((gpio)->bsrr = ((level) ? 0x1u : 0x10000u) << (pin))
@@ -137,8 +96,6 @@ void fpec_init(void);
void fpec_page_erase(uint32_t flash_address);
void fpec_write(const void *data, unsigned int size, uint32_t flash_address);
#define FLASH_PAGE_SIZE 1024
/*
* Local variables:
* mode: C

66
inc/stm32/f1.h Normal file
View File

@@ -0,0 +1,66 @@
/*
* stm32/f1.h
*
* Core and peripheral registers.
*
* Written & released by Keir Fraser <keir.xen@gmail.com>
*
* This is free and unencumbered software released into the public domain.
* See the file COPYING for more details, or visit <http://unlicense.org>.
*/
/* C pointer types */
#define BKP volatile struct bkp * const
#define AFIO volatile struct afio * const
/* C-accessible registers. */
static STK stk = (struct stk *)STK_BASE;
static SCB scb = (struct scb *)SCB_BASE;
static NVIC nvic = (struct nvic *)NVIC_BASE;
static DBG dbg = (struct dbg *)DBG_BASE;
static FLASH flash = (struct flash *)FLASH_BASE;
static PWR pwr = (struct pwr *)PWR_BASE;
static BKP bkp = (struct bkp *)BKP_BASE;
static RCC rcc = (struct rcc *)RCC_BASE;
static IWDG iwdg = (struct iwdg *)IWDG_BASE;
static GPIO gpioa = (struct gpio *)GPIOA_BASE;
static GPIO gpiob = (struct gpio *)GPIOB_BASE;
static GPIO gpioc = (struct gpio *)GPIOC_BASE;
static GPIO gpiod = (struct gpio *)GPIOD_BASE;
static GPIO gpioe = (struct gpio *)GPIOE_BASE;
static GPIO gpiof = (struct gpio *)GPIOF_BASE;
static GPIO gpiog = (struct gpio *)GPIOG_BASE;
static AFIO afio = (struct afio *)AFIO_BASE;
static EXTI exti = (struct exti *)EXTI_BASE;
static DMA dma1 = (struct dma *)DMA1_BASE;
static DMA dma2 = (struct dma *)DMA2_BASE;
static TIM tim1 = (struct tim *)TIM1_BASE;
static TIM tim2 = (struct tim *)TIM2_BASE;
static TIM tim3 = (struct tim *)TIM3_BASE;
static TIM tim4 = (struct tim *)TIM4_BASE;
static TIM tim5 = (struct tim *)TIM5_BASE;
static TIM tim6 = (struct tim *)TIM6_BASE;
static TIM tim7 = (struct tim *)TIM7_BASE;
static SPI spi1 = (struct spi *)SPI1_BASE;
static SPI spi2 = (struct spi *)SPI2_BASE;
static SPI spi3 = (struct spi *)SPI3_BASE;
static I2C i2c1 = (struct i2c *)I2C1_BASE;
static I2C i2c2 = (struct i2c *)I2C2_BASE;
static USART usart1 = (struct usart *)USART1_BASE;
static USART usart2 = (struct usart *)USART2_BASE;
static USART usart3 = (struct usart *)USART3_BASE;
static USB usb = (struct usb *)USB_BASE;
static USB_BUFD usb_bufd = (struct usb_bufd *)USB_BUF_BASE;
static USB_BUF usb_buf = (uint32_t *)USB_BUF_BASE;
#define FLASH_PAGE_SIZE 1024
/*
* Local variables:
* mode: C
* c-file-style: "Linux"
* c-basic-offset: 4
* tab-width: 4
* indent-tabs-mode: nil
* End:
*/

78
inc/stm32/f7.h Normal file
View File

@@ -0,0 +1,78 @@
/*
* stm32/f7.h
*
* Core and peripheral registers.
*
* Written & released by Keir Fraser <keir.xen@gmail.com>
*
* This is free and unencumbered software released into the public domain.
* See the file COPYING for more details, or visit <http://unlicense.org>.
*/
/* C pointer types */
#define SYSCFG volatile struct syscfg * const
/* C-accessible registers. */
static STK stk = (struct stk *)STK_BASE;
static SCB scb = (struct scb *)SCB_BASE;
static NVIC nvic = (struct nvic *)NVIC_BASE;
static DBG dbg = (struct dbg *)DBG_BASE;
static FLASH flash = (struct flash *)FLASH_BASE;
static PWR pwr = (struct pwr *)PWR_BASE;
static RCC rcc = (struct rcc *)RCC_BASE;
static IWDG iwdg = (struct iwdg *)IWDG_BASE;
static GPIO gpioa = (struct gpio *)GPIOA_BASE;
static GPIO gpiob = (struct gpio *)GPIOB_BASE;
static GPIO gpioc = (struct gpio *)GPIOC_BASE;
static GPIO gpiod = (struct gpio *)GPIOD_BASE;
static GPIO gpioe = (struct gpio *)GPIOE_BASE;
static GPIO gpiof = (struct gpio *)GPIOF_BASE;
static GPIO gpiog = (struct gpio *)GPIOG_BASE;
static GPIO gpioh = (struct gpio *)GPIOH_BASE;
static GPIO gpioi = (struct gpio *)GPIOI_BASE;
static SYSCFG syscfg = (struct syscfg *)SYSCFG_BASE;
static EXTI exti = (struct exti *)EXTI_BASE;
static DMA dma1 = (struct dma *)DMA1_BASE;
static DMA dma2 = (struct dma *)DMA2_BASE;
static TIM tim1 = (struct tim *)TIM1_BASE;
static TIM tim2 = (struct tim *)TIM2_BASE;
static TIM tim3 = (struct tim *)TIM3_BASE;
static TIM tim4 = (struct tim *)TIM4_BASE;
static TIM tim5 = (struct tim *)TIM5_BASE;
static TIM tim6 = (struct tim *)TIM6_BASE;
static TIM tim7 = (struct tim *)TIM7_BASE;
static TIM tim8 = (struct tim *)TIM8_BASE;
static TIM tim9 = (struct tim *)TIM9_BASE;
static TIM tim10 = (struct tim *)TIM10_BASE;
static TIM tim11 = (struct tim *)TIM11_BASE;
static TIM tim12 = (struct tim *)TIM12_BASE;
static TIM tim13 = (struct tim *)TIM13_BASE;
static TIM tim14 = (struct tim *)TIM14_BASE;
static SPI spi1 = (struct spi *)SPI1_BASE;
static SPI spi2 = (struct spi *)SPI2_BASE;
static SPI spi3 = (struct spi *)SPI3_BASE;
static SPI spi4 = (struct spi *)SPI4_BASE;
static SPI spi5 = (struct spi *)SPI5_BASE;
static I2C i2c1 = (struct i2c *)I2C1_BASE;
static I2C i2c2 = (struct i2c *)I2C2_BASE;
static I2C i2c3 = (struct i2c *)I2C3_BASE;
static USART usart1 = (struct usart *)USART1_BASE;
static USART usart2 = (struct usart *)USART2_BASE;
static USART usart3 = (struct usart *)USART3_BASE;
static USART usart4 = (struct usart *)USART4_BASE;
static USART usart5 = (struct usart *)USART5_BASE;
static USART usart6 = (struct usart *)USART6_BASE;
static USB_OTG usb_otg_fs = (struct usb_otg *)USB_OTG_FS_BASE;
static USB_OTG usb_otg_hs = (struct usb_otg *)USB_OTG_HS_BASE;
#define FLASH_PAGE_SIZE 16384
/*
* Local variables:
* mode: C
* c-file-style: "Linux"
* c-basic-offset: 4
* tab-width: 4
* indent-tabs-mode: nil
* End:
*/

View File

@@ -264,7 +264,7 @@ struct gpio {
#define GPIOF_BASE 0x40021400
#define GPIOG_BASE 0x40021800
#define GPIOH_BASE 0x40021C00
#define GPIOH_BASE 0x40022000
#define GPIOI_BASE 0x40022000
/* System configuration controller */
struct syscfg {
@@ -440,6 +440,7 @@ struct i2c {
#define I2C1_BASE 0x40005400
#define I2C2_BASE 0x40005800
#define I2C3_BASE 0x40005C00
/* USART */
struct usart {
@@ -520,9 +521,12 @@ struct usart {
#define USART_ICR_FECF (1u<< 1)
#define USART_ICR_PECF (1u<< 0)
#define USART1_BASE 0x40013800
#define USART1_BASE 0x40011000
#define USART2_BASE 0x40004400
#define USART3_BASE 0x40004800
#define USART4_BASE 0x40004C00
#define USART5_BASE 0x40005000
#define USART6_BASE 0x40011400
#define USB_OTG_FS_BASE 0x50000000
#define USB_OTG_HS_BASE 0x40040000

View File

@@ -3,15 +3,16 @@ OBJS += build_info.o
OBJS += vectors.o
OBJS += main.o
OBJS += string.o
OBJS += stm32f10x.o
OBJS += cortex.o
OBJS += stm32$(stm32).o
OBJS += time.o
OBJS += timer.o
OBJS += util.o
OBJS += floppy.o
OBJS-$(stm32f1) += floppy.o
OBJS-$(debug) += console.o
SUBDIRS += usb
SUBDIRS-$(stm32f1) += usb
.PHONY: build_info.c
build_info.o: CFLAGS += -DFW_MAJOR=$(FW_MAJOR) -DFW_MINOR=$(FW_MINOR)

View File

@@ -1,7 +1,7 @@
/*
* stm32f10x.c
* cortex.c
*
* Core and peripheral registers.
* STM32 ARM Cortex management.
*
* Written & released by Keir Fraser <keir.xen@gmail.com>
*
@@ -77,74 +77,9 @@ static void exception_init(void)
scb->shpr3 = 0xff<<16;
}
static void clock_init(void)
{
/* Flash controller: reads require 2 wait states at 72MHz. */
flash->acr = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY(2);
/* Start up the external oscillator. */
rcc->cr |= RCC_CR_HSEON;
while (!(rcc->cr & RCC_CR_HSERDY))
cpu_relax();
/* PLLs, scalers, muxes. */
rcc->cfgr = (RCC_CFGR_PLLMUL(9) | /* PLL = 9*8MHz = 72MHz */
RCC_CFGR_PLLSRC_PREDIV1 |
RCC_CFGR_ADCPRE_DIV8 |
RCC_CFGR_PPRE1_DIV2);
/* Enable and stabilise the PLL. */
rcc->cr |= RCC_CR_PLLON;
while (!(rcc->cr & RCC_CR_PLLRDY))
cpu_relax();
/* Switch to the externally-driven PLL for system clock. */
rcc->cfgr |= RCC_CFGR_SW_PLL;
while ((rcc->cfgr & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_PLL)
cpu_relax();
/* Internal oscillator no longer needed. */
rcc->cr &= ~RCC_CR_HSION;
/* Enable SysTick counter at 72/8=9MHz. */
stk->load = STK_MASK;
stk->ctrl = STK_CTRL_ENABLE;
}
static void gpio_init(GPIO gpio)
{
/* Floating Input. Reference Manual states that JTAG pins are in PU/PD
* mode at reset, so ensure all PU/PD are disabled. */
gpio->crl = gpio->crh = 0x44444444u;
}
static void peripheral_init(void)
{
/* Enable basic GPIO and AFIO clocks, all timers, and DMA. */
rcc->apb1enr = (RCC_APB1ENR_TIM2EN |
RCC_APB1ENR_TIM3EN |
RCC_APB1ENR_TIM4EN);
rcc->apb2enr = (RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_IOPCEN |
RCC_APB2ENR_AFIOEN |
RCC_APB2ENR_TIM1EN);
rcc->ahbenr = RCC_AHBENR_DMA1EN;
/* Turn off serial-wire JTAG and reclaim the GPIOs. */
afio->mapr = AFIO_MAPR_SWJ_CFG_DISABLED;
/* All pins in a stable state. */
gpio_init(gpioa);
gpio_init(gpiob);
gpio_init(gpioc);
}
void stm32_init(void)
void cortex_init(void)
{
exception_init();
clock_init();
peripheral_init();
cpu_sync();
}
@@ -177,25 +112,10 @@ void delay_ms(unsigned int ms)
delay_ticks(ms * 1000u * STK_MHZ);
}
void gpio_configure_pin(GPIO gpio, unsigned int pin, unsigned int mode)
{
gpio_write_pin(gpio, pin, mode >> 4);
mode &= 0xfu;
if (pin >= 8) {
pin -= 8;
gpio->crh = (gpio->crh & ~(0xfu<<(pin<<2))) | (mode<<(pin<<2));
} else {
gpio->crl = (gpio->crl & ~(0xfu<<(pin<<2))) | (mode<<(pin<<2));
}
}
void system_reset(void)
{
IRQ_global_disable();
printk("Resetting...\n");
/* Wait for serial console TX to idle. */
while (!(usart1->sr & USART_SR_TXE) || !(usart1->sr & USART_SR_TC))
cpu_relax();
/* Request reset and loop waiting for it to happen. */
scb->aircr = SCB_AIRCR_VECTKEY | SCB_AIRCR_SYSRESETREQ;
for (;;) ;

View File

@@ -186,6 +186,7 @@ int main(void)
memcpy(_sdat, _ldat, _edat-_sdat);
memset(_sbss, 0, _ebss-_sbss);
#if STM32F == 1
/* Turn on AFIO and GPIOA clocks. */
rcc->apb2enr = RCC_APB2ENR_IOPAEN | RCC_APB2ENR_AFIOEN;
@@ -213,6 +214,11 @@ int main(void)
:: "r" (sp), "r" (pc));
}
}
#else
rcc->ahb1enr |= RCC_AHB1ENR_GPIOAEN;
gpio_configure_pin(gpioa, 15, GPO_pushpull(_2MHz, HIGH));
for (;;);
#endif
stm32_init();
console_init();

103
src/stm32f1.c Normal file
View File

@@ -0,0 +1,103 @@
/*
* stm32f1.c
*
* Core and peripheral registers.
*
* Written & released by Keir Fraser <keir.xen@gmail.com>
*
* This is free and unencumbered software released into the public domain.
* See the file COPYING for more details, or visit <http://unlicense.org>.
*/
static void clock_init(void)
{
/* Flash controller: reads require 2 wait states at 72MHz. */
flash->acr = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY(2);
/* Start up the external oscillator. */
rcc->cr |= RCC_CR_HSEON;
while (!(rcc->cr & RCC_CR_HSERDY))
cpu_relax();
/* PLLs, scalers, muxes. */
rcc->cfgr = (RCC_CFGR_PLLMUL(9) | /* PLL = 9*8MHz = 72MHz */
RCC_CFGR_PLLSRC_PREDIV1 |
RCC_CFGR_ADCPRE_DIV8 |
RCC_CFGR_PPRE1_DIV2);
/* Enable and stabilise the PLL. */
rcc->cr |= RCC_CR_PLLON;
while (!(rcc->cr & RCC_CR_PLLRDY))
cpu_relax();
/* Switch to the externally-driven PLL for system clock. */
rcc->cfgr |= RCC_CFGR_SW_PLL;
while ((rcc->cfgr & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_PLL)
cpu_relax();
/* Internal oscillator no longer needed. */
rcc->cr &= ~RCC_CR_HSION;
/* Enable SysTick counter at 72/8=9MHz. */
stk->load = STK_MASK;
stk->ctrl = STK_CTRL_ENABLE;
}
static void gpio_init(GPIO gpio)
{
/* Floating Input. Reference Manual states that JTAG pins are in PU/PD
* mode at reset, so ensure all PU/PD are disabled. */
gpio->crl = gpio->crh = 0x44444444u;
}
static void peripheral_init(void)
{
/* Enable basic GPIO and AFIO clocks, all timers, and DMA. */
rcc->apb1enr = (RCC_APB1ENR_TIM2EN |
RCC_APB1ENR_TIM3EN |
RCC_APB1ENR_TIM4EN);
rcc->apb2enr = (RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_IOPCEN |
RCC_APB2ENR_AFIOEN |
RCC_APB2ENR_TIM1EN);
rcc->ahbenr = RCC_AHBENR_DMA1EN;
/* Turn off serial-wire JTAG and reclaim the GPIOs. */
afio->mapr = AFIO_MAPR_SWJ_CFG_DISABLED;
/* All pins in a stable state. */
gpio_init(gpioa);
gpio_init(gpiob);
gpio_init(gpioc);
}
void stm32_init(void)
{
cortex_init();
clock_init();
peripheral_init();
cpu_sync();
}
void gpio_configure_pin(GPIO gpio, unsigned int pin, unsigned int mode)
{
gpio_write_pin(gpio, pin, mode >> 4);
mode &= 0xfu;
if (pin >= 8) {
pin -= 8;
gpio->crh = (gpio->crh & ~(0xfu<<(pin<<2))) | (mode<<(pin<<2));
} else {
gpio->crl = (gpio->crl & ~(0xfu<<(pin<<2))) | (mode<<(pin<<2));
}
}
/*
* Local variables:
* mode: C
* c-file-style: "Linux"
* c-basic-offset: 4
* tab-width: 4
* indent-tabs-mode: nil
* End:
*/

120
src/stm32f7.c Normal file
View File

@@ -0,0 +1,120 @@
/*
* stm32f7.c
*
* Core and peripheral registers.
*
* Written & released by Keir Fraser <keir.xen@gmail.com>
*
* This is free and unencumbered software released into the public domain.
* See the file COPYING for more details, or visit <http://unlicense.org>.
*/
/* XXX */
void floppy_init(void) {}
void floppy_process(void) {}
void usb_init(void) {}
void usb_process(void) {}
void fpec_init(void) {}
void fpec_page_erase(uint32_t flash_address) {}
void fpec_write(const void *data, unsigned int size, uint32_t flash_address) {}
void usb_read(uint8_t ep, void *buf, uint32_t len) {}
void usb_write(uint8_t ep, const void *buf, uint32_t len) {}
bool_t ep_tx_ready(uint8_t ep) { return FALSE; }
int ep_rx_ready(uint8_t ep) { return -1; }
static void clock_init(void)
{
#if 0
/* Flash controller: reads require 2 wait states at 72MHz. */
flash->acr = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY(2);
/* Start up the external oscillator. */
rcc->cr |= RCC_CR_HSEON;
while (!(rcc->cr & RCC_CR_HSERDY))
cpu_relax();
/* PLLs, scalers, muxes. */
rcc->cfgr = (RCC_CFGR_PLLMUL(9) | /* PLL = 9*8MHz = 72MHz */
RCC_CFGR_PLLSRC_PREDIV1 |
RCC_CFGR_ADCPRE_DIV8 |
RCC_CFGR_PPRE1_DIV2);
/* Enable and stabilise the PLL. */
rcc->cr |= RCC_CR_PLLON;
while (!(rcc->cr & RCC_CR_PLLRDY))
cpu_relax();
/* Switch to the externally-driven PLL for system clock. */
rcc->cfgr |= RCC_CFGR_SW_PLL;
while ((rcc->cfgr & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_PLL)
cpu_relax();
/* Internal oscillator no longer needed. */
rcc->cr &= ~RCC_CR_HSION;
/* Enable SysTick counter at 72/8=9MHz. */
stk->load = STK_MASK;
stk->ctrl = STK_CTRL_ENABLE;
#endif
}
static void gpio_init(GPIO gpio)
{
/* Floating Input. Reference Manual states that JTAG pins are in PU/PD
* mode at reset, so ensure all PU/PD are disabled. */
//gpio->crl = gpio->crh = 0x44444444u;
}
static void peripheral_init(void)
{
#if 0
/* Enable basic GPIO and AFIO clocks, all timers, and DMA. */
rcc->apb1enr = (RCC_APB1ENR_TIM2EN |
RCC_APB1ENR_TIM3EN |
RCC_APB1ENR_TIM4EN);
rcc->apb2enr = (RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_IOPCEN |
RCC_APB2ENR_AFIOEN |
RCC_APB2ENR_TIM1EN);
rcc->ahbenr = RCC_AHBENR_DMA1EN;
/* Turn off serial-wire JTAG and reclaim the GPIOs. */
afio->mapr = AFIO_MAPR_SWJ_CFG_DISABLED;
#endif
/* All pins in a stable state. */
gpio_init(gpioa);
gpio_init(gpiob);
gpio_init(gpioc);
}
void stm32_init(void)
{
cortex_init();
clock_init();
peripheral_init();
cpu_sync();
}
void gpio_configure_pin(GPIO gpio, unsigned int pin, unsigned int mode)
{
gpio_write_pin(gpio, pin, mode >> 7);
gpio->moder = (gpio->moder & ~(3<<(pin<<1))) | ((mode&3)<<(pin<<1));
mode >>= 2;
gpio->otyper = (gpio->otyper & ~(1<<pin)) | ((mode&1)<<pin);
mode >>= 1;
gpio->ospeedr = (gpio->ospeedr & ~(3<<(pin<<1))) | ((mode&3)<<(pin<<1));
mode >>= 2;
gpio->pupdr = (gpio->pupdr & ~(3<<(pin<<1))) | ((mode&3)<<(pin<<1));
}
/*
* Local variables:
* mode: C
* c-file-style: "Linux"
* c-basic-offset: 4
* tab-width: 4
* indent-tabs-mode: nil
* End:
*/