diff options
| -rw-r--r-- | src/stmf0/Makefile-stmf0.defs | 47 | ||||
| -rw-r--r-- | src/stmf0/Makefile.defs | 9 | ||||
| -rw-r--r-- | src/stmf0/altos.ld | 97 | ||||
| -rw-r--r-- | src/stmf0/ao_arch.h | 157 | ||||
| -rw-r--r-- | src/stmf0/ao_arch_funcs.h | 398 | ||||
| -rw-r--r-- | src/stmf0/ao_boot_chain.c | 67 | ||||
| -rw-r--r-- | src/stmf0/ao_boot_pin.c | 46 | ||||
| -rw-r--r-- | src/stmf0/ao_interrupt.c | 167 | ||||
| -rw-r--r-- | src/stmf0/ao_led.c | 125 | ||||
| -rw-r--r-- | src/stmf0/ao_romconfig.c | 27 | ||||
| -rw-r--r-- | src/stmf0/ao_timer.c | 262 | ||||
| -rw-r--r-- | src/stmf0/ao_usb_stm.c | 1090 | ||||
| -rw-r--r-- | src/stmf0/registers.ld | 60 | ||||
| -rw-r--r-- | src/stmf0/stm32f0.h | 1995 | 
14 files changed, 4547 insertions, 0 deletions
diff --git a/src/stmf0/Makefile-stmf0.defs b/src/stmf0/Makefile-stmf0.defs new file mode 100644 index 00000000..4862f46e --- /dev/null +++ b/src/stmf0/Makefile-stmf0.defs @@ -0,0 +1,47 @@ +ifndef TOPDIR +TOPDIR=.. +endif + +include $(TOPDIR)/Makedefs + +vpath % $(TOPDIR)/stmf0:$(TOPDIR)/product:$(TOPDIR)/drivers:$(TOPDIR)/kernel:$(TOPDIR)/util:$(TOPDIR)/kalman:$(TOPDIR/aes):$(TOPDIR):$(TOPDIR)/math +vpath make-altitude $(TOPDIR)/util +vpath make-kalman $(TOPDIR)/util +vpath kalman.5c $(TOPDIR)/kalman +vpath kalman_filter.5c $(TOPDIR)/kalman +vpath load_csv.5c $(TOPDIR)/kalman +vpath matrix.5c $(TOPDIR)/kalman +vpath ao-make-product.5c $(TOPDIR)/util + +.SUFFIXES: .elf .ihx + +.elf.ihx: +	$(ELFTOHEX) --output=$@ $*.elf + +ifndef VERSION +include $(TOPDIR)/Version +endif + +ELFTOHEX=$(TOPDIR)/../ao-tools/ao-elftohex/ao-elftohex +CC=$(ARM_CC) + +WARN_FLAGS=-Wall -Wextra -Werror + +AO_CFLAGS=-I. -I$(TOPDIR)/stmf0 -I$(TOPDIR)/kernel -I$(TOPDIR)/drivers -I$(TOPDIR)/product -I$(TOPDIR) -I$(TOPDIR)/math $(PDCLIB_INCLUDES)  +STMF0_CFLAGS=-std=gnu99 -mlittle-endian -mcpu=cortex-m0 -mthumb\ +	-ffreestanding -nostdlib $(AO_CFLAGS) $(WARN_FLAGS) + +NICKLE=nickle + +LIBS=$(PDCLIB_LIBS_M0) -lgcc + +V=0 +# The user has explicitly enabled quiet compilation. +ifeq ($(V),0) +quiet = @printf "  $1 $2 $@\n"; $($1) +endif +# Otherwise, print the full command line. +quiet ?= $($1) + +.c.o: +	$(call quiet,CC) -c $(CFLAGS) -o $@ $< diff --git a/src/stmf0/Makefile.defs b/src/stmf0/Makefile.defs new file mode 100644 index 00000000..a1d93eb5 --- /dev/null +++ b/src/stmf0/Makefile.defs @@ -0,0 +1,9 @@ +ifndef TOPDIR +TOPDIR=.. +endif + +include $(TOPDIR)/stmf0/Makefile-stmf0.defs + +LDFLAGS=$(CFLAGS) -L$(TOPDIR)/stmf0 -Wl,-Taltos.ld + +.DEFAULT_GOAL=all diff --git a/src/stmf0/altos.ld b/src/stmf0/altos.ld new file mode 100644 index 00000000..6672c1fd --- /dev/null +++ b/src/stmf0/altos.ld @@ -0,0 +1,97 @@ +/* + * Copyright © 2012 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +MEMORY { +	rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K +	ram (!w) : ORIGIN = 0x20000000, LENGTH = 5632 +	stack (!w) : ORIGIN = 0x20001600, LENGTH = 512 +} + +INCLUDE registers.ld + +EXTERN (stm_interrupt_vector) + +SECTIONS { +	/* +	 * Rom contents +	 */ + +	.text ORIGIN(rom) : { +		__text_start__ = .; +		*(.interrupt)	/* Interrupt vectors */ + +		. = ORIGIN(rom) + 0x100; + + +		/* Ick. What I want is to specify the +		 * addresses of some global constants so +		 * that I can find them across versions +		 * of the application. I can't figure out +		 * how to make gnu ld do that, so instead +		 * we just load the two files that include +		 * these defines in the right order here and +		 * expect things to 'just work'. Don't change +		 * the contents of those files, ok? +		 */ +		ao_romconfig.o(.romconfig*) +		ao_product.o(.romconfig*) +		*(.text*)	/* Executable code */ +		*(.rodata*)	/* Constants */ + +	} > rom + +	.ARM.exidx : { +		*(.ARM.exidx* .gnu.linkonce.armexidx.*) +	} > rom +	__text_end__ = .; + +	/* Boot data which must live at the start of ram so that +	 * the application and bootloader share the same addresses. +	 * This must be all uninitialized data +	 */ +	.boot (NOLOAD) : { +		__boot_start__ = .; +		*(.boot) +		. = ALIGN(4); +		__boot_end__ = .; +	} >ram + +	/* Data -- relocated to RAM, but written to ROM +	 */ +	.data : { +		__data_start__ = .; +		*(.data)	/* initialized data */ +		. = ALIGN(4); +		__data_end__ = .; +	} >ram AT>rom + +	.bss : { +		__bss_start__ = .; +		*(.bss) +		*(COMMON) +		. = ALIGN(4); +		__bss_end__ = .; +	} >ram + +	PROVIDE(end = .); + +	PROVIDE(__stack__ = ORIGIN(stack) + LENGTH(stack)); +} + +ENTRY(start); + + diff --git a/src/stmf0/ao_arch.h b/src/stmf0/ao_arch.h new file mode 100644 index 00000000..6ee71ef9 --- /dev/null +++ b/src/stmf0/ao_arch.h @@ -0,0 +1,157 @@ +/* + * Copyright © 2012 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#ifndef _AO_ARCH_H_ +#define _AO_ARCH_H_ + +#include <stdio.h> +#include <stm32f0.h> + +/* + * STM32F0 definitions and code fragments for AltOS + */ + +#define AO_STACK_SIZE	512 + +#define AO_LED_TYPE	uint16_t + +#ifndef AO_TICK_TYPE +#define AO_TICK_TYPE	uint16_t +#define AO_TICK_SIGNED	int16_t +#endif + +#define AO_PORT_TYPE	uint16_t + +/* Various definitions to make GCC look more like SDCC */ + +#define ao_arch_naked_declare	__attribute__((naked)) +#define ao_arch_naked_define +#define __pdata +#define __data +#define __xdata +#define __code const +#define __reentrant +#define __interrupt(n) +#define __at(n) + +#define ao_arch_reboot() \ +	(stm_scb.aircr = ((STM_SCB_AIRCR_VECTKEY_KEY << STM_SCB_AIRCR_VECTKEY) | \ +			  (1 << STM_SCB_AIRCR_SYSRESETREQ))) + +#define ao_arch_nop()		asm("nop") + +#define ao_arch_interrupt(n)	/* nothing */ + +#undef putchar +#undef getchar +#define putchar(c)	ao_putchar(c) +#define getchar		ao_getchar + +extern void putchar(char c); +extern char getchar(void); +extern void ao_avr_stdio_init(void); + + +/* + * ao_romconfig.c + */ + +#define AO_ROMCONFIG_VERSION	2 + +#define AO_ROMCONFIG_SYMBOL(a) __attribute__((section(".romconfig"))) const + +extern const uint16_t ao_romconfig_version; +extern const uint16_t ao_romconfig_check; +extern const uint16_t ao_serial_number; +extern const uint32_t ao_radio_cal; + +#define ao_arch_task_members\ +	uint32_t *sp;			/* saved stack pointer */ + +#define ao_arch_block_interrupts()	asm("cpsid i") +#define ao_arch_release_interrupts()	asm("cpsie i") + +/* + * ao_timer.c + * + * For the stm32f042, we want to use the USB-based HSI48 clock + */ + +#if AO_HSI48 + +#define AO_SYSCLK	48000000 +#define AO_HCLK		(AO_SYSCLK / AO_AHB_PRESCALER) + +#endif + +#if AO_HSE || AO_HSI + +#if AO_HSE +#define AO_PLLSRC	AO_HSE +#else +#define AO_PLLSRC	STM_HSI_FREQ +#endif + +#define AO_PLLVCO	(AO_PLLSRC * AO_PLLMUL) +#define AO_SYSCLK	(AO_PLLVCO / AO_PLLDIV) + +#endif + +#define AO_HCLK		(AO_SYSCLK / AO_AHB_PRESCALER) +#define AO_PCLK1	(AO_HCLK / AO_APB1_PRESCALER) +#define AO_PCLK2	(AO_HCLK / AO_APB2_PRESCALER) +#define AO_SYSTICK	(AO_HCLK) + +#if AO_APB1_PRESCALER == 1 +#define AO_TIM23467_CLK		AO_PCLK1 +#else +#define AO_TIM23467_CLK		(2 * AO_PCLK1) +#endif + +#if AO_APB2_PRESCALER == 1 +#define AO_TIM91011_CLK		AO_PCLK2 +#else +#define AO_TIM91011_CLK		(2 * AO_PCLK2) +#endif + +#define AO_STM_NVIC_HIGH_PRIORITY	4 +#define AO_STM_NVIC_CLOCK_PRIORITY	6 +#define AO_STM_NVIC_MED_PRIORITY	8 +#define AO_STM_NVIC_LOW_PRIORITY	10 + +void ao_lcd_stm_init(void); + +void ao_lcd_font_init(void); + +void ao_lcd_font_string(char *s); + +extern const uint32_t	ao_radio_cal; + +void +ao_adc_init(); + +/* ADC maximum reported value */ +#define AO_ADC_MAX			4095 + +#define AO_BOOT_APPLICATION_BASE	((uint32_t *) 0x08001000) +#define AO_BOOT_APPLICATION_BOUND	((uint32_t *) (0x08000000 + stm_flash_size())) +#define AO_BOOT_LOADER_BASE		((uint32_t *) 0x08000000) +#define HAS_BOOT_LOADER			1 + +#endif /* _AO_ARCH_H_ */ + + diff --git a/src/stmf0/ao_arch_funcs.h b/src/stmf0/ao_arch_funcs.h new file mode 100644 index 00000000..2f2f8f43 --- /dev/null +++ b/src/stmf0/ao_arch_funcs.h @@ -0,0 +1,398 @@ +/* + * Copyright © 2012 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#ifndef _AO_ARCH_FUNCS_H_ +#define _AO_ARCH_FUNCS_H_ + +/* ao_spi_stm.c + */ + +/* PCLK is set to 16MHz (HCLK 32MHz, APB prescaler 2) */ + +#define AO_SPI_SPEED_8MHz	STM_SPI_CR1_BR_PCLK_2 +#define AO_SPI_SPEED_4MHz	STM_SPI_CR1_BR_PCLK_4 +#define AO_SPI_SPEED_2MHz	STM_SPI_CR1_BR_PCLK_8 +#define AO_SPI_SPEED_1MHz	STM_SPI_CR1_BR_PCLK_16 +#define AO_SPI_SPEED_500kHz	STM_SPI_CR1_BR_PCLK_32 +#define AO_SPI_SPEED_250kHz	STM_SPI_CR1_BR_PCLK_64 +#define AO_SPI_SPEED_125kHz	STM_SPI_CR1_BR_PCLK_128 +#define AO_SPI_SPEED_62500Hz	STM_SPI_CR1_BR_PCLK_256 + +#define AO_SPI_SPEED_FAST	AO_SPI_SPEED_8MHz + +/* Companion bus wants something no faster than 200kHz */ + +#define AO_SPI_SPEED_200kHz	AO_SPI_SPEED_125kHz + +#define AO_SPI_CONFIG_1		0x00 +#define AO_SPI_1_CONFIG_PA5_PA6_PA7	AO_SPI_CONFIG_1 +#define AO_SPI_2_CONFIG_PB13_PB14_PB15	AO_SPI_CONFIG_1 + +#define AO_SPI_CONFIG_2		0x04 +#define AO_SPI_1_CONFIG_PB3_PB4_PB5	AO_SPI_CONFIG_2 +#define AO_SPI_2_CONFIG_PD1_PD3_PD4	AO_SPI_CONFIG_2 + +#define AO_SPI_CONFIG_3		0x08 +#define AO_SPI_1_CONFIG_PE13_PE14_PE15	AO_SPI_CONFIG_3 + +#define AO_SPI_CONFIG_NONE	0x0c + +#define AO_SPI_INDEX_MASK	0x01 +#define AO_SPI_CONFIG_MASK	0x0c + +#define AO_SPI_1_PA5_PA6_PA7	(STM_SPI_INDEX(1) | AO_SPI_1_CONFIG_PA5_PA6_PA7) +#define AO_SPI_1_PB3_PB4_PB5	(STM_SPI_INDEX(1) | AO_SPI_1_CONFIG_PB3_PB4_PB5) +#define AO_SPI_1_PE13_PE14_PE15	(STM_SPI_INDEX(1) | AO_SPI_1_CONFIG_PE13_PE14_PE15) + +#define AO_SPI_2_PB13_PB14_PB15	(STM_SPI_INDEX(2) | AO_SPI_2_CONFIG_PB13_PB14_PB15) +#define AO_SPI_2_PD1_PD3_PD4	(STM_SPI_INDEX(2) | AO_SPI_2_CONFIG_PD1_PD3_PD4) + +#define AO_SPI_INDEX(id)	((id) & AO_SPI_INDEX_MASK) +#define AO_SPI_CONFIG(id)	((id) & AO_SPI_CONFIG_MASK) + +uint8_t +ao_spi_try_get(uint8_t spi_index, uint32_t speed, uint8_t task_id); + +void +ao_spi_get(uint8_t spi_index, uint32_t speed); + +void +ao_spi_put(uint8_t spi_index); + +void +ao_spi_send(const void *block, uint16_t len, uint8_t spi_index); + +void +ao_spi_send_fixed(uint8_t value, uint16_t len, uint8_t spi_index); + +void +ao_spi_send_sync(void *block, uint16_t len, uint8_t spi_index); + +void +ao_spi_recv(void *block, uint16_t len, uint8_t spi_index); + +void +ao_spi_duplex(void *out, void *in, uint16_t len, uint8_t spi_index); + +extern uint16_t	ao_spi_speed[STM_NUM_SPI]; + +void +ao_spi_init(void); + +#define ao_spi_set_cs(reg,mask) ((reg)->bsrr = ((uint32_t) (mask)) << 16) +#define ao_spi_clr_cs(reg,mask) ((reg)->bsrr = (mask)) + +#define ao_spi_get_mask(reg,mask,bus, speed) do {		\ +		ao_spi_get(bus, speed);				\ +		ao_spi_set_cs(reg,mask);			\ +	} while (0) + +static inline uint8_t +ao_spi_try_get_mask(struct stm_gpio *reg, uint16_t mask, uint8_t bus, uint32_t speed, uint8_t task_id) +{ +	if (!ao_spi_try_get(bus, speed, task_id)) +		return 0; +	ao_spi_set_cs(reg, mask); +	return 1; +} + +#define ao_spi_put_mask(reg,mask,bus) do {	\ +		ao_spi_clr_cs(reg,mask);	\ +		ao_spi_put(bus);		\ +	} while (0) + +#define ao_spi_get_bit(reg,bit,pin,bus,speed) ao_spi_get_mask(reg,(1<<bit),bus,speed) +#define ao_spi_put_bit(reg,bit,pin,bus) ao_spi_put_mask(reg,(1<<bit),bus) + +#define ao_enable_port(port) do {					\ +		if ((port) == &stm_gpioa)				\ +			stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_GPIOAEN); \ +		else if ((port) == &stm_gpiob)				\ +			stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_GPIOBEN); \ +		else if ((port) == &stm_gpioc)				\ +			stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_GPIOCEN); \ +		else if ((port) == &stm_gpiod)				\ +			stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_GPIODEN); \ +		else if ((port) == &stm_gpioe)				\ +			stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_GPIOEEN); \ +	} while (0) + +#define ao_disable_port(port) do {					\ +		if ((port) == &stm_gpioa)				\ +			stm_rcc.ahbenr &= ~(1 << STM_RCC_AHBENR_GPIOAEN); \ +		else if ((port) == &stm_gpiob)				\ +			stm_rcc.ahbenr &= ~(1 << STM_RCC_AHBENR_GPIOBEN); \ +		else if ((port) == &stm_gpioc)				\ +			stm_rcc.ahbenr &= ~(1 << STM_RCC_AHBENR_GPIOCEN); \ +		else if ((port) == &stm_gpiod)				\ +			stm_rcc.ahbenr &= ~(1 << STM_RCC_AHBENR_GPIODEN); \ +		else if ((port) == &stm_gpioe)				\ +			stm_rcc.ahbenr &= ~(1 << STM_RCC_AHBENR_GPIOEEN); \ +	} while (0) + + +#define ao_gpio_set(port, bit, pin, v) stm_gpio_set(port, bit, v) + +#define ao_gpio_get(port, bit, pin) stm_gpio_get(port, bit) + +#define ao_enable_output(port,bit,pin,v) do {			\ +		ao_enable_port(port);				\ +		ao_gpio_set(port, bit, pin, v);			\ +		stm_moder_set(port, bit, STM_MODER_OUTPUT);\ +	} while (0) + +#define ao_gpio_set_mode(port,bit,mode) do {				\ +		if (mode == AO_EXTI_MODE_PULL_UP)			\ +			stm_pupdr_set(port, bit, STM_PUPDR_PULL_UP);	\ +		else if (mode == AO_EXTI_MODE_PULL_DOWN)		\ +			stm_pupdr_set(port, bit, STM_PUPDR_PULL_DOWN);	\ +		else							\ +			stm_pupdr_set(port, bit, STM_PUPDR_NONE);	\ +	} while (0) +	 +#define ao_enable_input(port,bit,mode) do {				\ +		ao_enable_port(port);					\ +		stm_moder_set(port, bit, STM_MODER_INPUT);		\ +		ao_gpio_set_mode(port, bit, mode);			\ +	} while (0) + +#define ao_enable_cs(port,bit) do {				\ +		stm_gpio_set((port), bit, 1);			\ +		stm_moder_set((port), bit, STM_MODER_OUTPUT);	\ +	} while (0) + +#define ao_spi_init_cs(port, mask) do {				\ +		ao_enable_port(port);				\ +		if ((mask) & 0x0001) ao_enable_cs(port, 0);	\ +		if ((mask) & 0x0002) ao_enable_cs(port, 1);	\ +		if ((mask) & 0x0004) ao_enable_cs(port, 2);	\ +		if ((mask) & 0x0008) ao_enable_cs(port, 3);	\ +		if ((mask) & 0x0010) ao_enable_cs(port, 4);	\ +		if ((mask) & 0x0020) ao_enable_cs(port, 5);	\ +		if ((mask) & 0x0040) ao_enable_cs(port, 6);	\ +		if ((mask) & 0x0080) ao_enable_cs(port, 7);	\ +		if ((mask) & 0x0100) ao_enable_cs(port, 8);	\ +		if ((mask) & 0x0200) ao_enable_cs(port, 9);	\ +		if ((mask) & 0x0400) ao_enable_cs(port, 10);\ +		if ((mask) & 0x0800) ao_enable_cs(port, 11);\ +		if ((mask) & 0x1000) ao_enable_cs(port, 12);\ +		if ((mask) & 0x2000) ao_enable_cs(port, 13);\ +		if ((mask) & 0x4000) ao_enable_cs(port, 14);\ +		if ((mask) & 0x8000) ao_enable_cs(port, 15);\ +	} while (0) + +/* ao_dma_stm.c + */ + +extern uint8_t ao_dma_done[STM_NUM_DMA]; + +void +ao_dma_set_transfer(uint8_t 		index, +		    volatile void	*peripheral, +		    void		*memory, +		    uint16_t		count, +		    uint32_t		ccr); + +void +ao_dma_set_isr(uint8_t index, void (*isr)(int index)); + +void +ao_dma_start(uint8_t index); + +void +ao_dma_done_transfer(uint8_t index); + +void +ao_dma_abort(uint8_t index); + +void +ao_dma_alloc(uint8_t index); + +void +ao_dma_init(void); + +/* ao_i2c_stm.c */ + +void +ao_i2c_get(uint8_t i2c_index); + +uint8_t +ao_i2c_start(uint8_t i2c_index, uint16_t address); + +void +ao_i2c_put(uint8_t i2c_index); + +uint8_t +ao_i2c_send(void *block, uint16_t len, uint8_t i2c_index, uint8_t stop); + +uint8_t +ao_i2c_recv(void *block, uint16_t len, uint8_t i2c_index, uint8_t stop); + +void +ao_i2c_init(void); + +/* ao_serial_stm.c */ +struct ao_stm_usart { +	struct ao_fifo		rx_fifo; +	struct ao_fifo		tx_fifo; +	struct stm_usart	*reg; +	uint8_t			tx_started; +}; + +#if HAS_SERIAL_1 +extern struct ao_stm_usart	ao_stm_usart1; +#endif + +#if HAS_SERIAL_2 +extern struct ao_stm_usart	ao_stm_usart2; +#endif + +#if HAS_SERIAL_3 +extern struct ao_stm_usart	ao_stm_usart3; +#endif + +#define ARM_PUSH32(stack, val)	(*(--(stack)) = (val)) + +typedef uint32_t	ao_arch_irq_t; + +static inline uint32_t +ao_arch_irqsave(void) { +	uint32_t	primask; +	asm("mrs %0,primask" : "=&r" (primask)); +	ao_arch_block_interrupts(); +	return primask; +} + +static inline void +ao_arch_irqrestore(uint32_t primask) { +	asm("msr primask,%0" : : "r" (primask)); +} + +static inline void +ao_arch_memory_barrier() { +	asm volatile("" ::: "memory"); +} + +#if HAS_TASK +static inline void +ao_arch_init_stack(struct ao_task *task, void *start) +{ +	uint32_t	*sp = (uint32_t *) (task->stack + AO_STACK_SIZE); +	uint32_t	a = (uint32_t) start; +	int		i; + +	/* Return address (goes into LR) */ +	ARM_PUSH32(sp, a); + +	/* Clear register values r0-r7 */ +	i = 8; +	while (i--) +		ARM_PUSH32(sp, 0); + +	/* APSR */ +	ARM_PUSH32(sp, 0); + +	/* PRIMASK with interrupts enabled */ +	ARM_PUSH32(sp, 0); + +	task->sp = sp; +} + +static inline void ao_arch_save_regs(void) { +	/* Save general registers */ +	asm("push {r0-r7,lr}\n"); + +	/* Save APSR */ +	asm("mrs r0,apsr"); +	asm("push {r0}"); + +	/* Save PRIMASK */ +	asm("mrs r0,primask"); +	asm("push {r0}"); +} + +static inline void ao_arch_save_stack(void) { +	uint32_t	*sp; +	asm("mov %0,sp" : "=&r" (sp) ); +	ao_cur_task->sp = (sp); +	if ((uint8_t *) sp < &ao_cur_task->stack[0]) +		ao_panic (AO_PANIC_STACK); +} + +static inline void ao_arch_restore_stack(void) { +	uint32_t	sp; +	sp = (uint32_t) ao_cur_task->sp; + +	/* Switch stacks */ +	asm("mov sp, %0" : : "r" (sp) ); + +	/* Restore PRIMASK */ +	asm("pop {r0}"); +	asm("msr primask,r0"); + +	/* Restore APSR */ +	asm("pop {r0}"); +	asm("msr apsr_nczvq,r0"); + +	/* Restore general registers */ +	asm("pop {r0-r7,pc}\n"); +} + +#ifndef HAS_SAMPLE_PROFILE +#define HAS_SAMPLE_PROFILE 0 +#endif + +#if !HAS_SAMPLE_PROFILE +#define HAS_ARCH_START_SCHEDULER	1 + +static inline void ao_arch_start_scheduler(void) { +	uint32_t	sp; +	uint32_t	control; + +	asm("mrs %0,msp" : "=&r" (sp)); +	asm("msr psp,%0" : : "r" (sp)); +	asm("mrs %0,control" : "=&r" (control)); +	control |= (1 << 1); +	asm("msr control,%0" : : "r" (control)); +	asm("isb"); +} +#endif + +#define ao_arch_isr_stack() + +#endif + +#define ao_arch_wait_interrupt() do {				\ +		asm("\twfi\n");					\ +		ao_arch_release_interrupts();			\ +		asm(".global ao_idle_loc\nao_idle_loc:");	\ +		ao_arch_block_interrupts();			\ +	} while (0) + +#define ao_arch_critical(b) do {			\ +		uint32_t __mask = ao_arch_irqsave();	\ +		do { b } while (0);			\ +		ao_arch_irqrestore(__mask);		\ +	} while (0) + +void +ao_clock_enable_crs(void); + +void +ao_clock_disable_crs(void); + +#endif /* _AO_ARCH_FUNCS_H_ */ diff --git a/src/stmf0/ao_boot_chain.c b/src/stmf0/ao_boot_chain.c new file mode 100644 index 00000000..bcebf033 --- /dev/null +++ b/src/stmf0/ao_boot_chain.c @@ -0,0 +1,67 @@ +/* + * Copyright © 2013 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#include <ao.h> +#include <ao_boot.h> + +void +ao_boot_chain(uint32_t *base) +{ +	uint32_t	sp; +	uint32_t	pc; + +	sp = base[0]; +	pc = base[1]; +	if (0x08000100 <= pc && pc <= 0x08200000 && (pc & 1) == 1) { +		asm ("mov sp, %0" : : "r" (sp)); +		asm ("mov lr, %0" : : "r" (pc)); +		asm ("bx lr"); +	} +} + +#define AO_BOOT_SIGNAL	0x5a5aa5a5 +#define AO_BOOT_CHECK	0xc3c33c3c + +struct ao_boot { +	uint32_t	*base; +	uint32_t	signal; +	uint32_t	check; +}; + +static struct ao_boot __attribute__ ((section(".boot"))) ao_boot; +	 +int +ao_boot_check_chain(void) +{ +	if (ao_boot.signal == AO_BOOT_SIGNAL && ao_boot.check == AO_BOOT_CHECK) { +		ao_boot.signal = 0; +		ao_boot.check = 0; +		if (ao_boot.base == AO_BOOT_FORCE_LOADER) +			return 0; +		ao_boot_chain(ao_boot.base); +	} +	return 1; +} + +void +ao_boot_reboot(uint32_t *base) +{ +	ao_boot.base = base; +	ao_boot.signal = AO_BOOT_SIGNAL; +	ao_boot.check = AO_BOOT_CHECK; +	ao_arch_reboot(); +} diff --git a/src/stmf0/ao_boot_pin.c b/src/stmf0/ao_boot_pin.c new file mode 100644 index 00000000..e825b618 --- /dev/null +++ b/src/stmf0/ao_boot_pin.c @@ -0,0 +1,46 @@ +/* + * Copyright © 2013 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#include <ao.h> +#include <ao_boot.h> +#include <ao_exti.h> + +void +ao_boot_check_pin(void) +{ +	uint16_t v; + +	/* Enable power interface clock */ +	stm_rcc.apb1enr |= (1 << STM_RCC_APB1ENR_PWREN); + +	/* Enable the input pin */ +	ao_enable_input(&AO_BOOT_APPLICATION_GPIO, AO_BOOT_APPLICATION_PIN, +			AO_BOOT_APPLICATION_MODE); + +	for (v = 0; v < 100; v++) +		ao_arch_nop(); + +	/* Read the value */ +	v = stm_gpio_get(&AO_BOOT_APPLICATION_GPIO, AO_BOOT_APPLICATION_PIN); + +	/* Reset the chip to turn off the port and the power interface clock */ +	ao_gpio_set_mode(&AO_BOOT_APPLICATION_GPIO, AO_BOOT_APPLICATION_PIN, 0); +	ao_disable_port(&AO_BOOT_APPLICATION_GPIO); +	stm_rcc.apb1enr &= ~(1 << STM_RCC_APB1ENR_PWREN); +	if (v == AO_BOOT_APPLICATION_VALUE) +		ao_boot_chain(AO_BOOT_APPLICATION_BASE); +} diff --git a/src/stmf0/ao_interrupt.c b/src/stmf0/ao_interrupt.c new file mode 100644 index 00000000..99a88dcb --- /dev/null +++ b/src/stmf0/ao_interrupt.c @@ -0,0 +1,167 @@ +/* + * Copyright © 2012 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#include <ao.h> +#include "stm32f0.h" +#include <string.h> +#include <ao_boot.h> + +extern void main(void); +extern char __stack__; +extern char __text_start__, __text_end__; +extern char __data_start__, __data_end__; +extern char __bss_start__, __bss_end__; + +/* Interrupt functions */ + +void stm_halt_isr(void) +{ +	ao_panic(AO_PANIC_CRASH); +} + +void stm_ignore_isr(void) +{ +} + +const void *stm_interrupt_vector[]; + +uint32_t +stm_flash_size(void) { +	uint16_t	dev_id = stm_dev_id(); +	uint16_t	kbytes = 0; + +	switch (dev_id) { +	case 0x445: +		kbytes = 32;	/* assume 32kB until we figure this out */ +		break; +	} +	return (uint32_t) kbytes * 1024; +} + +void start(void) +{ +#if 0 +#ifdef AO_BOOT_CHAIN +	if (ao_boot_check_chain()) { +#ifdef AO_BOOT_PIN +		ao_boot_check_pin(); +#endif +	} +#endif +#endif +	memcpy(&__data_start__, &__text_end__, &__data_end__ - &__data_start__); +	memset(&__bss_start__, '\0', &__bss_end__ - &__bss_start__); +	main(); +} + +#define STRINGIFY(x) #x + +#define isr(name) \ +	void __attribute__ ((weak)) stm_ ## name ## _isr(void); \ +	_Pragma(STRINGIFY(weak stm_ ## name ## _isr = stm_ignore_isr)) + +#define isr_halt(name) \ +	void __attribute__ ((weak)) stm_ ## name ## _isr(void); \ +	_Pragma(STRINGIFY(weak stm_ ## name ## _isr = stm_halt_isr)) + +isr(nmi) +isr_halt(hardfault) +isr_halt(memmanage) +isr_halt(busfault) +isr_halt(usagefault) +isr(svc) +isr(debugmon) +isr(pendsv) +isr(systick) +isr(wwdg) +isr(pvd) +isr(rtc) +isr(flash) +isr(rcc_crs) +isr(exti0_1) +isr(exti2_3) +isr(exti4_15) +isr(tsc) +isr(dma_ch1) +isr(dma_ch2_3_dma2_ch1_2) +isr(dma_ch4_5_6_7_dma2_ch3_4_5) +isr(adc_comp) +isr(tim1_brk_up_trg_com) +isr(tim1_cc) +isr(tim2) +isr(tim3) +isr(tim6_dac) +isr(tim7) +isr(tim14) +isr(tim15) +isr(tim16) +isr(tim17) +isr(i2c1) +isr(i2c2) +isr(spi1) +isr(spi2) +isr(usart1) +isr(usart2) +isr(usart3_4_5_6_7_8) +isr(cec_can) +isr(usb) + +#define i(addr,name)	[(addr)/4] = stm_ ## name ## _isr + +__attribute__ ((section(".interrupt"))) +const void *stm_interrupt_vector[] = { +	[0] = &__stack__, +	[1] = start, +	i(0x08, nmi), +	i(0x0c, hardfault), +	i(0x2c, svc), +	i(0x30, debugmon), +	i(0x38, pendsv), +	i(0x3c, systick), +	i(0x40, wwdg),		/* IRQ0 */ +	i(0x44, pvd), +	i(0x48, rtc), +	i(0x4c, flash), +	i(0x50, rcc_crs), +	i(0x54, exti0_1), +	i(0x58, exti2_3), +	i(0x5c, exti4_15), +	i(0x60, tsc), +	i(0x64, dma_ch1), +	i(0x68, dma_ch2_3_dma2_ch1_2), +	i(0x6c, dma_ch4_5_6_7_dma2_ch3_4_5), +	i(0x70, adc_comp), +	i(0x74, tim1_brk_up_trg_com), +	i(0x78, tim1_cc), +	i(0x7c, tim2), +	i(0x80, tim3), +	i(0x84, tim6_dac), +	i(0x88, tim7), +	i(0x8c, tim14), +	i(0x90, tim15), +	i(0x94, tim16), +	i(0x98, tim17), +	i(0x9c, i2c1), +	i(0xa0, i2c2), +	i(0xa4, spi1), +	i(0xa8, spi2), +	i(0xac, usart1), +	i(0xb0, usart2), +	i(0xb4, usart3_4_5_6_7_8), +	i(0xb8, cec_can), +	i(0xbc, usb), +}; diff --git a/src/stmf0/ao_led.c b/src/stmf0/ao_led.c new file mode 100644 index 00000000..9b61cf62 --- /dev/null +++ b/src/stmf0/ao_led.c @@ -0,0 +1,125 @@ +/* + * Copyright © 2012 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#include "ao.h" + +__pdata uint16_t ao_led_enable; + +void +ao_led_on(uint16_t colors) +{ +#ifdef LED_PORT +	LED_PORT->bsrr = (colors & ao_led_enable); +#else +#ifdef LED_PORT_0 +	LED_PORT_0->bsrr = ((colors & ao_led_enable) & LED_PORT_0_MASK) << LED_PORT_0_SHIFT; +#endif +#ifdef LED_PORT_1 +	LED_PORT_1->bsrr = ((colors & ao_led_enable) & LED_PORT_1_MASK) << LED_PORT_1_SHIFT; +#endif +#endif +} + +void +ao_led_off(uint16_t colors) +{ +#ifdef LED_PORT +	LED_PORT->bsrr = (uint32_t) (colors & ao_led_enable) << 16; +#else +#ifdef LED_PORT_0 +	LED_PORT_0->bsrr = ((uint32_t) (colors & ao_led_enable) & LED_PORT_0_MASK) << (LED_PORT_0_SHIFT + 16); +#endif +#ifdef LED_PORT_1 +	LED_PORT_1->bsrr = ((uint32_t) (colors & ao_led_enable) & LED_PORT_1_MASK) << (LED_PORT_1_SHIFT + 16); +#endif +#endif +} + +void +ao_led_set(uint16_t colors) +{ +	uint16_t	on = colors & ao_led_enable; +	uint16_t	off = ~colors & ao_led_enable; + +	ao_led_off(off); +	ao_led_on(on); +} + +void +ao_led_toggle(uint16_t colors) +{ +#ifdef LED_PORT +	LED_PORT->odr ^= (colors & ao_led_enable); +#else +#ifdef LED_PORT_0 +	LED_PORT_0->odr ^= ((colors & ao_led_enable) & LED_PORT_0_MASK) << LED_PORT_0_SHIFT; +#endif +#ifdef LED_PORT_1 +	LED_PORT_1->odr ^= ((colors & ao_led_enable) & LED_PORT_1_MASK) << LED_PORT_1_SHIFT; +#endif +#endif +} + +void +ao_led_for(uint16_t colors, uint16_t ticks) __reentrant +{ +	ao_led_on(colors); +	ao_delay(ticks); +	ao_led_off(colors); +} + +#define init_led_pin(port, bit) do { \ +		stm_moder_set(port, bit, STM_MODER_OUTPUT);		\ +		stm_otyper_set(port, bit, STM_OTYPER_PUSH_PULL);	\ +	} while (0) + +void +ao_led_init(uint16_t enable) +{ +	int	bit; + +	ao_led_enable = enable; +#ifdef LED_PORT +	stm_rcc.ahbenr |= (1 << LED_PORT_ENABLE); +	LED_PORT->odr &= ~enable; +#else +#ifdef LED_PORT_0 +	stm_rcc.ahbenr |= (1 << LED_PORT_0_ENABLE); +	LED_PORT_0->odr &= ~((enable & ao_led_enable) & LED_PORT_0_MASK) << LED_PORT_0_SHIFT; +#endif +#ifdef LED_PORT_1 +	stm_rcc.ahbenr |= (1 << LED_PORT_1_ENABLE); +	LED_PORT_1->odr &= ~((enable & ao_led_enable) & LED_PORT_1_MASK) << LED_PORT_1_SHIFT; +#endif +#endif +	for (bit = 0; bit < 16; bit++) { +		if (enable & (1 << bit)) { +#ifdef LED_PORT +			init_led_pin(LED_PORT, bit); +#else +#ifdef LED_PORT_0 +			if (LED_PORT_0_MASK & (1 << bit)) +				init_led_pin(LED_PORT_0, bit + LED_PORT_0_SHIFT); +#endif +#ifdef LED_PORT_1 +			if (LED_PORT_1_MASK & (1 << bit)) +				init_led_pin(LED_PORT_1, bit + LED_PORT_1_SHIFT); +#endif +#endif +		} +	} +} diff --git a/src/stmf0/ao_romconfig.c b/src/stmf0/ao_romconfig.c new file mode 100644 index 00000000..5da15072 --- /dev/null +++ b/src/stmf0/ao_romconfig.c @@ -0,0 +1,27 @@ +/* + * Copyright © 2011 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#include "ao.h" + +AO_ROMCONFIG_SYMBOL (0) uint16_t ao_romconfig_version = AO_ROMCONFIG_VERSION; +AO_ROMCONFIG_SYMBOL (0) uint16_t ao_romconfig_check = ~AO_ROMCONFIG_VERSION; +AO_ROMCONFIG_SYMBOL (0) uint16_t ao_serial_number = 0; +#ifndef AO_RADIO_CAL_DEFAULT +#define AO_RADIO_CAL_DEFAULT 0x01020304 +#endif +AO_ROMCONFIG_SYMBOL (0) uint32_t ao_radio_cal = AO_RADIO_CAL_DEFAULT; + diff --git a/src/stmf0/ao_timer.c b/src/stmf0/ao_timer.c new file mode 100644 index 00000000..82a4cad6 --- /dev/null +++ b/src/stmf0/ao_timer.c @@ -0,0 +1,262 @@ +/* + * Copyright © 2012 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#include "ao.h" +#include <ao_task.h> +#if HAS_FAKE_FLIGHT +#include <ao_fake_flight.h> +#endif + +#ifndef HAS_TICK +#define HAS_TICK 1 +#endif + +#if HAS_TICK +volatile AO_TICK_TYPE ao_tick_count; + +AO_TICK_TYPE +ao_time(void) +{ +	return ao_tick_count; +} + +#if AO_DATA_ALL +volatile __data uint8_t	ao_data_interval = 1; +volatile __data uint8_t	ao_data_count; +#endif + +void stm_systick_isr(void) +{ +	if (stm_systick.csr & (1 << STM_SYSTICK_CSR_COUNTFLAG)) { +		++ao_tick_count; +#if HAS_TASK_QUEUE +		if (ao_task_alarm_tick && (int16_t) (ao_tick_count - ao_task_alarm_tick) >= 0) +			ao_task_check_alarm((uint16_t) ao_tick_count); +#endif +#if AO_DATA_ALL +		if (++ao_data_count == ao_data_interval) { +			ao_data_count = 0; +#if HAS_FAKE_FLIGHT +			if (ao_fake_flight_active) +				ao_fake_flight_poll(); +			else +#endif +				ao_adc_poll(); +#if (AO_DATA_ALL & ~(AO_DATA_ADC)) +			ao_wakeup((void *) &ao_data_count); +#endif +		} +#endif +#ifdef AO_TIMER_HOOK +		AO_TIMER_HOOK; +#endif +	} +} + +#if HAS_ADC +void +ao_timer_set_adc_interval(uint8_t interval) +{ +	ao_arch_critical( +		ao_data_interval = interval; +		ao_data_count = 0; +		); +} +#endif + +#define SYSTICK_RELOAD (AO_SYSTICK / 100 - 1) + +void +ao_timer_init(void) +{ +	stm_systick.rvr = SYSTICK_RELOAD; +	stm_systick.cvr = 0; +	stm_systick.csr = ((1 << STM_SYSTICK_CSR_ENABLE) | +			   (1 << STM_SYSTICK_CSR_TICKINT) | +			   (STM_SYSTICK_CSR_CLKSOURCE_HCLK_8 << STM_SYSTICK_CSR_CLKSOURCE)); +} + +#endif + +static void +ao_clock_enable_crs(void) +{ +	/* Enable crs interface clock */ +	stm_rcc.apb1enr |= (1 << STM_RCC_APB1ENR_CRSEN); + +	/* Disable error counter */ +	stm_crs.cr = ((stm_crs.cr & (1 << 4)) | +		      (32 << STM_CRS_CR_TRIM) | +		      (0 << STM_CRS_CR_SWSYNC) | +		      (0 << STM_CRS_CR_AUTOTRIMEN) | +		      (0 << STM_CRS_CR_CEN) | +		      (0 << STM_CRS_CR_ESYNCIE) | +		      (0 << STM_CRS_CR_ERRIE) | +		      (0 << STM_CRS_CR_SYNCWARNIE) | +		      (0 << STM_CRS_CR_SYNCOKIE)); + +	/* Configure for USB source */ +	stm_crs.cfgr = ((stm_crs.cfgr & ((1 << 30) | (1 << 27))) | +			(0 << STM_CRS_CFGR_SYNCPOL) | +			(STM_CRS_CFGR_SYNCSRC_USB << STM_CRS_CFGR_SYNCSRC) | +			(STM_CRS_CFGR_SYNCDIV_1 << STM_CRS_CFGR_SYNCDIV) | +			(0x22 << STM_CRS_CFGR_FELIM) | +			(((48000000 / 1000) - 1) << STM_CRS_CFGR_RELOAD)); + +	/* Enable error counter, set auto trim */ +	stm_crs.cr = ((stm_crs.cr & (1 << 4)) | +		      (32 << STM_CRS_CR_TRIM) | +		      (0 << STM_CRS_CR_SWSYNC) | +		      (1 << STM_CRS_CR_AUTOTRIMEN) | +		      (1 << STM_CRS_CR_CEN) | +		      (0 << STM_CRS_CR_ESYNCIE) | +		      (0 << STM_CRS_CR_ERRIE) | +		      (0 << STM_CRS_CR_SYNCWARNIE) | +		      (0 << STM_CRS_CR_SYNCOKIE)); + +} + +void +ao_clock_init(void) +{ +	uint32_t	cfgr; + +	/* Switch to HSI while messing about */ +	stm_rcc.cr |= (1 << STM_RCC_CR_HSION); +	while (!(stm_rcc.cr & (1 << STM_RCC_CR_HSIRDY))) +		ao_arch_nop(); + +	stm_rcc.cfgr = (stm_rcc.cfgr & ~(STM_RCC_CFGR_SW_MASK << STM_RCC_CFGR_SW)) | +		(STM_RCC_CFGR_SW_HSI << STM_RCC_CFGR_SW); + +	/* wait for system to switch to HSI */ +	while ((stm_rcc.cfgr & (STM_RCC_CFGR_SWS_MASK << STM_RCC_CFGR_SWS)) != +	       (STM_RCC_CFGR_SWS_HSI << STM_RCC_CFGR_SWS)) +		ao_arch_nop(); + +	/* reset the clock config, leaving us running on the HSI */ +	stm_rcc.cfgr &= (uint32_t)0x0000000f; + +	/* reset PLLON, CSSON, HSEBYP, HSEON */ +	stm_rcc.cr &= 0x0000ffff; + +	/* Disable all interrupts */ +	stm_rcc.cir = 0; + +#if AO_HSE +#define STM_RCC_CFGR_SWS_TARGET_CLOCK		STM_RCC_CFGR_SWS_HSE +#define STM_RCC_CFGR_SW_TARGET_CLOCK		STM_RCC_CFGR_SW_HSE +#define STM_PLLSRC				AO_HSE +#define STM_RCC_CFGR_PLLSRC_TARGET_CLOCK	1 + +#if AO_HSE_BYPASS +	stm_rcc.cr |= (1 << STM_RCC_CR_HSEBYP); +#else +	stm_rcc.cr &= ~(1 << STM_RCC_CR_HSEBYP); +#endif +	/* Enable HSE clock */ +	stm_rcc.cr |= (1 << STM_RCC_CR_HSEON); +	while (!(stm_rcc.cr & (1 << STM_RCC_CR_HSERDY))) +		asm("nop"); +#endif + + +#if AO_HSI48 +#define STM_RCC_CFGR_SWS_TARGET_CLOCK		STM_RCC_CFGR_SWS_HSI48 +#define STM_RCC_CFGR_SW_TARGET_CLOCK		STM_RCC_CFGR_SW_HSI48 + +	/* Turn HSI48 clock on */ +	stm_rcc.cr2 |= (1 << STM_RCC_CR2_HSI48ON); + +	/* Wait for clock to stabilize */ +	while ((stm_rcc.cr2 & (1 << STM_RCC_CR2_HSI48RDY)) == 0) +		ao_arch_nop(); + +	ao_clock_enable_crs(); +#endif + +#ifndef STM_RCC_CFGR_SWS_TARGET_CLOCK +#define STM_HSI 				16000000 +#define STM_RCC_CFGR_SWS_TARGET_CLOCK		STM_RCC_CFGR_SWS_HSI +#define STM_RCC_CFGR_SW_TARGET_CLOCK		STM_RCC_CFGR_SW_HSI +#define STM_PLLSRC				STM_HSI +#define STM_RCC_CFGR_PLLSRC_TARGET_CLOCK	0 +#endif + +#ifdef STM_PLLSRC +#error No code for PLL initialization yet +#endif + +	/* Set flash latency to tolerate 48MHz SYSCLK  -> 1 wait state */ + +	/* Enable prefetch */ +	stm_flash.acr |= (1 << STM_FLASH_ACR_PRFTBE); + +	/* Enable 1 wait state so the CPU can run at 48MHz */ +	stm_flash.acr |= (STM_FLASH_ACR_LATENCY_1 << STM_FLASH_ACR_LATENCY); + +	/* Enable power interface clock */ +	stm_rcc.apb1enr |= (1 << STM_RCC_APB1ENR_PWREN); + +	/* HCLK to 48MHz -> AHB prescaler = /1 */ +	cfgr = stm_rcc.cfgr; +	cfgr &= ~(STM_RCC_CFGR_HPRE_MASK << STM_RCC_CFGR_HPRE); +	cfgr |= (AO_RCC_CFGR_HPRE_DIV << STM_RCC_CFGR_HPRE); +	stm_rcc.cfgr = cfgr; +	while ((stm_rcc.cfgr & (STM_RCC_CFGR_HPRE_MASK << STM_RCC_CFGR_HPRE)) != +	       (AO_RCC_CFGR_HPRE_DIV << STM_RCC_CFGR_HPRE)) +		ao_arch_nop(); + +	/* APB Prescaler = AO_APB_PRESCALER */ +	cfgr = stm_rcc.cfgr; +	cfgr &= ~(STM_RCC_CFGR_PPRE_MASK << STM_RCC_CFGR_PPRE); +	cfgr |= (AO_RCC_CFGR_PPRE_DIV << STM_RCC_CFGR_PPRE); +	stm_rcc.cfgr = cfgr; + +	/* Switch to the desired system clock */ + +	cfgr = stm_rcc.cfgr; +	cfgr &= ~(STM_RCC_CFGR_SW_MASK << STM_RCC_CFGR_SW); +	cfgr |= (STM_RCC_CFGR_SW_TARGET_CLOCK << STM_RCC_CFGR_SW); +	stm_rcc.cfgr = cfgr; +	for (;;) { +		uint32_t	c, part, mask, val; + +		c = stm_rcc.cfgr; +		mask = (STM_RCC_CFGR_SWS_MASK << STM_RCC_CFGR_SWS); +		val = (STM_RCC_CFGR_SWS_TARGET_CLOCK << STM_RCC_CFGR_SWS); +		part = c & mask; +		if (part == val) +			break; +	} + +	/* Clear reset flags */ +	stm_rcc.csr |= (1 << STM_RCC_CSR_RMVF); + +#if DEBUG_THE_CLOCK +	/* Output SYSCLK on PA8 for measurments */ + +	stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_GPIOAEN); + +	stm_afr_set(&stm_gpioa, 8, STM_AFR_AF0); +	stm_moder_set(&stm_gpioa, 8, STM_MODER_ALTERNATE); +	stm_ospeedr_set(&stm_gpioa, 8, STM_OSPEEDR_40MHz); + +	stm_rcc.cfgr |= (STM_RCC_CFGR_MCOPRE_DIV_1 << STM_RCC_CFGR_MCOPRE); +	stm_rcc.cfgr |= (STM_RCC_CFGR_MCOSEL_HSE << STM_RCC_CFGR_MCOSEL); +#endif +} diff --git a/src/stmf0/ao_usb_stm.c b/src/stmf0/ao_usb_stm.c new file mode 100644 index 00000000..b9d86368 --- /dev/null +++ b/src/stmf0/ao_usb_stm.c @@ -0,0 +1,1090 @@ +/* + * Copyright © 2012 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#include "ao.h" +#include "ao_usb.h" +#include "ao_product.h" + +#define USB_DEBUG 	0 +#define USB_DEBUG_DATA	0 +#define USB_ECHO	0 + +#ifndef USE_USB_STDIO +#define USE_USB_STDIO	1 +#endif + +#if USE_USB_STDIO +#define AO_USB_OUT_SLEEP_ADDR	(&ao_stdin_ready) +#else +#define AO_USB_OUT_SLEEP_ADDR	(&ao_usb_out_avail) +#endif + +#if USB_DEBUG +#define debug(format, args...)	printf(format, ## args); +#else +#define debug(format, args...) +#endif + +#if USB_DEBUG_DATA +#define debug_data(format, args...)	printf(format, ## args); +#else +#define debug_data(format, args...) +#endif + +struct ao_usb_setup { +	uint8_t		dir_type_recip; +	uint8_t		request; +	uint16_t	value; +	uint16_t	index; +	uint16_t	length; +} ao_usb_setup; + +static uint8_t 	ao_usb_ep0_state; + +/* Pending EP0 IN data */ +static const uint8_t	*ao_usb_ep0_in_data;	/* Remaining data */ +static uint8_t 		ao_usb_ep0_in_len;	/* Remaining amount */ + +/* Temp buffer for smaller EP0 in data */ +static uint8_t	ao_usb_ep0_in_buf[2]; + +/* Pending EP0 OUT data */ +static uint8_t *ao_usb_ep0_out_data; +static uint8_t 	ao_usb_ep0_out_len; + +/* + * Objects allocated in special USB memory + */ + +/* Buffer description tables */ +static union stm_usb_bdt	*ao_usb_bdt; +/* USB address of end of allocated storage */ +static uint16_t	ao_usb_sram_addr; + +/* Pointer to ep0 tx/rx buffers in USB memory */ +static uint16_t	*ao_usb_ep0_tx_buffer; +static uint16_t	*ao_usb_ep0_rx_buffer; + +/* Pointer to bulk data tx/rx buffers in USB memory */ +static uint16_t	*ao_usb_in_tx_buffer; +static uint16_t	*ao_usb_out_rx_buffer; + +/* System ram shadow of USB buffer; writing individual bytes is + * too much of a pain (sigh) */ +static uint8_t	ao_usb_tx_buffer[AO_USB_IN_SIZE]; +static uint8_t	ao_usb_tx_count; + +static uint8_t	ao_usb_rx_buffer[AO_USB_OUT_SIZE]; +static uint8_t	ao_usb_rx_count, ao_usb_rx_pos; + +/* + * End point register indices + */ + +#define AO_USB_CONTROL_EPR	0 +#define AO_USB_INT_EPR		1 +#define AO_USB_OUT_EPR		2 +#define AO_USB_IN_EPR		3 + +/* Marks when we don't need to send an IN packet. + * This happens only when the last IN packet is not full, + * otherwise the host will expect to keep seeing packets. + * Send a zero-length packet as required + */ +static uint8_t	ao_usb_in_flushed; + +/* Marks when we have delivered an IN packet to the hardware + * and it has not been received yet. ao_sleep on this address + * to wait for it to be delivered. + */ +static uint8_t	ao_usb_in_pending; + +/* Marks when an OUT packet has been received by the hardware + * but not pulled to the shadow buffer. + */ +static uint8_t	ao_usb_out_avail; +uint8_t		ao_usb_running; +static uint8_t	ao_usb_configuration; + +#define AO_USB_EP0_GOT_RESET	1 +#define AO_USB_EP0_GOT_SETUP	2 +#define AO_USB_EP0_GOT_RX_DATA	4 +#define AO_USB_EP0_GOT_TX_ACK	8 + +static uint8_t	ao_usb_ep0_receive; +static uint8_t	ao_usb_address; +static uint8_t	ao_usb_address_pending; + +static inline uint32_t set_toggle(uint32_t 	current_value, +				   uint32_t	mask, +				   uint32_t	desired_value) +{ +	return (current_value ^ desired_value) & mask; +} + +static inline uint16_t *ao_usb_packet_buffer_addr(uint16_t sram_addr) +{ +	return (uint16_t *) (stm_usb_sram + sram_addr); +} + +static inline uint32_t ao_usb_epr_stat_rx(uint32_t epr) { +	return (epr >> STM_USB_EPR_STAT_RX) & STM_USB_EPR_STAT_RX_MASK; +} + +static inline uint32_t ao_usb_epr_stat_tx(uint32_t epr) { +	return (epr >> STM_USB_EPR_STAT_TX) & STM_USB_EPR_STAT_TX_MASK; +} + +static inline uint32_t ao_usb_epr_ctr_rx(uint32_t epr) { +	return (epr >> STM_USB_EPR_CTR_RX) & 1; +} + +static inline uint32_t ao_usb_epr_ctr_tx(uint32_t epr) { +	return (epr >> STM_USB_EPR_CTR_TX) & 1; +} + +static inline uint32_t ao_usb_epr_setup(uint32_t epr) { +	return (epr >> STM_USB_EPR_SETUP) & 1; +} + +static inline uint32_t ao_usb_epr_dtog_rx(uint32_t epr) { +	return (epr >> STM_USB_EPR_DTOG_RX) & 1; +} + +static inline uint32_t ao_usb_epr_dtog_tx(uint32_t epr) { +	return (epr >> STM_USB_EPR_DTOG_TX) & 1; +} + +/* + * Set current device address and mark the + * interface as active + */ +void +ao_usb_set_address(uint8_t address) +{ +	debug("ao_usb_set_address %02x\n", address); +	stm_usb.daddr = (1 << STM_USB_DADDR_EF) | address; +	ao_usb_address_pending = 0; +} + +/* + * Write these values to preserve register contents under HW changes + */ + +#define STM_USB_EPR_INVARIANT	((1 << STM_USB_EPR_CTR_RX) |		\ +				 (STM_USB_EPR_DTOG_RX_WRITE_INVARIANT << STM_USB_EPR_DTOG_RX) | \ +				 (STM_USB_EPR_STAT_RX_WRITE_INVARIANT << STM_USB_EPR_STAT_RX) | \ +				 (1 << STM_USB_EPR_CTR_TX) |		\ +				 (STM_USB_EPR_DTOG_TX_WRITE_INVARIANT << STM_USB_EPR_DTOG_TX) |	\ +				 (STM_USB_EPR_STAT_TX_WRITE_INVARIANT << STM_USB_EPR_STAT_TX)) + +#define STM_USB_EPR_INVARIANT_MASK	((1 << STM_USB_EPR_CTR_RX) |	\ +					 (STM_USB_EPR_DTOG_RX_MASK << STM_USB_EPR_DTOG_RX) | \ +					 (STM_USB_EPR_STAT_RX_MASK << STM_USB_EPR_STAT_RX) | \ +					 (1 << STM_USB_EPR_CTR_TX) |	\ +					 (STM_USB_EPR_DTOG_TX_MASK << STM_USB_EPR_DTOG_TX) | \ +					 (STM_USB_EPR_STAT_TX_MASK << STM_USB_EPR_STAT_TX)) + +/* + * These bits are purely under sw control, so preserve them in the + * register by re-writing what was read + */ +#define STM_USB_EPR_PRESERVE_MASK	((STM_USB_EPR_EP_TYPE_MASK << STM_USB_EPR_EP_TYPE) | \ +					 (1 << STM_USB_EPR_EP_KIND) |	\ +					 (STM_USB_EPR_EA_MASK << STM_USB_EPR_EA)) + +#define TX_DBG 0 +#define RX_DBG 0 + +#if TX_DBG +#define _tx_dbg0(msg) _dbg(__LINE__,msg,0) +#define _tx_dbg1(msg,value) _dbg(__LINE__,msg,value) +#else +#define _tx_dbg0(msg) +#define _tx_dbg1(msg,value) +#endif + +#if RX_DBG +#define _rx_dbg0(msg) _dbg(__LINE__,msg,0) +#define _rx_dbg1(msg,value) _dbg(__LINE__,msg,value) +#else +#define _rx_dbg0(msg) +#define _rx_dbg1(msg,value) +#endif + +#if TX_DBG || RX_DBG +static void _dbg(int line, char *msg, uint32_t value); +#endif + +/* + * Set the state of the specified endpoint register to a new + * value. This is tricky because the bits toggle where the new + * value is one, and we need to write invariant values in other + * spots of the register. This hardware is strange... + */ +static void +_ao_usb_set_stat_tx(int ep, uint32_t stat_tx) +{ +	uint16_t	epr_write, epr_old; + +	_tx_dbg1("set_stat_tx top", stat_tx); +	epr_old = epr_write = stm_usb.epr[ep].r; +	epr_write &= STM_USB_EPR_PRESERVE_MASK; +	epr_write |= STM_USB_EPR_INVARIANT; +	epr_write |= set_toggle(epr_old, +			      STM_USB_EPR_STAT_TX_MASK << STM_USB_EPR_STAT_TX, +			      stat_tx << STM_USB_EPR_STAT_TX); +	stm_usb.epr[ep].r = epr_write; +	_tx_dbg1("set_stat_tx bottom", epr_write); +} + +static void +ao_usb_set_stat_tx(int ep, uint32_t stat_tx) +{ +	ao_arch_block_interrupts(); +	_ao_usb_set_stat_tx(ep, stat_tx); +	ao_arch_release_interrupts(); +} + +static void +_ao_usb_set_stat_rx(int ep, uint32_t stat_rx) { +	uint16_t	epr_write, epr_old; + +	epr_write = epr_old = stm_usb.epr[ep].r; +	epr_write &= STM_USB_EPR_PRESERVE_MASK; +	epr_write |= STM_USB_EPR_INVARIANT; +	epr_write |= set_toggle(epr_old, +			      STM_USB_EPR_STAT_RX_MASK << STM_USB_EPR_STAT_RX, +			      stat_rx << STM_USB_EPR_STAT_RX); +	stm_usb.epr[ep].r = epr_write; +} + +static void +ao_usb_set_stat_rx(int ep, uint32_t stat_rx) { +	ao_arch_block_interrupts(); +	_ao_usb_set_stat_rx(ep, stat_rx); +	ao_arch_release_interrupts(); +} + +/* + * Set just endpoint 0, for use during startup + */ + +static void +ao_usb_init_ep(uint8_t ep, uint32_t addr, uint32_t type, uint32_t stat_rx, uint32_t stat_tx) +{ +	uint16_t		epr; + +	ao_arch_block_interrupts(); +	epr = stm_usb.epr[ep].r; +	epr = ((0 << STM_USB_EPR_CTR_RX) | +	       (epr & (1 << STM_USB_EPR_DTOG_RX)) | +	       set_toggle(epr, +			  (STM_USB_EPR_STAT_RX_MASK << STM_USB_EPR_STAT_RX), +			  (stat_rx << STM_USB_EPR_STAT_RX)) | +	       (type << STM_USB_EPR_EP_TYPE) | +	       (0 << STM_USB_EPR_EP_KIND) | +	       (0 << STM_USB_EPR_CTR_TX) | +	       (epr & (1 << STM_USB_EPR_DTOG_TX)) | +	       set_toggle(epr, +			  (STM_USB_EPR_STAT_TX_MASK << STM_USB_EPR_STAT_TX), +			  (stat_tx << STM_USB_EPR_STAT_TX)) | +	       (addr << STM_USB_EPR_EA)); +	stm_usb.epr[ep].r = epr; +	ao_arch_release_interrupts(); +	debug ("writing epr[%d] 0x%04x wrote 0x%04x\n", +	       ep, epr, stm_usb.epr[ep].r); +} + +static void +ao_usb_init_btable(void) +{ +	ao_usb_sram_addr = 0; + +	ao_usb_bdt = (void *) stm_usb_sram; + +	ao_usb_sram_addr += 8 * STM_USB_BDT_SIZE; + +	/* Set up EP 0 - a Control end point with 32 bytes of in and out buffers */ + +	ao_usb_bdt[0].single.addr_tx = ao_usb_sram_addr; +	ao_usb_bdt[0].single.count_tx = 0; +	ao_usb_ep0_tx_buffer = ao_usb_packet_buffer_addr(ao_usb_sram_addr); +	ao_usb_sram_addr += AO_USB_CONTROL_SIZE; + +	ao_usb_bdt[0].single.addr_rx = ao_usb_sram_addr; +	ao_usb_bdt[0].single.count_rx = ((1 << STM_USB_BDT_COUNT_RX_BL_SIZE) | +				  (((AO_USB_CONTROL_SIZE / 32) - 1) << STM_USB_BDT_COUNT_RX_NUM_BLOCK)); +	ao_usb_ep0_rx_buffer = ao_usb_packet_buffer_addr(ao_usb_sram_addr); +	ao_usb_sram_addr += AO_USB_CONTROL_SIZE; + +} + +static void +ao_usb_set_ep0(void) +{ +	int			e; + +	ao_usb_init_btable(); + +	/* buffer table is at the start of USB memory */ +	stm_usb.btable = 0; + +	ao_usb_init_ep(AO_USB_CONTROL_EPR, AO_USB_CONTROL_EP, +		       STM_USB_EPR_EP_TYPE_CONTROL, +		       STM_USB_EPR_STAT_RX_VALID, +		       STM_USB_EPR_STAT_TX_NAK); + +	/* Clear all of the other endpoints */ +	for (e = 1; e < 8; e++) { +		ao_usb_init_ep(e, 0, +			       STM_USB_EPR_EP_TYPE_CONTROL, +			       STM_USB_EPR_STAT_RX_DISABLED, +			       STM_USB_EPR_STAT_TX_DISABLED); +	} + +	ao_usb_set_address(0); +} + +static void +ao_usb_set_configuration(void) +{ +	debug ("ao_usb_set_configuration\n"); + +	/* Set up the INT end point */ +	ao_usb_bdt[AO_USB_INT_EPR].single.addr_tx = ao_usb_sram_addr; +	ao_usb_bdt[AO_USB_INT_EPR].single.count_tx = 0; +	ao_usb_in_tx_buffer = ao_usb_packet_buffer_addr(ao_usb_sram_addr); +	ao_usb_sram_addr += AO_USB_INT_SIZE; + +	ao_usb_init_ep(AO_USB_INT_EPR, +		       AO_USB_INT_EP, +		       STM_USB_EPR_EP_TYPE_INTERRUPT, +		       STM_USB_EPR_STAT_RX_DISABLED, +		       STM_USB_EPR_STAT_TX_NAK); + +	/* Set up the OUT end point */ +	ao_usb_bdt[AO_USB_OUT_EPR].single.addr_rx = ao_usb_sram_addr; +	ao_usb_bdt[AO_USB_OUT_EPR].single.count_rx = ((1 << STM_USB_BDT_COUNT_RX_BL_SIZE) | +						      (((AO_USB_OUT_SIZE / 32) - 1) << STM_USB_BDT_COUNT_RX_NUM_BLOCK)); +	ao_usb_out_rx_buffer = ao_usb_packet_buffer_addr(ao_usb_sram_addr); +	ao_usb_sram_addr += AO_USB_OUT_SIZE; + +	ao_usb_init_ep(AO_USB_OUT_EPR, +		       AO_USB_OUT_EP, +		       STM_USB_EPR_EP_TYPE_BULK, +		       STM_USB_EPR_STAT_RX_VALID, +		       STM_USB_EPR_STAT_TX_DISABLED); + +	/* Set up the IN end point */ +	ao_usb_bdt[AO_USB_IN_EPR].single.addr_tx = ao_usb_sram_addr; +	ao_usb_bdt[AO_USB_IN_EPR].single.count_tx = 0; +	ao_usb_in_tx_buffer = ao_usb_packet_buffer_addr(ao_usb_sram_addr); +	ao_usb_sram_addr += AO_USB_IN_SIZE; + +	ao_usb_init_ep(AO_USB_IN_EPR, +		       AO_USB_IN_EP, +		       STM_USB_EPR_EP_TYPE_BULK, +		       STM_USB_EPR_STAT_RX_DISABLED, +		       STM_USB_EPR_STAT_TX_NAK); + +	ao_usb_running = 1; +} + +static uint16_t	control_count; +static uint16_t int_count; +static uint16_t	in_count; +static uint16_t	out_count; +static uint16_t	reset_count; + +/* The USB memory must be accessed in 16-bit units + */ + +static void +ao_usb_write(const uint8_t *src, uint16_t *base, uint16_t bytes) +{ +	while (bytes >= 2) { +		*base++ = src[0] | (src[1] << 8); +		src += 2; +		bytes -= 2; +	} +	if (bytes) +		*base = *src; +} + +static void +ao_usb_read(uint8_t *dst, uint16_t *base, uint16_t bytes) +{ +	while (bytes >= 2) { +		uint16_t s = *base++; +		dst[0] = s; +		dst[1] = s >> 8; +		dst += 2; +		bytes -= 2; +	} +	if (bytes) +		*dst = *base; +} + +/* Send an IN data packet */ +static void +ao_usb_ep0_flush(void) +{ +	uint8_t this_len; + +	/* Check to see if the endpoint is still busy */ +	if (ao_usb_epr_stat_tx(stm_usb.epr[0].r) == STM_USB_EPR_STAT_TX_VALID) { +		debug("EP0 not accepting IN data\n"); +		return; +	} + +	this_len = ao_usb_ep0_in_len; +	if (this_len > AO_USB_CONTROL_SIZE) +		this_len = AO_USB_CONTROL_SIZE; + +	if (this_len < AO_USB_CONTROL_SIZE) +		ao_usb_ep0_state = AO_USB_EP0_IDLE; + +	ao_usb_ep0_in_len -= this_len; + +	debug_data ("Flush EP0 len %d:", this_len); +	ao_usb_write(ao_usb_ep0_in_data, ao_usb_ep0_tx_buffer, this_len); +	debug_data ("\n"); +	ao_usb_ep0_in_data += this_len; + +	/* Mark the endpoint as TX valid to send the packet */ +	ao_usb_bdt[AO_USB_CONTROL_EPR].single.count_tx = this_len; +	ao_usb_set_stat_tx(AO_USB_CONTROL_EPR, STM_USB_EPR_STAT_TX_VALID); +	debug ("queue tx. epr 0 now %08x\n", stm_usb.epr[AO_USB_CONTROL_EPR]); +} + +/* Read data from the ep0 OUT fifo */ +static void +ao_usb_ep0_fill(void) +{ +	uint16_t	len = ao_usb_bdt[0].single.count_rx & STM_USB_BDT_COUNT_RX_COUNT_RX_MASK; + +	if (len > ao_usb_ep0_out_len) +		len = ao_usb_ep0_out_len; +	ao_usb_ep0_out_len -= len; + +	/* Pull all of the data out of the packet */ +	debug_data ("Fill EP0 len %d:", len); +	ao_usb_read(ao_usb_ep0_out_data, ao_usb_ep0_rx_buffer, len); +	debug_data ("\n"); +	ao_usb_ep0_out_data += len; + +	/* ACK the packet */ +	ao_usb_set_stat_rx(0, STM_USB_EPR_STAT_RX_VALID); +} + +static void +ao_usb_ep0_in_reset(void) +{ +	ao_usb_ep0_in_data = ao_usb_ep0_in_buf; +	ao_usb_ep0_in_len = 0; +} + +static void +ao_usb_ep0_in_queue_byte(uint8_t a) +{ +	if (ao_usb_ep0_in_len < sizeof (ao_usb_ep0_in_buf)) +		ao_usb_ep0_in_buf[ao_usb_ep0_in_len++] = a; +} + +static void +ao_usb_ep0_in_set(const uint8_t *data, uint8_t len) +{ +	ao_usb_ep0_in_data = data; +	ao_usb_ep0_in_len = len; +} + +static void +ao_usb_ep0_out_set(uint8_t *data, uint8_t len) +{ +	ao_usb_ep0_out_data = data; +	ao_usb_ep0_out_len = len; +} + +static void +ao_usb_ep0_in_start(uint16_t max) +{ +	/* Don't send more than asked for */ +	if (ao_usb_ep0_in_len > max) +		ao_usb_ep0_in_len = max; +	ao_usb_ep0_flush(); +} + +static struct ao_usb_line_coding ao_usb_line_coding = {115200, 0, 0, 8}; + +/* Walk through the list of descriptors and find a match + */ +static void +ao_usb_get_descriptor(uint16_t value) +{ +	const uint8_t		*descriptor; +	uint8_t		type = value >> 8; +	uint8_t		index = value; + +	descriptor = ao_usb_descriptors; +	while (descriptor[0] != 0) { +		if (descriptor[1] == type && index-- == 0) { +			uint8_t	len; +			if (type == AO_USB_DESC_CONFIGURATION) +				len = descriptor[2]; +			else +				len = descriptor[0]; +			ao_usb_ep0_in_set(descriptor, len); +			break; +		} +		descriptor += descriptor[0]; +	} +} + +static void +ao_usb_ep0_setup(void) +{ +	/* Pull the setup packet out of the fifo */ +	ao_usb_ep0_out_set((uint8_t *) &ao_usb_setup, 8); +	ao_usb_ep0_fill(); +	if (ao_usb_ep0_out_len != 0) { +		debug ("invalid setup packet length\n"); +		return; +	} + +	if ((ao_usb_setup.dir_type_recip & AO_USB_DIR_IN) || ao_usb_setup.length == 0) +		ao_usb_ep0_state = AO_USB_EP0_DATA_IN; +	else +		ao_usb_ep0_state = AO_USB_EP0_DATA_OUT; + +	ao_usb_ep0_in_reset(); + +	switch(ao_usb_setup.dir_type_recip & AO_USB_SETUP_TYPE_MASK) { +	case AO_USB_TYPE_STANDARD: +		debug ("Standard setup packet\n"); +		switch(ao_usb_setup.dir_type_recip & AO_USB_SETUP_RECIP_MASK) { +		case AO_USB_RECIP_DEVICE: +			debug ("Device setup packet\n"); +			switch(ao_usb_setup.request) { +			case AO_USB_REQ_GET_STATUS: +				debug ("get status\n"); +				ao_usb_ep0_in_queue_byte(0); +				ao_usb_ep0_in_queue_byte(0); +				break; +			case AO_USB_REQ_SET_ADDRESS: +				debug ("set address %d\n", ao_usb_setup.value); +				ao_usb_address = ao_usb_setup.value; +				ao_usb_address_pending = 1; +				break; +			case AO_USB_REQ_GET_DESCRIPTOR: +				debug ("get descriptor %d\n", ao_usb_setup.value); +				ao_usb_get_descriptor(ao_usb_setup.value); +				break; +			case AO_USB_REQ_GET_CONFIGURATION: +				debug ("get configuration %d\n", ao_usb_configuration); +				ao_usb_ep0_in_queue_byte(ao_usb_configuration); +				break; +			case AO_USB_REQ_SET_CONFIGURATION: +				ao_usb_configuration = ao_usb_setup.value; +				debug ("set configuration %d\n", ao_usb_configuration); +				ao_usb_set_configuration(); +				break; +			} +			break; +		case AO_USB_RECIP_INTERFACE: +			debug ("Interface setup packet\n"); +			switch(ao_usb_setup.request) { +			case AO_USB_REQ_GET_STATUS: +				ao_usb_ep0_in_queue_byte(0); +				ao_usb_ep0_in_queue_byte(0); +				break; +			case AO_USB_REQ_GET_INTERFACE: +				ao_usb_ep0_in_queue_byte(0); +				break; +			case AO_USB_REQ_SET_INTERFACE: +				break; +			} +			break; +		case AO_USB_RECIP_ENDPOINT: +			debug ("Endpoint setup packet\n"); +			switch(ao_usb_setup.request) { +			case AO_USB_REQ_GET_STATUS: +				ao_usb_ep0_in_queue_byte(0); +				ao_usb_ep0_in_queue_byte(0); +				break; +			} +			break; +		} +		break; +	case AO_USB_TYPE_CLASS: +		debug ("Class setup packet\n"); +		switch (ao_usb_setup.request) { +		case AO_USB_SET_LINE_CODING: +			debug ("set line coding\n"); +			ao_usb_ep0_out_set((uint8_t *) &ao_usb_line_coding, 7); +			break; +		case AO_USB_GET_LINE_CODING: +			debug ("get line coding\n"); +			ao_usb_ep0_in_set((const uint8_t *) &ao_usb_line_coding, 7); +			break; +		case AO_USB_SET_CONTROL_LINE_STATE: +			break; +		} +		break; +	} + +	/* If we're not waiting to receive data from the host, +	 * queue an IN response +	 */ +	if (ao_usb_ep0_state == AO_USB_EP0_DATA_IN) +		ao_usb_ep0_in_start(ao_usb_setup.length); +} + +static void +ao_usb_ep0_handle(uint8_t receive) +{ +	ao_usb_ep0_receive = 0; +	if (receive & AO_USB_EP0_GOT_RESET) { +		debug ("\treset\n"); +		ao_usb_set_ep0(); +		return; +	} +	if (receive & AO_USB_EP0_GOT_SETUP) { +		debug ("\tsetup\n"); +		ao_usb_ep0_setup(); +	} +	if (receive & AO_USB_EP0_GOT_RX_DATA) { +		debug ("\tgot rx data\n"); +		if (ao_usb_ep0_state == AO_USB_EP0_DATA_OUT) { +			ao_usb_ep0_fill(); +			if (ao_usb_ep0_out_len == 0) { +				ao_usb_ep0_state = AO_USB_EP0_DATA_IN; +				ao_usb_ep0_in_start(0); +			} +		} +	} +	if (receive & AO_USB_EP0_GOT_TX_ACK) { +		debug ("\tgot tx ack\n"); + +#if HAS_FLIGHT && AO_USB_FORCE_IDLE +		ao_flight_force_idle = 1; +#endif +		/* Wait until the IN packet is received from addr 0 +		 * before assigning our local address +		 */ +		if (ao_usb_address_pending) +			ao_usb_set_address(ao_usb_address); +		if (ao_usb_ep0_state == AO_USB_EP0_DATA_IN) +			ao_usb_ep0_flush(); +	} +} + +void +stm_usb_isr(void) +{ +	uint32_t	istr = stm_usb.istr; + +	stm_usb.istr = ~istr; +	if (istr & (1 << STM_USB_ISTR_CTR)) { +		uint8_t		ep = istr & STM_USB_ISTR_EP_ID_MASK; +		uint16_t	epr, epr_write; + +		/* Preserve the SW write bits, don't mess with most HW writable bits, +		 * clear the CTR_RX and CTR_TX bits +		 */ +		epr = stm_usb.epr[ep].r; +		epr_write = epr; +		epr_write &= STM_USB_EPR_PRESERVE_MASK; +		epr_write |= STM_USB_EPR_INVARIANT; +		epr_write &= ~(1 << STM_USB_EPR_CTR_RX); +		epr_write &= ~(1 << STM_USB_EPR_CTR_TX); +		stm_usb.epr[ep].r = epr_write; + +		switch (ep) { +		case 0: +			++control_count; +			if (ao_usb_epr_ctr_rx(epr)) { +				if (ao_usb_epr_setup(epr)) +					ao_usb_ep0_receive |= AO_USB_EP0_GOT_SETUP; +				else +					ao_usb_ep0_receive |= AO_USB_EP0_GOT_RX_DATA; +			} +			if (ao_usb_epr_ctr_tx(epr)) +				ao_usb_ep0_receive |= AO_USB_EP0_GOT_TX_ACK; +			ao_usb_ep0_handle(ao_usb_ep0_receive); +			break; +		case AO_USB_OUT_EPR: +			++out_count; +			if (ao_usb_epr_ctr_rx(epr)) { +				_rx_dbg1("RX ISR", epr); +				ao_usb_out_avail = 1; +				_rx_dbg0("out avail set"); +				ao_wakeup(AO_USB_OUT_SLEEP_ADDR); +				_rx_dbg0("stdin awoken"); +			} +			break; +		case AO_USB_IN_EPR: +			++in_count; +			_tx_dbg1("TX ISR", epr); +			if (ao_usb_epr_ctr_tx(epr)) { +				ao_usb_in_pending = 0; +				ao_wakeup(&ao_usb_in_pending); +			} +			break; +		case AO_USB_INT_EPR: +			++int_count; +			if (ao_usb_epr_ctr_tx(epr)) +				_ao_usb_set_stat_tx(AO_USB_INT_EPR, STM_USB_EPR_STAT_TX_NAK); +			break; +		} +		return; +	} + +	if (istr & (1 << STM_USB_ISTR_RESET)) { +		++reset_count; +		ao_usb_ep0_receive |= AO_USB_EP0_GOT_RESET; +		ao_usb_ep0_handle(ao_usb_ep0_receive); +	} + +} + +/* Queue the current IN buffer for transmission */ +static void +_ao_usb_in_send(void) +{ +	_tx_dbg0("in_send start"); +	debug ("send %d\n", ao_usb_tx_count); +	while (ao_usb_in_pending) +		ao_sleep(&ao_usb_in_pending); +	ao_usb_in_pending = 1; +	if (ao_usb_tx_count != AO_USB_IN_SIZE) +		ao_usb_in_flushed = 1; +	ao_usb_write(ao_usb_tx_buffer, ao_usb_in_tx_buffer, ao_usb_tx_count); +	ao_usb_bdt[AO_USB_IN_EPR].single.count_tx = ao_usb_tx_count; +	ao_usb_tx_count = 0; +	_ao_usb_set_stat_tx(AO_USB_IN_EPR, STM_USB_EPR_STAT_TX_VALID); +	_tx_dbg0("in_send end"); +} + +/* Wait for a free IN buffer. Interrupts are blocked */ +static void +_ao_usb_in_wait(void) +{ +	for (;;) { +		/* Check if the current buffer is writable */ +		if (ao_usb_tx_count < AO_USB_IN_SIZE) +			break; + +		_tx_dbg0("in_wait top"); +		/* Wait for an IN buffer to be ready */ +		while (ao_usb_in_pending) +			ao_sleep(&ao_usb_in_pending); +		_tx_dbg0("in_wait bottom"); +	} +} + +void +ao_usb_flush(void) +{ +	if (!ao_usb_running) +		return; + +	/* Anytime we've sent a character since +	 * the last time we flushed, we'll need +	 * to send a packet -- the only other time +	 * we would send a packet is when that +	 * packet was full, in which case we now +	 * want to send an empty packet +	 */ +	ao_arch_block_interrupts(); +	while (!ao_usb_in_flushed) { +		_tx_dbg0("flush top"); +		_ao_usb_in_send(); +		_tx_dbg0("flush end"); +	} +	ao_arch_release_interrupts(); +} + +void +ao_usb_putchar(char c) +{ +	if (!ao_usb_running) +		return; + +	ao_arch_block_interrupts(); +	_ao_usb_in_wait(); + +	ao_usb_in_flushed = 0; +	ao_usb_tx_buffer[ao_usb_tx_count++] = (uint8_t) c; + +	/* Send the packet when full */ +	if (ao_usb_tx_count == AO_USB_IN_SIZE) { +		_tx_dbg0("putchar full"); +		_ao_usb_in_send(); +		_tx_dbg0("putchar flushed"); +	} +	ao_arch_release_interrupts(); +} + +static void +_ao_usb_out_recv(void) +{ +	_rx_dbg0("out_recv top"); +	ao_usb_out_avail = 0; + +	ao_usb_rx_count = ao_usb_bdt[AO_USB_OUT_EPR].single.count_rx & STM_USB_BDT_COUNT_RX_COUNT_RX_MASK; + +	_rx_dbg1("out_recv count", ao_usb_rx_count); +	debug ("recv %d\n", ao_usb_rx_count); +	debug_data("Fill OUT len %d:", ao_usb_rx_count); +	ao_usb_read(ao_usb_rx_buffer, ao_usb_out_rx_buffer, ao_usb_rx_count); +	debug_data("\n"); +	ao_usb_rx_pos = 0; + +	/* ACK the packet */ +	_ao_usb_set_stat_rx(AO_USB_OUT_EPR, STM_USB_EPR_STAT_RX_VALID); +} + +int +_ao_usb_pollchar(void) +{ +	uint8_t c; + +	if (!ao_usb_running) +		return AO_READ_AGAIN; + +	for (;;) { +		if (ao_usb_rx_pos != ao_usb_rx_count) +			break; + +		_rx_dbg0("poll check"); +		/* Check to see if a packet has arrived */ +		if (!ao_usb_out_avail) { +			_rx_dbg0("poll none"); +			return AO_READ_AGAIN; +		} +		_ao_usb_out_recv(); +	} + +	/* Pull a character out of the fifo */ +	c = ao_usb_rx_buffer[ao_usb_rx_pos++]; +	return c; +} + +char +ao_usb_getchar(void) +{ +	int	c; + +	ao_arch_block_interrupts(); +	while ((c = _ao_usb_pollchar()) == AO_READ_AGAIN) +		ao_sleep(AO_USB_OUT_SLEEP_ADDR); +	ao_arch_release_interrupts(); +	return c; +} + +void +ao_usb_disable(void) +{ +	ao_arch_block_interrupts(); +	stm_usb.cntr = (1 << STM_USB_CNTR_FRES); +	stm_usb.istr = 0; + +	/* Disable USB pull-up */ +	stm_usb.bcdr &= ~(1 << STM_USB_BCDR_DPPU); + +	/* Switch off the device */ +	stm_usb.cntr = (1 << STM_USB_CNTR_PDWN) | (1 << STM_USB_CNTR_FRES); + +	/* Disable the interface */ +	stm_rcc.apb1enr &= ~(1 << STM_RCC_APB1ENR_USBEN); +	ao_arch_release_interrupts(); +} + +void +ao_usb_enable(void) +{ +	int	t; + +	/* Select HSI48 as USB clock source */ +	stm_rcc.cfgr3 &= ~(1 << STM_RCC_CFGR3_USBSW); + +	/* Enable USB device */ +	stm_rcc.apb1enr |= (1 << STM_RCC_APB1ENR_USBEN); + +	/* Clear reset condition */ +	stm_rcc.apb1rstr &= ~(1 << STM_RCC_APB1RSTR_USBRST); + +	/* Disable USB pull-up */ +	stm_usb.bcdr &= ~(1 << STM_USB_BCDR_DPPU); + +	/* Do not touch the GPIOA configuration; USB takes priority +	 * over GPIO on pins A11 and A12, but if you select alternate +	 * input 10 (the documented correct selection), then USB is +	 * pulled low and doesn't work at all +	 */ + +	ao_arch_block_interrupts(); + +	/* Route interrupts */ +	stm_nvic_set_enable(STM_ISR_USB_POS); +	stm_nvic_set_priority(STM_ISR_USB_POS, 3); + +	ao_usb_configuration = 0; + +	/* Set up buffer descriptors */ +	ao_usb_init_btable(); + +	/* Reset the USB controller */ +	stm_usb.cntr = (1 << STM_USB_CNTR_FRES); + +	/* Clear the reset bit */ +	stm_usb.cntr = 0; + +	/* Clear any spurious interrupts */ +	stm_usb.istr = 0; + +	ao_usb_set_ep0(); + +	debug ("ao_usb_enable\n"); + +	/* Enable interrupts */ +	stm_usb.cntr = ((1 << STM_USB_CNTR_CTRM) | +			(0 << STM_USB_CNTR_PMAOVRM) | +			(0 << STM_USB_CNTR_ERRM) | +			(0 << STM_USB_CNTR_WKUPM) | +			(0 << STM_USB_CNTR_SUSPM) | +			(1 << STM_USB_CNTR_RESETM) | +			(0 << STM_USB_CNTR_SOFM) | +			(0 << STM_USB_CNTR_ESOFM) | +			(0 << STM_USB_CNTR_RESUME) | +			(0 << STM_USB_CNTR_FSUSP) | +			(0 << STM_USB_CNTR_LP_MODE) | +			(0 << STM_USB_CNTR_PDWN) | +			(0 << STM_USB_CNTR_FRES)); + +	ao_arch_release_interrupts(); + +	for (t = 0; t < 1000; t++) +		ao_arch_nop(); + +	/* Enable USB pull-up */ +	stm_usb.bcdr |= (1 << STM_USB_BCDR_DPPU); +} + +#if USB_ECHO +struct ao_task ao_usb_echo_task; + +static void +ao_usb_echo(void) +{ +	char	c; + +	for (;;) { +		c = ao_usb_getchar(); +		ao_usb_putchar(c); +		ao_usb_flush(); +	} +} +#endif + +#if USB_DEBUG +static void +ao_usb_irq(void) +{ +	printf ("control: %d out: %d in: %d int: %d reset: %d\n", +		control_count, out_count, in_count, int_count, reset_count); +} + +__code struct ao_cmds ao_usb_cmds[] = { +	{ ao_usb_irq, "I\0Show USB interrupt counts" }, +	{ 0, NULL } +}; +#endif + +void +ao_usb_init(void) +{ +	ao_usb_enable(); + +	debug ("ao_usb_init\n"); +	ao_usb_ep0_state = AO_USB_EP0_IDLE; +#if USB_ECHO +	ao_add_task(&ao_usb_echo_task, ao_usb_echo, "usb echo"); +#endif +#if USB_DEBUG +	ao_cmd_register(&ao_usb_cmds[0]); +#endif +#if !USB_ECHO +#if USE_USB_STDIO +	ao_add_stdio(_ao_usb_pollchar, ao_usb_putchar, ao_usb_flush); +#endif +#endif +} + +#if TX_DBG || RX_DBG + +struct ao_usb_dbg { +	int		line; +	char		*msg; +	uint32_t	value; +	uint32_t	primask; +#if TX_DBG +	uint16_t	in_count; +	uint32_t	in_epr; +	uint32_t	in_pending; +	uint32_t	tx_count; +	uint32_t	in_flushed; +#endif +#if RX_DBG +	uint8_t		rx_count; +	uint8_t		rx_pos; +	uint8_t		out_avail; +	uint32_t	out_epr; +#endif +}; + +#define NUM_USB_DBG	128 + +static struct ao_usb_dbg dbg[128]; +static int dbg_i; + +static void _dbg(int line, char *msg, uint32_t value) +{ +	uint32_t	primask; +	dbg[dbg_i].line = line; +	dbg[dbg_i].msg = msg; +	dbg[dbg_i].value = value; +	asm("mrs %0,primask" : "=&r" (primask)); +	dbg[dbg_i].primask = primask; +#if TX_DBG +	dbg[dbg_i].in_count = in_count; +	dbg[dbg_i].in_epr = stm_usb.epr[AO_USB_IN_EPR]; +	dbg[dbg_i].in_pending = ao_usb_in_pending; +	dbg[dbg_i].tx_count = ao_usb_tx_count; +	dbg[dbg_i].in_flushed = ao_usb_in_flushed; +#endif +#if RX_DBG +	dbg[dbg_i].rx_count = ao_usb_rx_count; +	dbg[dbg_i].rx_pos = ao_usb_rx_pos; +	dbg[dbg_i].out_avail = ao_usb_out_avail; +	dbg[dbg_i].out_epr = stm_usb.epr[AO_USB_OUT_EPR]; +#endif +	if (++dbg_i == NUM_USB_DBG) +		dbg_i = 0; +} +#endif diff --git a/src/stmf0/registers.ld b/src/stmf0/registers.ld new file mode 100644 index 00000000..5358f15a --- /dev/null +++ b/src/stmf0/registers.ld @@ -0,0 +1,60 @@ +stm_gpiof  = 0x48001400; +stm_gpioc  = 0x48000800; +stm_gpiob  = 0x48000400; +stm_gpioa  = 0x48000000; + +stm_tsc    = 0x40024000; +stm_crc    = 0x40023000; +stm_flash  = 0x40022000; +stm_rcc    = 0x40021000; +stm_dma    = 0x40020000; +stm_dbgmcu = 0x40015800; +stm_tim17  = 0x40014800; +stm_tim16  = 0x40014400; +stm_usart1 = 0x40013800; +stm_spi1   = 0x40013000; +stm_tim1   = 0x40012c00; +stm_adc    = 0x40012400; + +stm_exti   = 0x40010400; +stm_syscfg = 0x40010000; + +stm_cec    = 0x40007800; + +stm_pwr    = 0x40007000; +stm_crs    = 0x40006c00; + +stm_bxcan  = 0x40006400; +stm_usb_sram = 0x40006000; +stm_usb    = 0x40005c00; + +stm_i2c1   = 0x40005400; + +stm_usart2 = 0x40004400; + +stm_spi2   = 0x40003800;	/* docs are broken here */ + +stm_iwdg   = 0x40003000; +stm_wwdg   = 0x40002c00; +stm_rtc    = 0x40002800; + +stm_tim14  = 0x40002000; + +stm_tim3   = 0x40000400; +stm_tim2   = 0x40000000; + +stm_systick = 0xe000e010; + +stm_nvic   = 0xe000e100; + +stm_scb    = 0xe000ed00; + +stm_mpu    = 0xe000ed90; + +stm_dbg_mcu = 0xe0042000; + +/* calibration data in system memory */ +stm_temp_cal = 0x1ff80078; +stm_flash_size_medium = 0x1ff8004c; +stm_flash_size_large = 0x1ff800cc; +stm_device_id = 0x1ff80050; diff --git a/src/stmf0/stm32f0.h b/src/stmf0/stm32f0.h new file mode 100644 index 00000000..2adfeee0 --- /dev/null +++ b/src/stmf0/stm32f0.h @@ -0,0 +1,1995 @@ +/* + * Copyright © 2015 Keith Packard <keithp@keithp.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; version 2 of the License. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU + * General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA. + */ + +#ifndef _STM32F0_H_ +#define _STM32F0_H_ + +#include <stdint.h> + +typedef volatile uint32_t	vuint32_t; +typedef volatile void *		vvoid_t; +typedef volatile uint16_t	vuint16_t; + +struct stm_gpio { +	vuint32_t	moder; +	vuint32_t	otyper; +	vuint32_t	ospeedr; +	vuint32_t	pupdr; + +	vuint32_t	idr; +	vuint32_t	odr; +	vuint32_t	bsrr; +	vuint32_t	lckr; + +	vuint32_t	afrl; +	vuint32_t	afrh; +	vuint32_t	brr; +}; + +#define STM_MODER_SHIFT(pin)		((pin) << 1) +#define STM_MODER_MASK			3 +#define STM_MODER_INPUT			0 +#define STM_MODER_OUTPUT		1 +#define STM_MODER_ALTERNATE		2 +#define STM_MODER_ANALOG		3 + +static inline void +stm_moder_set(struct stm_gpio *gpio, int pin, vuint32_t value) { +	gpio->moder = ((gpio->moder & +			~(STM_MODER_MASK << STM_MODER_SHIFT(pin))) | +		       value << STM_MODER_SHIFT(pin)); +} + +static inline uint32_t +stm_moder_get(struct stm_gpio *gpio, int pin) { +	return (gpio->moder >> STM_MODER_SHIFT(pin)) & STM_MODER_MASK; +} + +#define STM_OTYPER_SHIFT(pin)		(pin) +#define STM_OTYPER_MASK			1 +#define STM_OTYPER_PUSH_PULL		0 +#define STM_OTYPER_OPEN_DRAIN		1 + +static inline void +stm_otyper_set(struct stm_gpio *gpio, int pin, vuint32_t value) { +	gpio->otyper = ((gpio->otyper & +			 ~(STM_OTYPER_MASK << STM_OTYPER_SHIFT(pin))) | +			value << STM_OTYPER_SHIFT(pin)); +} + +static inline uint32_t +stm_otyper_get(struct stm_gpio *gpio, int pin) { +	return (gpio->otyper >> STM_OTYPER_SHIFT(pin)) & STM_OTYPER_MASK; +} + +#define STM_OSPEEDR_SHIFT(pin)		((pin) << 1) +#define STM_OSPEEDR_MASK		3 +#define STM_OSPEEDR_LOW			0	/* 2MHz */ +#define STM_OSPEEDR_MEDIUM		1	/* 10MHz */ +#define STM_OSPEEDR_HIGH		3	/* 10-50MHz */ + +static inline void +stm_ospeedr_set(struct stm_gpio *gpio, int pin, vuint32_t value) { +	gpio->ospeedr = ((gpio->ospeedr & +			~(STM_OSPEEDR_MASK << STM_OSPEEDR_SHIFT(pin))) | +		       value << STM_OSPEEDR_SHIFT(pin)); +} + +static inline uint32_t +stm_ospeedr_get(struct stm_gpio *gpio, int pin) { +	return (gpio->ospeedr >> STM_OSPEEDR_SHIFT(pin)) & STM_OSPEEDR_MASK; +} + +#define STM_PUPDR_SHIFT(pin)		((pin) << 1) +#define STM_PUPDR_MASK			3 +#define STM_PUPDR_NONE			0 +#define STM_PUPDR_PULL_UP		1 +#define STM_PUPDR_PULL_DOWN		2 +#define STM_PUPDR_RESERVED		3 + +static inline void +stm_pupdr_set(struct stm_gpio *gpio, int pin, uint32_t value) { +	gpio->pupdr = ((gpio->pupdr & +			~(STM_PUPDR_MASK << STM_PUPDR_SHIFT(pin))) | +		       value << STM_PUPDR_SHIFT(pin)); +} + +static inline uint32_t +stm_pupdr_get(struct stm_gpio *gpio, int pin) { +	return (gpio->pupdr >> STM_PUPDR_SHIFT(pin)) & STM_PUPDR_MASK; +} + +#define STM_AFR_SHIFT(pin)		((pin) << 2) +#define STM_AFR_MASK			0xf +#define STM_AFR_NONE			0 +#define STM_AFR_AF0			0x0 +#define STM_AFR_AF1			0x1 +#define STM_AFR_AF2			0x2 +#define STM_AFR_AF3			0x3 +#define STM_AFR_AF4			0x4 +#define STM_AFR_AF5			0x5 +#define STM_AFR_AF6			0x6 +#define STM_AFR_AF7			0x7 + +static inline void +stm_afr_set(struct stm_gpio *gpio, int pin, uint32_t value) { +	/* +	 * Set alternate pin mode too +	 */ +	stm_moder_set(gpio, pin, STM_MODER_ALTERNATE); +	if (pin < 8) +		gpio->afrl = ((gpio->afrl & +			       ~(STM_AFR_MASK << STM_AFR_SHIFT(pin))) | +			      value << STM_AFR_SHIFT(pin)); +	else { +		pin -= 8; +		gpio->afrh = ((gpio->afrh & +			       ~(STM_AFR_MASK << STM_AFR_SHIFT(pin))) | +			      value << STM_AFR_SHIFT(pin)); +	} +} + +static inline uint32_t +stm_afr_get(struct stm_gpio *gpio, int pin) { +	if (pin < 8) +		return (gpio->afrl >> STM_AFR_SHIFT(pin)) & STM_AFR_MASK; +	else { +		pin -= 8; +		return (gpio->afrh >> STM_AFR_SHIFT(pin)) & STM_AFR_MASK; +	} +} + +static inline void +stm_gpio_set(struct stm_gpio *gpio, int pin, uint8_t value) { +	/* Use the bit set/reset register to do this atomically */ +	gpio->bsrr = ((uint32_t) (value ^ 1) << (pin + 16)) | ((uint32_t) value << pin); +} + +static inline uint8_t +stm_gpio_get(struct stm_gpio *gpio, int pin) { +	return (gpio->idr >> pin) & 1; +} + +static inline uint16_t +stm_gpio_get_all(struct stm_gpio *gpio) { +	return gpio->idr; +} + +/* + * We can't define these in registers.ld or our fancy + * ao_enable_gpio macro will expand into a huge pile of code + * as the compiler won't do correct constant folding and + * dead-code elimination + */ + +extern struct stm_gpio stm_gpioa; +extern struct stm_gpio stm_gpiob; +extern struct stm_gpio stm_gpioc; +extern struct stm_gpio stm_gpiof; + +#define stm_gpiof  (*((struct stm_gpio *) 0x48001400)) +#define stm_gpioc  (*((struct stm_gpio *) 0x48000800)) +#define stm_gpiob  (*((struct stm_gpio *) 0x48000400)) +#define stm_gpioa  (*((struct stm_gpio *) 0x48000000)) + +struct stm_usart { +	vuint32_t	cr1;	/* control register 1 */ +	vuint32_t	cr2;	/* control register 2 */ +	vuint32_t	cr3;	/* control register 3 */ +	vuint32_t	brr;	/* baud rate register */ + +	vuint32_t	gtpr;	/* guard time and prescaler */ +	vuint32_t	rtor;	/* */ +	vuint32_t	rqr;	/* */ +	vuint32_t	isr;	/* */ + +	vuint32_t	icr;	/* */ +	vuint32_t	rdr;	/* */ +	vuint32_t	tdr;	/* */ +}; + +extern struct stm_usart	stm_usart1; +extern struct stm_usart stm_usart2; + +#define STM_USART_SR_CTS	(9)	/* CTS flag */ +#define STM_USART_SR_LBD	(8)	/* LIN break detection flag */ +#define STM_USART_SR_TXE	(7)	/* Transmit data register empty */ +#define STM_USART_SR_TC		(6)	/* Transmission complete */ +#define STM_USART_SR_RXNE	(5)	/* Read data register not empty */ +#define STM_USART_SR_IDLE	(4)	/* IDLE line detected */ +#define STM_USART_SR_ORE	(3)	/* Overrun error */ +#define STM_USART_SR_NF		(2)	/* Noise detected flag */ +#define STM_USART_SR_FE		(1)	/* Framing error */ +#define STM_USART_SR_PE		(0)	/* Parity error */ + +#define STM_USART_CR1_OVER8	(15)	/* Oversampling mode */ +#define STM_USART_CR1_UE	(13)	/* USART enable */ +#define STM_USART_CR1_M		(12)	/* Word length */ +#define STM_USART_CR1_WAKE	(11)	/* Wakeup method */ +#define STM_USART_CR1_PCE	(10)	/* Parity control enable */ +#define STM_USART_CR1_PS	(9)	/* Parity selection */ +#define STM_USART_CR1_PEIE	(8)	/* PE interrupt enable */ +#define STM_USART_CR1_TXEIE	(7)	/* TXE interrupt enable */ +#define STM_USART_CR1_TCIE	(6)	/* Transmission complete interrupt enable */ +#define STM_USART_CR1_RXNEIE	(5)	/* RXNE interrupt enable */ +#define STM_USART_CR1_IDLEIE	(4)	/* IDLE interrupt enable */ +#define STM_USART_CR1_TE	(3)	/* Transmitter enable */ +#define STM_USART_CR1_RE	(2)	/* Receiver enable */ +#define STM_USART_CR1_RWU	(1)	/* Receiver wakeup */ +#define STM_USART_CR1_SBK	(0)	/* Send break */ + +#define STM_USART_CR2_LINEN	(14)	/* LIN mode enable */ +#define STM_USART_CR2_STOP	(12)	/* STOP bits */ +#define STM_USART_CR2_STOP_MASK	3 +#define STM_USART_CR2_STOP_1	0 +#define STM_USART_CR2_STOP_0_5	1 +#define STM_USART_CR2_STOP_2	2 +#define STM_USART_CR2_STOP_1_5	3 + +#define STM_USART_CR2_CLKEN	(11)	/* Clock enable */ +#define STM_USART_CR2_CPOL	(10)	/* Clock polarity */ +#define STM_USART_CR2_CPHA	(9)	/* Clock phase */ +#define STM_USART_CR2_LBCL	(8)	/* Last bit clock pulse */ +#define STM_USART_CR2_LBDIE	(6)	/* LIN break detection interrupt enable */ +#define STM_USART_CR2_LBDL	(5)	/* lin break detection length */ +#define STM_USART_CR2_ADD	(0) +#define STM_USART_CR2_ADD_MASK	0xf + +#define STM_USART_CR3_ONEBITE	(11)	/* One sample bit method enable */ +#define STM_USART_CR3_CTSIE	(10)	/* CTS interrupt enable */ +#define STM_USART_CR3_CTSE	(9)	/* CTS enable */ +#define STM_USART_CR3_RTSE	(8)	/* RTS enable */ +#define STM_USART_CR3_DMAT	(7)	/* DMA enable transmitter */ +#define STM_USART_CR3_DMAR	(6)	/* DMA enable receiver */ +#define STM_USART_CR3_SCEN	(5)	/* Smartcard mode enable */ +#define STM_USART_CR3_NACK	(4)	/* Smartcard NACK enable */ +#define STM_USART_CR3_HDSEL	(3)	/* Half-duplex selection */ +#define STM_USART_CR3_IRLP	(2)	/* IrDA low-power */ +#define STM_USART_CR3_IREN	(1)	/* IrDA mode enable */ +#define STM_USART_CR3_EIE	(0)	/* Error interrupt enable */ + +struct stm_tim { +}; + +extern struct stm_tim stm_tim9; + +struct stm_tim1011 { +	vuint32_t	cr1; +	uint32_t	unused_4; +	vuint32_t	smcr; +	vuint32_t	dier; +	vuint32_t	sr; +	vuint32_t	egr; +	vuint32_t	ccmr1; +	uint32_t	unused_1c; +	vuint32_t	ccer; +	vuint32_t	cnt; +	vuint32_t	psc; +	vuint32_t	arr; +	uint32_t	unused_30; +	vuint32_t	ccr1; +	uint32_t	unused_38; +	uint32_t	unused_3c; +	uint32_t	unused_40; +	uint32_t	unused_44; +	uint32_t	unused_48; +	uint32_t	unused_4c; +	vuint32_t	or; +}; + +extern struct stm_tim1011 stm_tim10; +extern struct stm_tim1011 stm_tim11; + +#define STM_TIM1011_CR1_CKD	8 +#define  STM_TIM1011_CR1_CKD_1		0 +#define  STM_TIM1011_CR1_CKD_2		1 +#define  STM_TIM1011_CR1_CKD_4		2 +#define  STM_TIM1011_CR1_CKD_MASK	3 +#define STM_TIM1011_CR1_ARPE	7 +#define STM_TIM1011_CR1_URS	2 +#define STM_TIM1011_CR1_UDIS	1 +#define STM_TIM1011_CR1_CEN	0 + +#define STM_TIM1011_SMCR_ETP	15 +#define STM_TIM1011_SMCR_ECE	14 +#define STM_TIM1011_SMCR_ETPS	12 +#define  STM_TIM1011_SMCR_ETPS_OFF	0 +#define  STM_TIM1011_SMCR_ETPS_2	1 +#define  STM_TIM1011_SMCR_ETPS_4	2 +#define  STM_TIM1011_SMCR_ETPS_8	3 +#define  STM_TIM1011_SMCR_ETPS_MASK	3 +#define STM_TIM1011_SMCR_ETF	8 +#define  STM_TIM1011_SMCR_ETF_NONE		0 +#define  STM_TIM1011_SMCR_ETF_CK_INT_2		1 +#define  STM_TIM1011_SMCR_ETF_CK_INT_4		2 +#define  STM_TIM1011_SMCR_ETF_CK_INT_8		3 +#define  STM_TIM1011_SMCR_ETF_DTS_2_6		4 +#define  STM_TIM1011_SMCR_ETF_DTS_2_8		5 +#define  STM_TIM1011_SMCR_ETF_DTS_4_6		6 +#define  STM_TIM1011_SMCR_ETF_DTS_4_8		7 +#define  STM_TIM1011_SMCR_ETF_DTS_8_6		8 +#define  STM_TIM1011_SMCR_ETF_DTS_8_8		9 +#define  STM_TIM1011_SMCR_ETF_DTS_16_5		10 +#define  STM_TIM1011_SMCR_ETF_DTS_16_6		11 +#define  STM_TIM1011_SMCR_ETF_DTS_16_8		12 +#define  STM_TIM1011_SMCR_ETF_DTS_32_5		13 +#define  STM_TIM1011_SMCR_ETF_DTS_32_6		14 +#define  STM_TIM1011_SMCR_ETF_DTS_32_8		15 +#define  STM_TIM1011_SMCR_ETF_MASK		15 + +#define STM_TIM1011_DIER_CC1E	1 +#define STM_TIM1011_DIER_UIE	0 + +#define STM_TIM1011_SR_CC1OF	9 +#define STM_TIM1011_SR_CC1IF	1 +#define STM_TIM1011_SR_UIF	0 + +#define STM_TIM1011_EGR_CC1G	1 +#define STM_TIM1011_EGR_UG	0 + +#define STM_TIM1011_CCMR1_OC1CE	7 +#define STM_TIM1011_CCMR1_OC1M	4 +#define  STM_TIM1011_CCMR1_OC1M_FROZEN			0 +#define  STM_TIM1011_CCMR1_OC1M_SET_1_ACTIVE_ON_MATCH	1 +#define  STM_TIM1011_CCMR1_OC1M_SET_1_INACTIVE_ON_MATCH	2 +#define  STM_TIM1011_CCMR1_OC1M_TOGGLE			3 +#define  STM_TIM1011_CCMR1_OC1M_FORCE_INACTIVE		4 +#define  STM_TIM1011_CCMR1_OC1M_FORCE_ACTIVE		5 +#define  STM_TIM1011_CCMR1_OC1M_PWM_MODE_1		6 +#define  STM_TIM1011_CCMR1_OC1M_PWM_MODE_2		7 +#define  STM_TIM1011_CCMR1_OC1M_MASK			7 +#define STM_TIM1011_CCMR1_OC1PE	3 +#define STM_TIM1011_CCMR1_OC1FE	2 +#define STM_TIM1011_CCMR1_CC1S	0 +#define  STM_TIM1011_CCMR1_CC1S_OUTPUT			0 +#define  STM_TIM1011_CCMR1_CC1S_INPUT_TI1		1 +#define  STM_TIM1011_CCMR1_CC1S_INPUT_TI2		2 +#define  STM_TIM1011_CCMR1_CC1S_INPUT_TRC		3 +#define  STM_TIM1011_CCMR1_CC1S_MASK			3 + +#define  STM_TIM1011_CCMR1_IC1F_NONE		0 +#define  STM_TIM1011_CCMR1_IC1F_CK_INT_2	1 +#define  STM_TIM1011_CCMR1_IC1F_CK_INT_4	2 +#define  STM_TIM1011_CCMR1_IC1F_CK_INT_8	3 +#define  STM_TIM1011_CCMR1_IC1F_DTS_2_6		4 +#define  STM_TIM1011_CCMR1_IC1F_DTS_2_8		5 +#define  STM_TIM1011_CCMR1_IC1F_DTS_4_6		6 +#define  STM_TIM1011_CCMR1_IC1F_DTS_4_8		7 +#define  STM_TIM1011_CCMR1_IC1F_DTS_8_6		8 +#define  STM_TIM1011_CCMR1_IC1F_DTS_8_8		9 +#define  STM_TIM1011_CCMR1_IC1F_DTS_16_5	10 +#define  STM_TIM1011_CCMR1_IC1F_DTS_16_6	11 +#define  STM_TIM1011_CCMR1_IC1F_DTS_16_8	12 +#define  STM_TIM1011_CCMR1_IC1F_DTS_32_5	13 +#define  STM_TIM1011_CCMR1_IC1F_DTS_32_6	14 +#define  STM_TIM1011_CCMR1_IC1F_DTS_32_8	15 +#define  STM_TIM1011_CCMR1_IC1F_MASK		15 +#define STM_TIM1011_CCMR1_IC1PSC	2 +#define  STM_TIM1011_CCMR1_IC1PSC_1		0 +#define  STM_TIM1011_CCMR1_IC1PSC_2		1 +#define  STM_TIM1011_CCMR1_IC1PSC_4		2 +#define  STM_TIM1011_CCMR1_IC1PSC_8		3 +#define  STM_TIM1011_CCMR1_IC1PSC_MASK		3 +#define STM_TIM1011_CCMR1_CC1S		0 + +#define STM_TIM1011_CCER_CC1NP		3 +#define STM_TIM1011_CCER_CC1P		1 +#define STM_TIM1011_CCER_CC1E		0 + +#define STM_TIM1011_OR_TI1_RMP_RI	3 +#define STM_TIM1011_ETR_RMP		2 +#define STM_TIM1011_TI1_RMP		0 +#define  STM_TIM1011_TI1_RMP_GPIO		0 +#define  STM_TIM1011_TI1_RMP_LSI		1 +#define  STM_TIM1011_TI1_RMP_LSE		2 +#define  STM_TIM1011_TI1_RMP_RTC		3 +#define  STM_TIM1011_TI1_RMP_MASK		3 + +/* Flash interface */ + +struct stm_flash { +	vuint32_t	acr; +	vuint32_t	keyr; +	vuint32_t	optkeyr; +	vuint32_t	sr; + +	vuint32_t	cr; +	vuint32_t	ar; +	vuint32_t	unused_0x18; +	vuint32_t	obr; + +	vuint32_t	wrpr; +}; + +extern struct stm_flash	stm_flash; + +#define STM_FLASH_ACR_PRFTBS	(5) +#define STM_FLASH_ACR_PRFTBE	(4) +#define STM_FLASH_ACR_LATENCY	(0) +#define  STM_FLASH_ACR_LATENCY_0		0 +#define  STM_FLASH_ACR_LATENCY_1		1 + +#define STM_FLASH_PECR_OBL_LAUNCH	18 +#define STM_FLASH_PECR_ERRIE		17 +#define STM_FLASH_PECR_EOPIE		16 +#define STM_FLASH_PECR_FPRG		10 +#define STM_FLASH_PECR_ERASE		9 +#define STM_FLASH_PECR_FTDW		8 +#define STM_FLASH_PECR_DATA		4 +#define STM_FLASH_PECR_PROG		3 +#define STM_FLASH_PECR_OPTLOCK		2 +#define STM_FLASH_PECR_PRGLOCK		1 +#define STM_FLASH_PECR_PELOCK		0 + +#define STM_FLASH_SR_OPTVERR		11 +#define STM_FLASH_SR_SIZERR		10 +#define STM_FLASH_SR_PGAERR		9 +#define STM_FLASH_SR_WRPERR		8 +#define STM_FLASH_SR_READY		3 +#define STM_FLASH_SR_ENDHV		2 +#define STM_FLASH_SR_EOP		1 +#define STM_FLASH_SR_BSY		0 + +#define STM_FLASH_PEKEYR_PEKEY1	0x89ABCDEF +#define STM_FLASH_PEKEYR_PEKEY2 0x02030405 + +#define STM_FLASH_PRGKEYR_PRGKEY1 0x8C9DAEBF +#define STM_FLASH_PRGKEYR_PRGKEY2 0x13141516 + +struct stm_rcc { +	vuint32_t	cr; +	vuint32_t	cfgr; +	vuint32_t	cir; +	vuint32_t	apb2rstr; + +	vuint32_t	apb1rstr; +	vuint32_t	ahbenr; +	vuint32_t	apb2enr; +	vuint32_t	apb1enr; + +	vuint32_t	bdcr; +	vuint32_t	csr; +	vuint32_t	ahbrstr; +	vuint32_t	cfgr2; + +	vuint32_t	cfgr3; +	vuint32_t	cr2; +}; + +extern struct stm_rcc stm_rcc; + +/* Nominal high speed internal oscillator frequency is 16MHz */ +#define STM_HSI_FREQ		16000000 + +#define STM_RCC_CR_PLLRDY	(25) +#define STM_RCC_CR_PLLON	(24) +#define STM_RCC_CR_CSSON	(19) +#define STM_RCC_CR_HSEBYP	(18) +#define STM_RCC_CR_HSERDY	(17) +#define STM_RCC_CR_HSEON	(16) +#define STM_RCC_CR_HSICAL	(8) +#define STM_RCC_CR_HSITRIM	(3) +#define STM_RCC_CR_HSIRDY	(1) +#define STM_RCC_CR_HSION	(0) + +#define STM_RCC_CFGR_PLL_NODIV	(31) +#define  STM_RCC_CFGR_PLL_NODIV_DIV_1	1 +#define  STM_RCC_CFGR_PLL_NODIV_DIV_2	0 + +#define STM_RCC_CFGR_MCOPRE	(28) +#define  STM_RCC_CFGR_MCOPRE_DIV_1	0 +#define  STM_RCC_CFGR_MCOPRE_DIV_2	1 +#define  STM_RCC_CFGR_MCOPRE_DIV_4	2 +#define  STM_RCC_CFGR_MCOPRE_DIV_8	3 +#define  STM_RCC_CFGR_MCOPRE_DIV_16	4 +#define  STM_RCC_CFGR_MCOPRE_DIV_32	5 +#define  STM_RCC_CFGR_MCOPRE_DIV_64	6 +#define  STM_RCC_CFGR_MCOPRE_DIV_128	7 +#define  STM_RCC_CFGR_MCOPRE_DIV_MASK	7 + +#define STM_RCC_CFGR_MCO	(24) +# define STM_RCC_CFGR_MCO_DISABLE	0 + +#define STM_RCC_CFGR_PLLMUL	(18) +#define  STM_RCC_CFGR_PLLMUL_2		0 +#define  STM_RCC_CFGR_PLLMUL_3		1 +#define  STM_RCC_CFGR_PLLMUL_4		2 +#define  STM_RCC_CFGR_PLLMUL_5		3 +#define  STM_RCC_CFGR_PLLMUL_6		4 +#define  STM_RCC_CFGR_PLLMUL_7		5 +#define  STM_RCC_CFGR_PLLMUL_8		6 +#define  STM_RCC_CFGR_PLLMUL_9		7 +#define  STM_RCC_CFGR_PLLMUL_10		8 +#define  STM_RCC_CFGR_PLLMUL_11		9 +#define  STM_RCC_CFGR_PLLMUL_12		10 +#define  STM_RCC_CFGR_PLLMUL_13		11 +#define  STM_RCC_CFGR_PLLMUL_14	       	12 +#define  STM_RCC_CFGR_PLLMUL_15	       	13 +#define  STM_RCC_CFGR_PLLMUL_16	       	14 +#define  STM_RCC_CFGR_PLLMUL_MASK	0xf + +#define STM_RCC_CFGR_PLLXTPRE	(17) + +#define STM_RCC_CFGR_PLLSRC	(15) +# define STM_RCC_CFGR_PLLSRC_HSI_DIV_2	0 +# define STM_RCC_CFGR_PLLSRC_HSI	1 +# define STM_RCC_CFGR_PLLSRC_HSE	2 +# define STM_RCC_CFGR_PLLSRC_HSI48	3 + +#define STM_RCC_CFGR_ADCPRE	(14) + +#define STM_RCC_CFGR_PPRE	(8) +#define  STM_RCC_CFGR_PPRE_DIV_1	0 +#define  STM_RCC_CFGR_PPRE_DIV_2	4 +#define  STM_RCC_CFGR_PPRE_DIV_4	5 +#define  STM_RCC_CFGR_PPRE_DIV_8	6 +#define  STM_RCC_CFGR_PPRE_DIV_16	7 +#define  STM_RCC_CFGR_PPRE_MASK		7 + +#define STM_RCC_CFGR_HPRE	(4) +#define  STM_RCC_CFGR_HPRE_DIV_1	0 +#define  STM_RCC_CFGR_HPRE_DIV_2	8 +#define  STM_RCC_CFGR_HPRE_DIV_4	9 +#define  STM_RCC_CFGR_HPRE_DIV_8	0xa +#define  STM_RCC_CFGR_HPRE_DIV_16	0xb +#define  STM_RCC_CFGR_HPRE_DIV_64	0xc +#define  STM_RCC_CFGR_HPRE_DIV_128	0xd +#define  STM_RCC_CFGR_HPRE_DIV_256	0xe +#define  STM_RCC_CFGR_HPRE_DIV_512	0xf +#define  STM_RCC_CFGR_HPRE_MASK		0xf + +#define STM_RCC_CFGR_SWS	(2) +#define  STM_RCC_CFGR_SWS_HSI		0 +#define  STM_RCC_CFGR_SWS_HSE		1 +#define  STM_RCC_CFGR_SWS_PLL		2 +#define  STM_RCC_CFGR_SWS_HSI48		3 +#define  STM_RCC_CFGR_SWS_MASK		3 + +#define STM_RCC_CFGR_SW		(0) +#define  STM_RCC_CFGR_SW_HSI		0 +#define  STM_RCC_CFGR_SW_HSE		1 +#define  STM_RCC_CFGR_SW_PLL		2 +#define  STM_RCC_CFGR_SW_HSI48		3 +#define  STM_RCC_CFGR_SW_MASK		3 + +#define STM_RCC_APB1RSTR_CECRST		30 +#define STM_RCC_APB1RSTR_DACRST		29 +#define STM_RCC_APB1RSTR_PWRRST		28 +#define STM_RCC_APB1RSTR_CRSRST		27 +#define STM_RCC_APB1RSTR_CANRST		25 +#define STM_RCC_APB1RSTR_USBRST		23 +#define STM_RCC_APB1RSTR_I2C2RST	22 +#define STM_RCC_APB1RSTR_I1C1RST	21 +#define STM_RCC_APB1RSTR_USART5RST	20 +#define STM_RCC_APB1RSTR_USART4RST	19 +#define STM_RCC_APB1RSTR_USART3RST	18 +#define STM_RCC_APB1RSTR_USART2RST	17 +#define STM_RCC_APB1RSTR_SPI2RST	14 +#define STM_RCC_APB1RSTR_WWDGRST	11 +#define STM_RCC_APB1RSTR_TIM14RST	8 +#define STM_RCC_APB1RSTR_TIM7RST	5 +#define STM_RCC_APB1RSTR_TIM6RST	4 +#define STM_RCC_APB1RSTR_TIM3RST	1 +#define STM_RCC_APB1RSTR_TIM2RST	0 + +#define STM_RCC_AHBENR_TSCEN	24 +#define STM_RCC_AHBENR_IOPFEN	22 +#define STM_RCC_AHBENR_IOPEEN	21 +#define STM_RCC_AHBENR_IOPDEN	20 +#define STM_RCC_AHBENR_IOPCEN	19 +#define STM_RCC_AHBENR_IOPBEN	18 +#define STM_RCC_AHBENR_IOPAEN	17 +#define STM_RCC_AHBENR_CRCEN	6 +#define STM_RCC_AHBENR_FLITFEN	4 +#define STM_RCC_AHBENR_SRAMEN	2 +#define STM_RCC_AHBENR_DMA2EN	1 +#define STM_RCC_AHBENR_DMAEM	0 + +#define STM_RCC_APB2ENR_DBGMCUEN	22 +#define STM_RCC_APB2ENR_TIM17EN		18 +#define STM_RCC_APB2ENR_TIM16EN		17 +#define STM_RCC_APB2ENR_TIM15EN		16 +#define STM_RCC_APB2ENR_USART1EN	14 +#define STM_RCC_APB2ENR_SPI1EN		12 +#define STM_RCC_APB2ENR_TIM1EN		11 +#define STM_RCC_APB2ENR_ADCEN		9 +#define STM_RCC_APB2ENR_USART8EN	7 +#define STM_RCC_APB2ENR_USART7EN	6 +#define STM_RCC_APB2ENR_USART6EN	5 +#define STM_RCC_APB2ENR_SYSCFGCOMPEN	0 + +#define STM_RCC_APB1ENR_CECEN		30 +#define STM_RCC_APB1ENR_DACEN		29 +#define STM_RCC_APB1ENR_PWREN		28 +#define STM_RCC_APB1ENR_CRSEN		27 +#define STM_RCC_APB1ENR_CANEN		25 +#define STM_RCC_APB1ENR_USBEN		23 +#define STM_RCC_APB1ENR_I2C2EN		22 +#define STM_RCC_APB1ENR_IC21EN		21 +#define STM_RCC_APB1ENR_USART5EN	20 +#define STM_RCC_APB1ENR_USART4EN	19 +#define STM_RCC_APB1ENR_USART3EN	18 +#define STM_RCC_APB1ENR_USART2EN	17 +#define STM_RCC_APB1ENR_SPI2EN		14 +#define STM_RCC_APB1ENR_WWDGEN		11 +#define STM_RCC_APB1ENR_TIM14EN		8 +#define STM_RCC_APB1ENR_TIM7EN		5 +#define STM_RCC_APB1ENR_TIM6EN		4 +#define STM_RCC_APB1ENR_TIM3EN		1 +#define STM_RCC_APB1ENR_TIM2EN		0 + +#define STM_RCC_CSR_LPWRRSTF		(31) +#define STM_RCC_CSR_WWDGRSTF		(30) +#define STM_RCC_CSR_IWDGRSTF		(29) +#define STM_RCC_CSR_SFTRSTF		(28) +#define STM_RCC_CSR_PORRSTF		(27) +#define STM_RCC_CSR_PINRSTF		(26) +#define STM_RCC_CSR_OBLRSTF		(25) +#define STM_RCC_CSR_RMVF		(24) +#define STM_RCC_CSR_V18PWRRSTF		(23) +#define STM_RCC_CSR_LSIRDY		(1) +#define STM_RCC_CSR_LSION		(0) + +#define STM_RCC_CR2_HSI48CAL		24 +#define STM_RCC_CR2_HSI48RDY		17 +#define STM_RCC_CR2_HSI48ON		16 +#define STM_RCC_CR2_HSI14CAL		8 +#define STM_RCC_CR2_HSI14TRIM		3 +#define STM_RCC_CR2_HSI14DIS		2 +#define STM_RCC_CR2_HSI14RDY		1 +#define STM_RCC_CR2_HSI14ON		0 + +#define STM_RCC_CFGR3_USART3SW		18 +#define STM_RCC_CFGR3_USART2SW		16 +#define STM_RCC_CFGR3_ADCSW		8 +#define STM_RCC_CFGR3_USBSW		7 +#define STM_RCC_CFGR3_CECSW		6 +#define STM_RCC_CFGR3_I2C1SW		4 +#define STM_RCC_CFGR3_USART1SW		0 + +struct stm_crs { +	vuint32_t	cr; +	vuint32_t	cfgr; +	vuint32_t	isr; +	vuint32_t	icr; +}; + +extern struct stm_crs stm_crs; + +#define STM_CRS_CR_TRIM		8 +#define STM_CRS_CR_SWSYNC	7 +#define STM_CRS_CR_AUTOTRIMEN	6 +#define STM_CRS_CR_CEN		5 +#define STM_CRS_CR_ESYNCIE	3 +#define STM_CRS_CR_ERRIE	2 +#define STM_CRS_CR_SYNCWARNIE	1 +#define STM_CRS_CR_SYNCOKIE	0 + +#define STM_CRS_CFGR_SYNCPOL	31 +#define STM_CRS_CFGR_SYNCSRC	28 +#define  STM_CRS_CFGR_SYNCSRC_GPIO	0 +#define  STM_CRS_CFGR_SYNCSRC_LSE	1 +#define  STM_CRS_CFGR_SYNCSRC_USB	2 +#define STM_CRS_CFGR_SYNCDIV	24 +#define  STM_CRS_CFGR_SYNCDIV_1		0 +#define  STM_CRS_CFGR_SYNCDIV_2		1 +#define  STM_CRS_CFGR_SYNCDIV_4		2 +#define  STM_CRS_CFGR_SYNCDIV_8		3 +#define  STM_CRS_CFGR_SYNCDIV_16	4 +#define  STM_CRS_CFGR_SYNCDIV_32	5 +#define  STM_CRS_CFGR_SYNCDIV_64	6 +#define  STM_CRS_CFGR_SYNCDIV_128	7 +#define STM_CRS_CFGR_FELIM	16 +#define STM_CRS_CFGR_RELOAD	0 + +#define STM_CRS_ISR_FECAP	16 +#define STM_CRS_ISR_FEDIR	15 +#define STM_CRS_ISR_TRIMOVF	10 +#define STM_CRS_ISR_SYNCMISS	9 +#define STM_CRS_ISR_SYNCERR	8 +#define STM_CRS_ISR_ESYNCF	3 +#define STM_CRS_ISR_ERRF	2 +#define STM_CRS_ISR_SYNCWARNF	1 +#define STM_CRS_ISR_SYNCOKF	0 + +#define STM_CRS_ICR_ESYNCC	3 +#define STM_CRS_ICR_ERRC	2 +#define STM_CRS_ICR_SYNCWARNC	1 +#define STM_CRS_ICR_SYNCOKC	0 + +struct stm_pwr { +	vuint32_t	cr; +	vuint32_t	csr; +}; + +extern struct stm_pwr stm_pwr; + +#define STM_PWR_CR_DBP		(8) + +#define STM_PWR_CR_PLS		(5) +#define  STM_PWR_CR_PLS_2_0	0 +#define  STM_PWR_CR_PLS_2_1	1 +#define  STM_PWR_CR_PLS_2_2	2 +#define  STM_PWR_CR_PLS_2_3	3 +#define  STM_PWR_CR_PLS_2_4	4 +#define  STM_PWR_CR_PLS_2_5	5 +#define  STM_PWR_CR_PLS_2_6	6 +#define  STM_PWR_CR_PLS_EXT	7 +#define  STM_PWR_CR_PLS_MASK	7 + +#define STM_PWR_CR_PVDE		(4) +#define STM_PWR_CR_CSBF		(3) +#define STM_PWR_CR_CWUF		(2) +#define STM_PWR_CR_PDDS		(1) +#define STM_PWR_CR_LPSDSR	(0) + +#define STM_PWR_CSR_EWUP3	(10) +#define STM_PWR_CSR_EWUP2	(9) +#define STM_PWR_CSR_EWUP1	(8) +#define STM_PWR_CSR_REGLPF	(5) +#define STM_PWR_CSR_VOSF	(4) +#define STM_PWR_CSR_VREFINTRDYF	(3) +#define STM_PWR_CSR_PVDO	(2) +#define STM_PWR_CSR_SBF		(1) +#define STM_PWR_CSR_WUF		(0) + +struct stm_tim67 { +	vuint32_t	cr1; +	vuint32_t	cr2; +	uint32_t	_unused_08; +	vuint32_t	dier; + +	vuint32_t	sr; +	vuint32_t	egr; +	uint32_t	_unused_18; +	uint32_t	_unused_1c; + +	uint32_t	_unused_20; +	vuint32_t	cnt; +	vuint32_t	psc; +	vuint32_t	arr; +}; + +extern struct stm_tim67 stm_tim6; + +#define STM_TIM67_CR1_ARPE	(7) +#define STM_TIM67_CR1_OPM	(3) +#define STM_TIM67_CR1_URS	(2) +#define STM_TIM67_CR1_UDIS	(1) +#define STM_TIM67_CR1_CEN	(0) + +#define STM_TIM67_CR2_MMS	(4) +#define  STM_TIM67_CR2_MMS_RESET	0 +#define  STM_TIM67_CR2_MMS_ENABLE	1 +#define  STM_TIM67_CR2_MMS_UPDATE	2 +#define  STM_TIM67_CR2_MMS_MASK		7 + +#define STM_TIM67_DIER_UDE	(8) +#define STM_TIM67_DIER_UIE	(0) + +#define STM_TIM67_SR_UIF	(0) + +#define STM_TIM67_EGR_UG	(0) + +struct stm_lcd { +	vuint32_t	cr; +	vuint32_t	fcr; +	vuint32_t	sr; +	vuint32_t	clr; +	uint32_t	unused_0x10; +	vuint32_t	ram[8*2]; +}; + +extern struct stm_lcd stm_lcd; + +#define STM_LCD_CR_MUX_SEG		(7) + +#define STM_LCD_CR_BIAS			(5) +#define  STM_LCD_CR_BIAS_1_4		0 +#define  STM_LCD_CR_BIAS_1_2		1 +#define  STM_LCD_CR_BIAS_1_3		2 +#define  STM_LCD_CR_BIAS_MASK		3 + +#define STM_LCD_CR_DUTY			(2) +#define  STM_LCD_CR_DUTY_STATIC		0 +#define  STM_LCD_CR_DUTY_1_2		1 +#define  STM_LCD_CR_DUTY_1_3		2 +#define  STM_LCD_CR_DUTY_1_4		3 +#define  STM_LCD_CR_DUTY_1_8		4 +#define  STM_LCD_CR_DUTY_MASK		7 + +#define STM_LCD_CR_VSEL			(1) +#define STM_LCD_CR_LCDEN		(0) + +#define STM_LCD_FCR_PS			(22) +#define  STM_LCD_FCR_PS_1		0x0 +#define  STM_LCD_FCR_PS_2		0x1 +#define  STM_LCD_FCR_PS_4		0x2 +#define  STM_LCD_FCR_PS_8		0x3 +#define  STM_LCD_FCR_PS_16		0x4 +#define  STM_LCD_FCR_PS_32		0x5 +#define  STM_LCD_FCR_PS_64		0x6 +#define  STM_LCD_FCR_PS_128		0x7 +#define  STM_LCD_FCR_PS_256		0x8 +#define  STM_LCD_FCR_PS_512		0x9 +#define  STM_LCD_FCR_PS_1024		0xa +#define  STM_LCD_FCR_PS_2048		0xb +#define  STM_LCD_FCR_PS_4096		0xc +#define  STM_LCD_FCR_PS_8192		0xd +#define  STM_LCD_FCR_PS_16384		0xe +#define  STM_LCD_FCR_PS_32768		0xf +#define  STM_LCD_FCR_PS_MASK		0xf + +#define STM_LCD_FCR_DIV			(18) +#define STM_LCD_FCR_DIV_16		0x0 +#define STM_LCD_FCR_DIV_17		0x1 +#define STM_LCD_FCR_DIV_18		0x2 +#define STM_LCD_FCR_DIV_19		0x3 +#define STM_LCD_FCR_DIV_20		0x4 +#define STM_LCD_FCR_DIV_21		0x5 +#define STM_LCD_FCR_DIV_22		0x6 +#define STM_LCD_FCR_DIV_23		0x7 +#define STM_LCD_FCR_DIV_24		0x8 +#define STM_LCD_FCR_DIV_25		0x9 +#define STM_LCD_FCR_DIV_26		0xa +#define STM_LCD_FCR_DIV_27		0xb +#define STM_LCD_FCR_DIV_28		0xc +#define STM_LCD_FCR_DIV_29		0xd +#define STM_LCD_FCR_DIV_30		0xe +#define STM_LCD_FCR_DIV_31		0xf +#define STM_LCD_FCR_DIV_MASK		0xf + +#define STM_LCD_FCR_BLINK		(16) +#define  STM_LCD_FCR_BLINK_DISABLE		0 +#define  STM_LCD_FCR_BLINK_SEG0_COM0		1 +#define  STM_LCD_FCR_BLINK_SEG0_COMALL		2 +#define  STM_LCD_FCR_BLINK_SEGALL_COMALL	3 +#define  STM_LCD_FCR_BLINK_MASK			3 + +#define STM_LCD_FCR_BLINKF		(13) +#define  STM_LCD_FCR_BLINKF_8			0 +#define  STM_LCD_FCR_BLINKF_16			1 +#define  STM_LCD_FCR_BLINKF_32			2 +#define  STM_LCD_FCR_BLINKF_64			3 +#define  STM_LCD_FCR_BLINKF_128			4 +#define  STM_LCD_FCR_BLINKF_256			5 +#define  STM_LCD_FCR_BLINKF_512			6 +#define  STM_LCD_FCR_BLINKF_1024		7 +#define  STM_LCD_FCR_BLINKF_MASK		7 + +#define STM_LCD_FCR_CC			(10) +#define  STM_LCD_FCR_CC_MASK			7 + +#define STM_LCD_FCR_DEAD		(7) +#define  STM_LCD_FCR_DEAD_MASK			7 + +#define STM_LCD_FCR_PON			(4) +#define  STM_LCD_FCR_PON_MASK			7 + +#define STM_LCD_FCR_UDDIE		(3) +#define STM_LCD_FCR_SOFIE		(1) +#define STM_LCD_FCR_HD			(0) + +#define STM_LCD_SR_FCRSF		(5) +#define STM_LCD_SR_RDY			(4) +#define STM_LCD_SR_UDD			(3) +#define STM_LCD_SR_UDR			(2) +#define STM_LCD_SR_SOF			(1) +#define STM_LCD_SR_ENS			(0) + +#define STM_LCD_CLR_UDDC		(3) +#define STM_LCD_CLR_SOFC		(1) + +/* The SYSTICK starts at 0xe000e010 */ + +struct stm_systick { +	vuint32_t	csr; +	vuint32_t	rvr; +	vuint32_t	cvr; +	vuint32_t	calib; +}; + +extern struct stm_systick stm_systick; + +#define STM_SYSTICK_CSR_ENABLE		0 +#define STM_SYSTICK_CSR_TICKINT		1 +#define STM_SYSTICK_CSR_CLKSOURCE	2 +#define  STM_SYSTICK_CSR_CLKSOURCE_EXTERNAL		0 +#define  STM_SYSTICK_CSR_CLKSOURCE_HCLK_8		1 +#define STM_SYSTICK_CSR_COUNTFLAG	16 + +/* The NVIC starts at 0xe000e100, so add that to the offsets to find the absolute address */ + +struct stm_nvic { +	vuint32_t	iser;		/* 0x000 0xe000e100 Set Enable Register */ + +	uint8_t		_unused020[0x080 - 0x004]; + +	vuint32_t	icer;		/* 0x080 0xe000e180 Clear Enable Register */ + +	uint8_t		_unused0a0[0x100 - 0x084]; + +	vuint32_t	ispr;		/* 0x100 0xe000e200 Set Pending Register */ + +	uint8_t		_unused120[0x180 - 0x104]; + +	vuint32_t	icpr;		/* 0x180 0xe000e280 Clear Pending Register */ + +	uint8_t		_unused1a0[0x300 - 0x184]; + +	vuint32_t	ipr[8];		/* 0x300 0xe000e400 Priority Register */ +}; + +extern struct stm_nvic stm_nvic; + +#define IRQ_MASK(irq)	(1 << (irq)) +#define IRQ_BOOL(v,irq)	(((v) >> (irq)) & 1) + +static inline void +stm_nvic_set_enable(int irq) { +	stm_nvic.iser = IRQ_MASK(irq); +} + +static inline void +stm_nvic_clear_enable(int irq) { +	stm_nvic.icer = IRQ_MASK(irq); +} + +static inline int +stm_nvic_enabled(int irq) { +	return IRQ_BOOL(stm_nvic.iser, irq); +} + +static inline void +stm_nvic_set_pending(int irq) { +	stm_nvic.ispr = IRQ_MASK(irq); +} + +static inline void +stm_nvic_clear_pending(int irq) { +	stm_nvic.icpr = IRQ_MASK(irq); +} + +static inline int +stm_nvic_pending(int irq) { +	return IRQ_BOOL(stm_nvic.ispr, irq); +} + +#define IRQ_PRIO_REG(irq)	((irq) >> 2) +#define IRQ_PRIO_BIT(irq)	(((irq) & 3) << 3) +#define IRQ_PRIO_MASK(irq)	(0xff << IRQ_PRIO_BIT(irq)) + +static inline void +stm_nvic_set_priority(int irq, uint8_t prio) { +	int		n = IRQ_PRIO_REG(irq); +	uint32_t	v; + +	v = stm_nvic.ipr[n]; +	v &= ~IRQ_PRIO_MASK(irq); +	v |= (prio) << IRQ_PRIO_BIT(irq); +	stm_nvic.ipr[n] = v; +} + +static inline uint8_t +stm_nvic_get_priority(int irq) { +	return (stm_nvic.ipr[IRQ_PRIO_REG(irq)] >> IRQ_PRIO_BIT(irq)) & IRQ_PRIO_MASK(0); +} + +struct stm_scb { +	vuint32_t	cpuid; +	vuint32_t	icsr; +	vuint32_t	vtor; +	vuint32_t	aircr; + +	vuint32_t	scr; +	vuint32_t	ccr; +	vuint32_t	shpr1; +	vuint32_t	shpr2; + +	vuint32_t	shpr3; +	vuint32_t	shcrs; +	vuint32_t	cfsr; +	vuint32_t	hfsr; + +	uint32_t	unused_30; +	vuint32_t	mmfar; +	vuint32_t	bfar; +}; + +extern struct stm_scb stm_scb; + +#define STM_SCB_AIRCR_VECTKEY		16 +#define  STM_SCB_AIRCR_VECTKEY_KEY		0x05fa +#define STM_SCB_AIRCR_PRIGROUP		8 +#define STM_SCB_AIRCR_SYSRESETREQ	2 +#define STM_SCB_AIRCR_VECTCLRACTIVE	1 +#define STM_SCB_AIRCR_VECTRESET		0 + +struct stm_mpu { +	vuint32_t	typer; +	vuint32_t	cr; +	vuint32_t	rnr; +	vuint32_t	rbar; + +	vuint32_t	rasr; +	vuint32_t	rbar_a1; +	vuint32_t	rasr_a1; +	vuint32_t	rbar_a2; +	vuint32_t	rasr_a2; +	vuint32_t	rbar_a3; +	vuint32_t	rasr_a3; +}; + +extern struct stm_mpu stm_mpu; + +#define STM_MPU_TYPER_IREGION	16 +#define  STM_MPU_TYPER_IREGION_MASK	0xff +#define STM_MPU_TYPER_DREGION	8 +#define  STM_MPU_TYPER_DREGION_MASK	0xff +#define STM_MPU_TYPER_SEPARATE	0 + +#define STM_MPU_CR_PRIVDEFENA	2 +#define STM_MPU_CR_HFNMIENA	1 +#define STM_MPU_CR_ENABLE	0 + +#define STM_MPU_RNR_REGION	0 +#define STM_MPU_RNR_REGION_MASK		0xff + +#define STM_MPU_RBAR_ADDR	5 +#define STM_MPU_RBAR_ADDR_MASK		0x7ffffff + +#define STM_MPU_RBAR_VALID	4 +#define STM_MPU_RBAR_REGION	0 +#define STM_MPU_RBAR_REGION_MASK	0xf + +#define STM_MPU_RASR_XN		28 +#define STM_MPU_RASR_AP		24 +#define  STM_MPU_RASR_AP_NONE_NONE	0 +#define  STM_MPU_RASR_AP_RW_NONE	1 +#define  STM_MPU_RASR_AP_RW_RO		2 +#define  STM_MPU_RASR_AP_RW_RW		3 +#define  STM_MPU_RASR_AP_RO_NONE	5 +#define  STM_MPU_RASR_AP_RO_RO		6 +#define  STM_MPU_RASR_AP_MASK		7 +#define STM_MPU_RASR_TEX	19 +#define  STM_MPU_RASR_TEX_MASK		7 +#define STM_MPU_RASR_S		18 +#define STM_MPU_RASR_C		17 +#define STM_MPU_RASR_B		16 +#define STM_MPU_RASR_SRD	8 +#define  STM_MPU_RASR_SRD_MASK		0xff +#define STM_MPU_RASR_SIZE	1 +#define  STM_MPU_RASR_SIZE_MASK		0x1f +#define STM_MPU_RASR_ENABLE	0 + +#define isr(name) void stm_ ## name ## _isr(void); + +isr(nmi) +isr(hardfault) +isr(memmanage) +isr(busfault) +isr(usagefault) +isr(svc) +isr(debugmon) +isr(pendsv) +isr(systick) +isr(wwdg) +isr(pvd) +isr(tamper_stamp) +isr(rtc_wkup) +isr(flash) +isr(rcc) +isr(exti0) +isr(exti1) +isr(exti2) +isr(exti3) +isr(exti4) +isr(dma1_channel1) +isr(dma1_channel2) +isr(dma1_channel3) +isr(dma1_channel4) +isr(dma1_channel5) +isr(dma1_channel6) +isr(dma1_channel7) +isr(adc1) +isr(usb_hp) +isr(usb_lp) +isr(dac) +isr(comp) +isr(exti9_5) +isr(lcd) +isr(tim9) +isr(tim10) +isr(tim11) +isr(tim2) +isr(tim3) +isr(tim4) +isr(i2c1_ev) +isr(i2c1_er) +isr(i2c2_ev) +isr(i2c2_er) +isr(spi1) +isr(spi2) +isr(usart1) +isr(usart2) +isr(usart3) +isr(exti15_10) +isr(rtc_alarm) +isr(usb_fs_wkup) +isr(tim6) +isr(tim7) + +#undef isr + +#define STM_ISR_WWDG_POS		0 +#define STM_ISR_PVD_VDDIO2_POS		1 +#define STM_ISR_RTC_POS			2 +#define STM_ISR_FLASH_POS		3 +#define STM_ISR_RCC_CRS_POS		4 +#define STM_ISR_EXTI0_1_POS		5 +#define STM_ISR_EXTI2_3_POS		6 +#define STM_ISR_EXTI4_15_POS		7 +#define STM_ISR_TSC_POS			8 +#define STM_ISR_DMA_CH1_POS		9 +#define STM_ISR_DMA_CH2_3_DMA2_CH1_2_POS	10 +#define STM_ISR_DMA_CH44_5_6_7_DMA2_CH3_4_5_POS	11 +#define STM_ISR_ADC_COMP_POS		12 +#define STM_ISR_TIM1_BRK_UP_TRG_COM_POS	13 +#define STM_ISR_TIM1_CC_POS		14 +#define STM_ISR_TIM2_POS		15 +#define STM_ISR_TIM3_POS		16 +#define STM_ISR_TIM6_DAC_POS		17 +#define STM_ISR_TIM7_POS		18 +#define STM_ISR_TIM14_POS		19 +#define STM_ISR_TIM15_POS		20 +#define STM_ISR_TIM16_POS		21 +#define STM_ISR_TIM17_POS		22 +#define STM_ISR_I2C1_POS		23 +#define STM_ISR_I2C2_POS		24 +#define STM_ISR_SPI1_POS		25 +#define STM_ISR_SPI2_POS		26 +#define STM_ISR_USART1_POS		27 +#define STM_ISR_USART2_POS		28 +#define STM_ISR_UASART3_4_5_6_7_8_POS	29 +#define STM_ISR_CEC_CAN_POS		30 +#define STM_ISR_USB_POS			31 + +struct stm_syscfg { +	vuint32_t	cfgr1; +	vuint32_t	exticr[4]; +	vuint32_t	cfgr2; +}; + +extern struct stm_syscfg stm_syscfg; + +#if 0 +static inline void +stm_exticr_set(struct stm_gpio *gpio, int pin) { +	uint8_t	reg = pin >> 2; +	uint8_t	shift = (pin & 3) << 2; +	uint8_t	val = 0; + +	/* Enable SYSCFG */ +	stm_rcc.apb2enr |= (1 << STM_RCC_APB2ENR_SYSCFGCOMPEN); + +	if (gpio == &stm_gpioa) +		val = STM_SYSCFG_EXTICR_PA; +	else if (gpio == &stm_gpiob) +		val = STM_SYSCFG_EXTICR_PB; +	else if (gpio == &stm_gpioc) +		val = STM_SYSCFG_EXTICR_PC; +	else if (gpio == &stm_gpiof) +		val = STM_SYSCFG_EXTICR_PF; + +	stm_syscfg.exticr[reg] = (stm_syscfg.exticr[reg] & ~(0xf << shift)) | val << shift; +} +#endif + + +struct stm_dma_channel { +	vuint32_t	ccr; +	vuint32_t	cndtr; +	vvoid_t		cpar; +	vvoid_t		cmar; +	vuint32_t	reserved; +}; + +#define STM_NUM_DMA	7 + +struct stm_dma { +	vuint32_t		isr; +	vuint32_t		ifcr; +	struct stm_dma_channel	channel[STM_NUM_DMA]; +}; + +extern struct stm_dma stm_dma; + +/* DMA channels go from 1 to 7, instead of 0 to 6 (sigh) + */ + +#define STM_DMA_INDEX(channel)		((channel) - 1) + +#define STM_DMA_ISR(index)		((index) << 2) +#define STM_DMA_ISR_MASK			0xf +#define STM_DMA_ISR_TEIF			3 +#define STM_DMA_ISR_HTIF			2 +#define STM_DMA_ISR_TCIF			1 +#define STM_DMA_ISR_GIF				0 + +#define STM_DMA_IFCR(index)		((index) << 2) +#define STM_DMA_IFCR_MASK			0xf +#define STM_DMA_IFCR_CTEIF      		3 +#define STM_DMA_IFCR_CHTIF			2 +#define STM_DMA_IFCR_CTCIF			1 +#define STM_DMA_IFCR_CGIF			0 + +#define STM_DMA_CCR_MEM2MEM		(14) + +#define STM_DMA_CCR_PL			(12) +#define  STM_DMA_CCR_PL_LOW			(0) +#define  STM_DMA_CCR_PL_MEDIUM			(1) +#define  STM_DMA_CCR_PL_HIGH			(2) +#define  STM_DMA_CCR_PL_VERY_HIGH		(3) +#define  STM_DMA_CCR_PL_MASK			(3) + +#define STM_DMA_CCR_MSIZE		(10) +#define  STM_DMA_CCR_MSIZE_8			(0) +#define  STM_DMA_CCR_MSIZE_16			(1) +#define  STM_DMA_CCR_MSIZE_32			(2) +#define  STM_DMA_CCR_MSIZE_MASK			(3) + +#define STM_DMA_CCR_PSIZE		(8) +#define  STM_DMA_CCR_PSIZE_8			(0) +#define  STM_DMA_CCR_PSIZE_16			(1) +#define  STM_DMA_CCR_PSIZE_32			(2) +#define  STM_DMA_CCR_PSIZE_MASK			(3) + +#define STM_DMA_CCR_MINC		(7) +#define STM_DMA_CCR_PINC		(6) +#define STM_DMA_CCR_CIRC		(5) +#define STM_DMA_CCR_DIR			(4) +#define  STM_DMA_CCR_DIR_PER_TO_MEM		0 +#define  STM_DMA_CCR_DIR_MEM_TO_PER		1 +#define STM_DMA_CCR_TEIE		(3) +#define STM_DMA_CCR_HTIE		(2) +#define STM_DMA_CCR_TCIE		(1) +#define STM_DMA_CCR_EN			(0) + +#define STM_DMA_CHANNEL_ADC1		1 +#define STM_DMA_CHANNEL_SPI1_RX		2 +#define STM_DMA_CHANNEL_SPI1_TX		3 +#define STM_DMA_CHANNEL_SPI2_RX		4 +#define STM_DMA_CHANNEL_SPI2_TX		5 +#define STM_DMA_CHANNEL_USART3_TX	2 +#define STM_DMA_CHANNEL_USART3_RX	3 +#define STM_DMA_CHANNEL_USART1_TX	4 +#define STM_DMA_CHANNEL_USART1_RX	5 +#define STM_DMA_CHANNEL_USART2_RX	6 +#define STM_DMA_CHANNEL_USART2_TX	7 +#define STM_DMA_CHANNEL_I2C2_TX		4 +#define STM_DMA_CHANNEL_I2C2_RX		5 +#define STM_DMA_CHANNEL_I2C1_TX		6 +#define STM_DMA_CHANNEL_I2C1_RX		7 +#define STM_DMA_CHANNEL_TIM2_CH3	1 +#define STM_DMA_CHANNEL_TIM2_UP		2 +#define STM_DMA_CHANNEL_TIM2_CH1	5 +#define STM_DMA_CHANNEL_TIM2_CH2	7 +#define STM_DMA_CHANNEL_TIM2_CH4	7 +#define STM_DMA_CHANNEL_TIM3_CH3	2 +#define STM_DMA_CHANNEL_TIM3_CH4	3 +#define STM_DMA_CHANNEL_TIM3_UP		3 +#define STM_DMA_CHANNEL_TIM3_CH1	6 +#define STM_DMA_CHANNEL_TIM3_TRIG	6 +#define STM_DMA_CHANNEL_TIM4_CH1	1 +#define STM_DMA_CHANNEL_TIM4_CH2	4 +#define STM_DMA_CHANNEL_TIM4_CH3	5 +#define STM_DMA_CHANNEL_TIM4_UP		7 +#define STM_DMA_CHANNEL_TIM6_UP_DA	2 +#define STM_DMA_CHANNEL_C_CHANNEL1	2 +#define STM_DMA_CHANNEL_TIM7_UP_DA	3 +#define STM_DMA_CHANNEL_C_CHANNEL2	3 + +/* + * Only spi channel 1 and 2 can use DMA + */ +#define STM_NUM_SPI	2 + +struct stm_spi { +	vuint32_t	cr1; +	vuint32_t	cr2; +	vuint32_t	sr; +	vuint32_t	dr; +	vuint32_t	crcpr; +	vuint32_t	rxcrcr; +	vuint32_t	txcrcr; +}; + +extern struct stm_spi stm_spi1, stm_spi2, stm_spi3; + +/* SPI channels go from 1 to 3, instead of 0 to 2 (sigh) + */ + +#define STM_SPI_INDEX(channel)		((channel) - 1) + +#define STM_SPI_CR1_BIDIMODE		15 +#define STM_SPI_CR1_BIDIOE		14 +#define STM_SPI_CR1_CRCEN		13 +#define STM_SPI_CR1_CRCNEXT		12 +#define STM_SPI_CR1_DFF			11 +#define STM_SPI_CR1_RXONLY		10 +#define STM_SPI_CR1_SSM			9 +#define STM_SPI_CR1_SSI			8 +#define STM_SPI_CR1_LSBFIRST		7 +#define STM_SPI_CR1_SPE			6 +#define STM_SPI_CR1_BR			3 +#define  STM_SPI_CR1_BR_PCLK_2			0 +#define  STM_SPI_CR1_BR_PCLK_4			1 +#define  STM_SPI_CR1_BR_PCLK_8			2 +#define  STM_SPI_CR1_BR_PCLK_16			3 +#define  STM_SPI_CR1_BR_PCLK_32			4 +#define  STM_SPI_CR1_BR_PCLK_64			5 +#define  STM_SPI_CR1_BR_PCLK_128		6 +#define  STM_SPI_CR1_BR_PCLK_256		7 +#define  STM_SPI_CR1_BR_MASK			7 + +#define STM_SPI_CR1_MSTR		2 +#define STM_SPI_CR1_CPOL		1 +#define STM_SPI_CR1_CPHA		0 + +#define STM_SPI_CR2_TXEIE	7 +#define STM_SPI_CR2_RXNEIE	6 +#define STM_SPI_CR2_ERRIE	5 +#define STM_SPI_CR2_SSOE	2 +#define STM_SPI_CR2_TXDMAEN	1 +#define STM_SPI_CR2_RXDMAEN	0 + +#define STM_SPI_SR_BSY		7 +#define STM_SPI_SR_OVR		6 +#define STM_SPI_SR_MODF		5 +#define STM_SPI_SR_CRCERR	4 +#define STM_SPI_SR_TXE		1 +#define STM_SPI_SR_RXNE		0 + +struct stm_adc { +	vuint32_t	sr; +	vuint32_t	cr1; +	vuint32_t	cr2; +	vuint32_t	smpr1; +	vuint32_t	smpr2; +	vuint32_t	smpr3; +	vuint32_t	jofr1; +	vuint32_t	jofr2; +	vuint32_t	jofr3; +	vuint32_t	jofr4; +	vuint32_t	htr; +	vuint32_t	ltr; +	vuint32_t	sqr1; +	vuint32_t	sqr2; +	vuint32_t	sqr3; +	vuint32_t	sqr4; +	vuint32_t	sqr5; +	vuint32_t	jsqr; +	vuint32_t	jdr1; +	vuint32_t	jdr2; +	vuint32_t	jdr3; +	vuint32_t	jdr4; +	vuint32_t	dr; +	uint8_t		reserved[0x300 - 0x5c]; +	vuint32_t	csr; +	vuint32_t	ccr; +}; + +extern struct stm_adc stm_adc; + +#define STM_ADC_SR_JCNR		9 +#define STM_ADC_SR_RCNR		8 +#define STM_ADC_SR_ADONS	6 +#define STM_ADC_SR_OVR		5 +#define STM_ADC_SR_STRT		4 +#define STM_ADC_SR_JSTRT	3 +#define STM_ADC_SR_JEOC		2 +#define STM_ADC_SR_EOC		1 +#define STM_ADC_SR_AWD		0 + +#define STM_ADC_CR1_OVRIE	26 +#define STM_ADC_CR1_RES		24 +#define  STM_ADC_CR1_RES_12		0 +#define  STM_ADC_CR1_RES_10		1 +#define  STM_ADC_CR1_RES_8		2 +#define  STM_ADC_CR1_RES_6		3 +#define  STM_ADC_CR1_RES_MASK		3 +#define STM_ADC_CR1_AWDEN       23 +#define STM_ADC_CR1_JAWDEN	22 +#define STM_ADC_CR1_PDI		17 +#define STM_ADC_CR1_PDD		16 +#define STM_ADC_CR1_DISCNUM	13 +#define  STM_ADC_CR1_DISCNUM_1		0 +#define  STM_ADC_CR1_DISCNUM_2		1 +#define  STM_ADC_CR1_DISCNUM_3		2 +#define  STM_ADC_CR1_DISCNUM_4		3 +#define  STM_ADC_CR1_DISCNUM_5		4 +#define  STM_ADC_CR1_DISCNUM_6		5 +#define  STM_ADC_CR1_DISCNUM_7		6 +#define  STM_ADC_CR1_DISCNUM_8		7 +#define  STM_ADC_CR1_DISCNUM_MASK	7 +#define STM_ADC_CR1_JDISCEN	12 +#define STM_ADC_CR1_DISCEN	11 +#define STM_ADC_CR1_JAUTO	10 +#define STM_ADC_CR1_AWDSGL	9 +#define STM_ADC_CR1_SCAN	8 +#define STM_ADC_CR1_JEOCIE	7 +#define STM_ADC_CR1_AWDIE	6 +#define STM_ADC_CR1_EOCIE	5 +#define STM_ADC_CR1_AWDCH	0 +#define  STM_ADC_CR1_AWDCH_MASK		0x1f + +#define STM_ADC_CR2_SWSTART	30 +#define STM_ADC_CR2_EXTEN	28 +#define  STM_ADC_CR2_EXTEN_DISABLE	0 +#define  STM_ADC_CR2_EXTEN_RISING	1 +#define  STM_ADC_CR2_EXTEN_FALLING	2 +#define  STM_ADC_CR2_EXTEN_BOTH		3 +#define  STM_ADC_CR2_EXTEN_MASK		3 +#define STM_ADC_CR2_EXTSEL	24 +#define  STM_ADC_CR2_EXTSEL_TIM9_CC2	0 +#define  STM_ADC_CR2_EXTSEL_TIM9_TRGO	1 +#define  STM_ADC_CR2_EXTSEL_TIM2_CC3	2 +#define  STM_ADC_CR2_EXTSEL_TIM2_CC2	3 +#define  STM_ADC_CR2_EXTSEL_TIM3_TRGO	4 +#define  STM_ADC_CR2_EXTSEL_TIM4_CC4	5 +#define  STM_ADC_CR2_EXTSEL_TIM2_TRGO	6 +#define  STM_ADC_CR2_EXTSEL_TIM3_CC1	7 +#define  STM_ADC_CR2_EXTSEL_TIM3_CC3	8 +#define  STM_ADC_CR2_EXTSEL_TIM4_TRGO	9 +#define  STM_ADC_CR2_EXTSEL_TIM6_TRGO	10 +#define  STM_ADC_CR2_EXTSEL_EXTI_11	15 +#define  STM_ADC_CR2_EXTSEL_MASK	15 +#define STM_ADC_CR2_JWSTART	22 +#define STM_ADC_CR2_JEXTEN	20 +#define  STM_ADC_CR2_JEXTEN_DISABLE	0 +#define  STM_ADC_CR2_JEXTEN_RISING	1 +#define  STM_ADC_CR2_JEXTEN_FALLING	2 +#define  STM_ADC_CR2_JEXTEN_BOTH	3 +#define  STM_ADC_CR2_JEXTEN_MASK	3 +#define STM_ADC_CR2_JEXTSEL	16 +#define  STM_ADC_CR2_JEXTSEL_TIM9_CC1	0 +#define  STM_ADC_CR2_JEXTSEL_TIM9_TRGO	1 +#define  STM_ADC_CR2_JEXTSEL_TIM2_TRGO	2 +#define  STM_ADC_CR2_JEXTSEL_TIM2_CC1	3 +#define  STM_ADC_CR2_JEXTSEL_TIM3_CC4	4 +#define  STM_ADC_CR2_JEXTSEL_TIM4_TRGO	5 +#define  STM_ADC_CR2_JEXTSEL_TIM4_CC1	6 +#define  STM_ADC_CR2_JEXTSEL_TIM4_CC2	7 +#define  STM_ADC_CR2_JEXTSEL_TIM4_CC3	8 +#define  STM_ADC_CR2_JEXTSEL_TIM10_CC1	9 +#define  STM_ADC_CR2_JEXTSEL_TIM7_TRGO	10 +#define  STM_ADC_CR2_JEXTSEL_EXTI_15	15 +#define  STM_ADC_CR2_JEXTSEL_MASK	15 +#define STM_ADC_CR2_ALIGN	11 +#define STM_ADC_CR2_EOCS	10 +#define STM_ADC_CR2_DDS		9 +#define STM_ADC_CR2_DMA		8 +#define STM_ADC_CR2_DELS	4 +#define  STM_ADC_CR2_DELS_NONE		0 +#define  STM_ADC_CR2_DELS_UNTIL_READ	1 +#define  STM_ADC_CR2_DELS_7		2 +#define  STM_ADC_CR2_DELS_15		3 +#define  STM_ADC_CR2_DELS_31		4 +#define  STM_ADC_CR2_DELS_63		5 +#define  STM_ADC_CR2_DELS_127		6 +#define  STM_ADC_CR2_DELS_255		7 +#define  STM_ADC_CR2_DELS_MASK		7 +#define STM_ADC_CR2_CONT	1 +#define STM_ADC_CR2_ADON	0 + +#define STM_ADC_CCR_TSVREFE	23 +#define STM_ADC_CCR_ADCPRE	16 +#define  STM_ADC_CCR_ADCPRE_HSI_1	0 +#define  STM_ADC_CCR_ADCPRE_HSI_2	1 +#define  STM_ADC_CCR_ADCPRE_HSI_4	2 +#define  STM_ADC_CCR_ADCPRE_MASK	3 + +struct stm_temp_cal { +	uint16_t	vref; +	uint16_t	ts_cal_cold; +	uint16_t	reserved; +	uint16_t	ts_cal_hot; +}; + +extern struct stm_temp_cal	stm_temp_cal; + +#define stm_temp_cal_cold	25 +#define stm_temp_cal_hot	110 + +struct stm_dbg_mcu { +	uint32_t	idcode; +}; + +extern struct stm_dbg_mcu	stm_dbg_mcu; + +static inline uint16_t +stm_dev_id(void) { +	return stm_dbg_mcu.idcode & 0xfff; +} + +struct stm_flash_size { +	uint16_t	f_size; +}; + +extern struct stm_flash_size	stm_flash_size_medium; +extern struct stm_flash_size	stm_flash_size_large; + +/* Returns flash size in bytes */ +extern uint32_t +stm_flash_size(void); + +struct stm_device_id { +	uint32_t	u_id0; +	uint32_t	u_id1; +	uint32_t	u_id2; +}; + +extern struct stm_device_id	stm_device_id; + +#define STM_NUM_I2C	2 + +#define STM_I2C_INDEX(channel)	((channel) - 1) + +struct stm_i2c { +	vuint32_t	cr1; +	vuint32_t	cr2; +	vuint32_t	oar1; +	vuint32_t	oar2; +	vuint32_t	dr; +	vuint32_t	sr1; +	vuint32_t	sr2; +	vuint32_t	ccr; +	vuint32_t	trise; +}; + +extern struct stm_i2c stm_i2c1, stm_i2c2; + +#define STM_I2C_CR1_SWRST	15 +#define STM_I2C_CR1_ALERT	13 +#define STM_I2C_CR1_PEC		12 +#define STM_I2C_CR1_POS		11 +#define STM_I2C_CR1_ACK		10 +#define STM_I2C_CR1_STOP	9 +#define STM_I2C_CR1_START	8 +#define STM_I2C_CR1_NOSTRETCH	7 +#define STM_I2C_CR1_ENGC	6 +#define STM_I2C_CR1_ENPEC	5 +#define STM_I2C_CR1_ENARP	4 +#define STM_I2C_CR1_SMBTYPE	3 +#define STM_I2C_CR1_SMBUS	1 +#define STM_I2C_CR1_PE		0 + +#define STM_I2C_CR2_LAST	12 +#define STM_I2C_CR2_DMAEN	11 +#define STM_I2C_CR2_ITBUFEN	10 +#define STM_I2C_CR2_ITEVTEN	9 +#define STM_I2C_CR2_ITERREN	8 +#define STM_I2C_CR2_FREQ	0 +#define  STM_I2C_CR2_FREQ_2_MHZ		2 +#define  STM_I2C_CR2_FREQ_4_MHZ		4 +#define  STM_I2C_CR2_FREQ_8_MHZ		8 +#define  STM_I2C_CR2_FREQ_16_MHZ	16 +#define  STM_I2C_CR2_FREQ_32_MHZ	32 +#define  STM_I2C_CR2_FREQ_MASK		0x3f + +#define STM_I2C_SR1_SMBALERT	15 +#define STM_I2C_SR1_TIMEOUT	14 +#define STM_I2C_SR1_PECERR	12 +#define STM_I2C_SR1_OVR		11 +#define STM_I2C_SR1_AF		10 +#define STM_I2C_SR1_ARLO	9 +#define STM_I2C_SR1_BERR	8 +#define STM_I2C_SR1_TXE		7 +#define STM_I2C_SR1_RXNE	6 +#define STM_I2C_SR1_STOPF	4 +#define STM_I2C_SR1_ADD10	3 +#define STM_I2C_SR1_BTF		2 +#define STM_I2C_SR1_ADDR	1 +#define STM_I2C_SR1_SB		0 + +#define STM_I2C_SR2_PEC		8 +#define  STM_I2C_SR2_PEC_MASK	0xff00 +#define STM_I2C_SR2_DUALF	7 +#define STM_I2C_SR2_SMBHOST	6 +#define STM_I2C_SR2_SMBDEFAULT	5 +#define STM_I2C_SR2_GENCALL	4 +#define STM_I2C_SR2_TRA		2 +#define STM_I2C_SR2_BUSY       	1 +#define STM_I2C_SR2_MSL		0 + +#define STM_I2C_CCR_FS		15 +#define STM_I2C_CCR_DUTY	14 +#define STM_I2C_CCR_CCR		0 +#define  STM_I2C_CCR_MASK	0x7ff + +struct stm_tim234 { +	vuint32_t	cr1; +	vuint32_t	cr2; +	vuint32_t	smcr; +	vuint32_t	dier; + +	vuint32_t	sr; +	vuint32_t	egr; +	vuint32_t	ccmr1; +	vuint32_t	ccmr2; + +	vuint32_t	ccer; +	vuint32_t	cnt; +	vuint32_t	psc; +	vuint32_t	arr; + +	uint32_t	reserved_30; +	vuint32_t	ccr1; +	vuint32_t	ccr2; +	vuint32_t	ccr3; + +	vuint32_t	ccr4; +	uint32_t	reserved_44; +	vuint32_t	dcr; +	vuint32_t	dmar; + +	uint32_t	reserved_50; +}; + +extern struct stm_tim234 stm_tim2, stm_tim3, stm_tim4; + +#define STM_TIM234_CR1_CKD	8 +#define  STM_TIM234_CR1_CKD_1		0 +#define  STM_TIM234_CR1_CKD_2		1 +#define  STM_TIM234_CR1_CKD_4		2 +#define  STM_TIM234_CR1_CKD_MASK	3 +#define STM_TIM234_CR1_ARPE	7 +#define STM_TIM234_CR1_CMS	5 +#define  STM_TIM234_CR1_CMS_EDGE	0 +#define  STM_TIM234_CR1_CMS_CENTER_1	1 +#define  STM_TIM234_CR1_CMS_CENTER_2	2 +#define  STM_TIM234_CR1_CMS_CENTER_3	3 +#define  STM_TIM234_CR1_CMS_MASK	3 +#define STM_TIM234_CR1_DIR	4 +#define  STM_TIM234_CR1_DIR_UP		0 +#define  STM_TIM234_CR1_DIR_DOWN	1 +#define STM_TIM234_CR1_OPM	3 +#define STM_TIM234_CR1_URS	2 +#define STM_TIM234_CR1_UDIS	1 +#define STM_TIM234_CR1_CEN	0 + +#define STM_TIM234_CR2_TI1S	7 +#define STM_TIM234_CR2_MMS	4 +#define  STM_TIM234_CR2_MMS_RESET		0 +#define  STM_TIM234_CR2_MMS_ENABLE		1 +#define  STM_TIM234_CR2_MMS_UPDATE		2 +#define  STM_TIM234_CR2_MMS_COMPARE_PULSE	3 +#define  STM_TIM234_CR2_MMS_COMPARE_OC1REF	4 +#define  STM_TIM234_CR2_MMS_COMPARE_OC2REF	5 +#define  STM_TIM234_CR2_MMS_COMPARE_OC3REF	6 +#define  STM_TIM234_CR2_MMS_COMPARE_OC4REF	7 +#define  STM_TIM234_CR2_MMS_MASK		7 +#define STM_TIM234_CR2_CCDS	3 + +#define STM_TIM234_SMCR_ETP	15 +#define STM_TIM234_SMCR_ECE	14 +#define STM_TIM234_SMCR_ETPS	12 +#define  STM_TIM234_SMCR_ETPS_OFF		0 +#define  STM_TIM234_SMCR_ETPS_DIV_2	       	1 +#define  STM_TIM234_SMCR_ETPS_DIV_4		2 +#define  STM_TIM234_SMCR_ETPS_DIV_8		3 +#define  STM_TIM234_SMCR_ETPS_MASK		3 +#define STM_TIM234_SMCR_ETF	8 +#define  STM_TIM234_SMCR_ETF_NONE		0 +#define  STM_TIM234_SMCR_ETF_INT_N_2		1 +#define  STM_TIM234_SMCR_ETF_INT_N_4		2 +#define  STM_TIM234_SMCR_ETF_INT_N_8		3 +#define  STM_TIM234_SMCR_ETF_DTS_2_N_6		4 +#define  STM_TIM234_SMCR_ETF_DTS_2_N_8		5 +#define  STM_TIM234_SMCR_ETF_DTS_4_N_6		6 +#define  STM_TIM234_SMCR_ETF_DTS_4_N_8		7 +#define  STM_TIM234_SMCR_ETF_DTS_8_N_6		8 +#define  STM_TIM234_SMCR_ETF_DTS_8_N_8		9 +#define  STM_TIM234_SMCR_ETF_DTS_16_N_5		10 +#define  STM_TIM234_SMCR_ETF_DTS_16_N_6		11 +#define  STM_TIM234_SMCR_ETF_DTS_16_N_8		12 +#define  STM_TIM234_SMCR_ETF_DTS_32_N_5		13 +#define  STM_TIM234_SMCR_ETF_DTS_32_N_6		14 +#define  STM_TIM234_SMCR_ETF_DTS_32_N_8		15 +#define  STM_TIM234_SMCR_ETF_MASK		15 +#define STM_TIM234_SMCR_MSM	7 +#define STM_TIM234_SMCR_TS	4 +#define  STM_TIM234_SMCR_TS_ITR0		0 +#define  STM_TIM234_SMCR_TS_ITR1		1 +#define  STM_TIM234_SMCR_TS_ITR2		2 +#define  STM_TIM234_SMCR_TS_ITR3		3 +#define  STM_TIM234_SMCR_TS_TI1F_ED		4 +#define  STM_TIM234_SMCR_TS_TI1FP1		5 +#define  STM_TIM234_SMCR_TS_TI2FP2		6 +#define  STM_TIM234_SMCR_TS_ETRF		7 +#define  STM_TIM234_SMCR_TS_MASK		7 +#define STM_TIM234_SMCR_OCCS	3 +#define STM_TIM234_SMCR_SMS	0 +#define  STM_TIM234_SMCR_SMS_DISABLE		0 +#define  STM_TIM234_SMCR_SMS_ENCODER_MODE_1	1 +#define  STM_TIM234_SMCR_SMS_ENCODER_MODE_2	2 +#define  STM_TIM234_SMCR_SMS_ENCODER_MODE_3	3 +#define  STM_TIM234_SMCR_SMS_RESET_MODE		4 +#define  STM_TIM234_SMCR_SMS_GATED_MODE		5 +#define  STM_TIM234_SMCR_SMS_TRIGGER_MODE	6 +#define  STM_TIM234_SMCR_SMS_EXTERNAL_CLOCK	7 +#define  STM_TIM234_SMCR_SMS_MASK		7 + +#define STM_TIM234_SR_CC4OF	12 +#define STM_TIM234_SR_CC3OF	11 +#define STM_TIM234_SR_CC2OF	10 +#define STM_TIM234_SR_CC1OF	9 +#define STM_TIM234_SR_TIF	6 +#define STM_TIM234_SR_CC4IF	4 +#define STM_TIM234_SR_CC3IF	3 +#define STM_TIM234_SR_CC2IF	2 +#define STM_TIM234_SR_CC1IF	1 +#define STM_TIM234_SR_UIF	0 + +#define STM_TIM234_EGR_TG	6 +#define STM_TIM234_EGR_CC4G	4 +#define STM_TIM234_EGR_CC3G	3 +#define STM_TIM234_EGR_CC2G	2 +#define STM_TIM234_EGR_CC1G	1 +#define STM_TIM234_EGR_UG	0 + +#define STM_TIM234_CCMR1_OC2CE	15 +#define STM_TIM234_CCMR1_OC2M	12 +#define  STM_TIM234_CCMR1_OC2M_FROZEN			0 +#define  STM_TIM234_CCMR1_OC2M_SET_HIGH_ON_MATCH	1 +#define  STM_TIM234_CCMR1_OC2M_SET_LOW_ON_MATCH		2 +#define  STM_TIM234_CCMR1_OC2M_TOGGLE			3 +#define  STM_TIM234_CCMR1_OC2M_FORCE_LOW		4 +#define  STM_TIM234_CCMR1_OC2M_FORCE_HIGH		5 +#define  STM_TIM234_CCMR1_OC2M_PWM_MODE_1		6 +#define  STM_TIM234_CCMR1_OC2M_PWM_MODE_2		7 +#define  STM_TIM234_CCMR1_OC2M_MASK			7 +#define STM_TIM234_CCMR1_OC2PE	11 +#define STM_TIM234_CCMR1_OC2FE	10 +#define STM_TIM234_CCMR1_CC2S	8 +#define  STM_TIM234_CCMR1_CC2S_OUTPUT			0 +#define  STM_TIM234_CCMR1_CC2S_INPUT_TI2		1 +#define  STM_TIM234_CCMR1_CC2S_INPUT_TI1		2 +#define  STM_TIM234_CCMR1_CC2S_INPUT_TRC		3 +#define  STM_TIM234_CCMR1_CC2S_MASK			3 + +#define STM_TIM234_CCMR1_OC1CE	7 +#define STM_TIM234_CCMR1_OC1M	4 +#define  STM_TIM234_CCMR1_OC1M_FROZEN			0 +#define  STM_TIM234_CCMR1_OC1M_SET_HIGH_ON_MATCH	1 +#define  STM_TIM234_CCMR1_OC1M_SET_LOW_ON_MATCH		2 +#define  STM_TIM234_CCMR1_OC1M_TOGGLE			3 +#define  STM_TIM234_CCMR1_OC1M_FORCE_LOW		4 +#define  STM_TIM234_CCMR1_OC1M_FORCE_HIGH		5 +#define  STM_TIM234_CCMR1_OC1M_PWM_MODE_1		6 +#define  STM_TIM234_CCMR1_OC1M_PWM_MODE_2		7 +#define  STM_TIM234_CCMR1_OC1M_MASK			7 +#define STM_TIM234_CCMR1_OC1PE	11 +#define STM_TIM234_CCMR1_OC1FE	2 +#define STM_TIM234_CCMR1_CC1S	0 +#define  STM_TIM234_CCMR1_CC1S_OUTPUT			0 +#define  STM_TIM234_CCMR1_CC1S_INPUT_TI1		1 +#define  STM_TIM234_CCMR1_CC1S_INPUT_TI2		2 +#define  STM_TIM234_CCMR1_CC1S_INPUT_TRC		3 +#define  STM_TIM234_CCMR1_CC1S_MASK			3 + +#define STM_TIM234_CCMR2_OC4CE	15 +#define STM_TIM234_CCMR2_OC4M	12 +#define  STM_TIM234_CCMR2_OC4M_FROZEN			0 +#define  STM_TIM234_CCMR2_OC4M_SET_HIGH_ON_MATCH	1 +#define  STM_TIM234_CCMR2_OC4M_SET_LOW_ON_MATCH		2 +#define  STM_TIM234_CCMR2_OC4M_TOGGLE			3 +#define  STM_TIM234_CCMR2_OC4M_FORCE_LOW		4 +#define  STM_TIM234_CCMR2_OC4M_FORCE_HIGH		5 +#define  STM_TIM234_CCMR2_OC4M_PWM_MODE_1		6 +#define  STM_TIM234_CCMR2_OC4M_PWM_MODE_2		7 +#define  STM_TIM234_CCMR2_OC4M_MASK			7 +#define STM_TIM234_CCMR2_OC4PE	11 +#define STM_TIM234_CCMR2_OC4FE	10 +#define STM_TIM234_CCMR2_CC4S	8 +#define  STM_TIM234_CCMR2_CC4S_OUTPUT			0 +#define  STM_TIM234_CCMR2_CC4S_INPUT_TI4		1 +#define  STM_TIM234_CCMR2_CC4S_INPUT_TI3		2 +#define  STM_TIM234_CCMR2_CC4S_INPUT_TRC		3 +#define  STM_TIM234_CCMR2_CC4S_MASK			3 + +#define STM_TIM234_CCMR2_OC3CE	7 +#define STM_TIM234_CCMR2_OC3M	4 +#define  STM_TIM234_CCMR2_OC3M_FROZEN			0 +#define  STM_TIM234_CCMR2_OC3M_SET_HIGH_ON_MATCH	1 +#define  STM_TIM234_CCMR2_OC3M_SET_LOW_ON_MATCH		2 +#define  STM_TIM234_CCMR2_OC3M_TOGGLE			3 +#define  STM_TIM234_CCMR2_OC3M_FORCE_LOW		4 +#define  STM_TIM234_CCMR2_OC3M_FORCE_HIGH		5 +#define  STM_TIM234_CCMR2_OC3M_PWM_MODE_1		6 +#define  STM_TIM234_CCMR2_OC3M_PWM_MODE_2		7 +#define  STM_TIM234_CCMR2_OC3M_MASK			7 +#define STM_TIM234_CCMR2_OC3PE	11 +#define STM_TIM234_CCMR2_OC3FE	2 +#define STM_TIM234_CCMR2_CC3S	0 +#define  STM_TIM234_CCMR2_CC3S_OUTPUT			0 +#define  STM_TIM234_CCMR2_CC3S_INPUT_TI3		1 +#define  STM_TIM234_CCMR2_CC3S_INPUT_TI4		2 +#define  STM_TIM234_CCMR2_CC3S_INPUT_TRC		3 +#define  STM_TIM234_CCMR2_CC3S_MASK			3 + +#define STM_TIM234_CCER_CC4NP	15 +#define STM_TIM234_CCER_CC4P	13 +#define STM_TIM234_CCER_CC4E	12 +#define STM_TIM234_CCER_CC3NP	11 +#define STM_TIM234_CCER_CC3P	9 +#define STM_TIM234_CCER_CC3E	8 +#define STM_TIM234_CCER_CC2NP	7 +#define STM_TIM234_CCER_CC2P	5 +#define STM_TIM234_CCER_CC2E	4 +#define STM_TIM234_CCER_CC1NP	3 +#define STM_TIM234_CCER_CC1P	1 +#define STM_TIM234_CCER_CC1E	0 + +struct stm_usb { +	struct { +		vuint16_t	r; +		uint16_t	_; +	} epr[8]; +	uint8_t		reserved_20[0x40 - 0x20]; +	vuint16_t	cntr; +	uint16_t	reserved_42; +	vuint16_t	istr; +	uint16_t	reserved_46; +	vuint16_t	fnr; +	uint16_t	reserved_4a; +	vuint16_t	daddr; +	uint16_t	reserved_4e; +	vuint16_t	btable; +	uint16_t	reserved_52; +	vuint16_t	lpmcsr; +	uint16_t	reserved_56; +	vuint16_t	bcdr; +	uint16_t	reserved_5a; +}; + +extern struct stm_usb stm_usb; + +#define STM_USB_EPR_CTR_RX	15 +#define  STM_USB_EPR_CTR_RX_WRITE_INVARIANT		1 +#define STM_USB_EPR_DTOG_RX	14 +#define STM_USB_EPR_DTOG_RX_WRITE_INVARIANT		0 +#define STM_USB_EPR_STAT_RX	12 +#define  STM_USB_EPR_STAT_RX_DISABLED			0 +#define  STM_USB_EPR_STAT_RX_STALL			1 +#define  STM_USB_EPR_STAT_RX_NAK			2 +#define  STM_USB_EPR_STAT_RX_VALID			3 +#define  STM_USB_EPR_STAT_RX_MASK			3 +#define  STM_USB_EPR_STAT_RX_WRITE_INVARIANT		0 +#define STM_USB_EPR_SETUP	11 +#define STM_USB_EPR_EP_TYPE	9 +#define  STM_USB_EPR_EP_TYPE_BULK			0 +#define  STM_USB_EPR_EP_TYPE_CONTROL			1 +#define  STM_USB_EPR_EP_TYPE_ISO			2 +#define  STM_USB_EPR_EP_TYPE_INTERRUPT			3 +#define  STM_USB_EPR_EP_TYPE_MASK			3 +#define STM_USB_EPR_EP_KIND	8 +#define  STM_USB_EPR_EP_KIND_DBL_BUF			1	/* Bulk */ +#define  STM_USB_EPR_EP_KIND_STATUS_OUT			1	/* Control */ +#define STM_USB_EPR_CTR_TX	7 +#define  STM_USB_CTR_TX_WRITE_INVARIANT			1 +#define STM_USB_EPR_DTOG_TX	6 +#define  STM_USB_EPR_DTOG_TX_WRITE_INVARIANT		0 +#define STM_USB_EPR_STAT_TX	4 +#define  STM_USB_EPR_STAT_TX_DISABLED			0 +#define  STM_USB_EPR_STAT_TX_STALL			1 +#define  STM_USB_EPR_STAT_TX_NAK			2 +#define  STM_USB_EPR_STAT_TX_VALID			3 +#define  STM_USB_EPR_STAT_TX_WRITE_INVARIANT		0 +#define  STM_USB_EPR_STAT_TX_MASK			3 +#define STM_USB_EPR_EA		0 +#define  STM_USB_EPR_EA_MASK				0xf + +#define STM_USB_CNTR_CTRM	15 +#define STM_USB_CNTR_PMAOVRM	14 +#define STM_USB_CNTR_ERRM	13 +#define STM_USB_CNTR_WKUPM	12 +#define STM_USB_CNTR_SUSPM	11 +#define STM_USB_CNTR_RESETM	10 +#define STM_USB_CNTR_SOFM	9 +#define STM_USB_CNTR_ESOFM	8 +#define STM_USB_CNTR_RESUME	4 +#define STM_USB_CNTR_FSUSP	3 +#define STM_USB_CNTR_LP_MODE	2 +#define STM_USB_CNTR_PDWN	1 +#define STM_USB_CNTR_FRES	0 + +#define STM_USB_ISTR_CTR	15 +#define STM_USB_ISTR_PMAOVR	14 +#define STM_USB_ISTR_ERR	13 +#define STM_USB_ISTR_WKUP	12 +#define STM_USB_ISTR_SUSP	11 +#define STM_USB_ISTR_RESET	10 +#define STM_USB_ISTR_SOF	9 +#define STM_USB_ISTR_ESOF	8 +#define STM_USB_L1REQ		7 +#define STM_USB_ISTR_DIR	4 +#define STM_USB_ISTR_EP_ID	0 +#define  STM_USB_ISTR_EP_ID_MASK		0xf + +#define STM_USB_FNR_RXDP	15 +#define STM_USB_FNR_RXDM	14 +#define STM_USB_FNR_LCK		13 +#define STM_USB_FNR_LSOF	11 +#define  STM_USB_FNR_LSOF_MASK			0x3 +#define STM_USB_FNR_FN		0 +#define  STM_USB_FNR_FN_MASK			0x7ff + +#define STM_USB_DADDR_EF	7 +#define STM_USB_DADDR_ADD	0 +#define  STM_USB_DADDR_ADD_MASK			0x7f + +#define STM_USB_BCDR_DPPU	15 +#define STM_USB_BCDR_PS2DET	7 +#define STM_USB_BCDR_SDET	6 +#define STM_USB_BCDR_PDET	5 +#define STM_USB_BCDR_DCDET	4 +#define STM_USB_BCDR_SDEN	3 +#define STM_USB_BCDR_PDEN	2 +#define STM_USB_BCDR_DCDEN	1 +#define STM_USB_BCDR_BCDEN	0 + +union stm_usb_bdt { +	struct { +		vuint16_t	addr_tx; +		vuint16_t	count_tx; +		vuint16_t	addr_rx; +		vuint16_t	count_rx; +	} single; +	struct { +		vuint16_t	addr; +		vuint16_t	count; +	} double_tx[2]; +	struct { +		vuint16_t	addr; +		vuint16_t	count; +	} double_rx[2]; +}; + +#define STM_USB_BDT_COUNT_RX_BL_SIZE	15 +#define STM_USB_BDT_COUNT_RX_NUM_BLOCK	10 +#define  STM_USB_BDT_COUNT_RX_NUM_BLOCK_MASK	0x1f +#define STM_USB_BDT_COUNT_RX_COUNT_RX	0 +#define  STM_USB_BDT_COUNT_RX_COUNT_RX_MASK	0x1ff + +#define STM_USB_BDT_SIZE	8 + +extern uint8_t stm_usb_sram[]; + +struct stm_exti { +	vuint32_t	imr; +	vuint32_t	emr; +	vuint32_t	rtsr; +	vuint32_t	ftsr; + +	vuint32_t	swier; +	vuint32_t	pr; +}; + +extern struct stm_exti stm_exti; + +#endif /* _STM32F0_H_ */  | 
