diff --git a/cpu/arm/stm32f103/Makefile.stm32f103 b/cpu/arm/stm32f103/Makefile.stm32f103 new file mode 100644 index 000000000..0eb80b216 --- /dev/null +++ b/cpu/arm/stm32f103/Makefile.stm32f103 @@ -0,0 +1,184 @@ +# Adapted from Makefile.msp430 + +# Default to STM32F103CB +SUBTARGET = CB + + +### Code common for all ARM CPUs + +CONTIKI_CPU_ARM=$(CONTIKI)/cpu/arm/ +CONTIKI_CPU_ARM_COMMON=$(CONTIKI_CPU_ARM)/common + +### Define the CPU directory +CONTIKI_CPU=$(CONTIKI_CPU_ARM)/stm32f103 + + +### Define the source files we have in the STM32F103 port + +CONTIKI_CPU_DIRS = . ../common/dbg-io ../common/usb loader + + + +STM32F103 = clock.c debug-uart.c # interrupt-utils.c newlib-syscalls.c sys-interrupt.c rtimer-arch.c rtimer-arch-interrupt.c uip-log.c + +# SYSAPPS = codeprop-otf.c +# APPDIRS += $(CONTIKI)/cpu/at91sam7s/loader + +# ELFLOADER = elfloader-otf.c elfloader-arm.c symtab.c cfs-ram.c + +include $(CONTIKI_CPU_ARM_COMMON)/usb/Makefile.usb + +include $(CONTIKI_CPU_ARM_COMMON)/SD-card/Makefile.sdcard + +TARGETLIBS = random.c dbg-printf.c dbg-puts.c dbg-putchar.c dbg-sprintf.c dbg-snprintf.c strformat.c + +CONTIKI_TARGET_SOURCEFILES += $(STM32F103) $(SYSAPPS) $(ELFLOADER) \ + $(TARGETLIBS) $(UIPDRIVERS) $(USB) + +CONTIKI_SOURCEFILES += $(CONTIKI_TARGET_SOURCEFILES) + + +THREADS = + +### Compiler definitions +CC = arm-elf-gcc +LD = arm-elf-ld +AS = arm-elf-as +AR = arm-elf-ar +NM = arm-elf-nm +OBJCOPY = arm-elf-objcopy +STRIP = arm-elf-strip + +XSLTPROC=xsltproc + +PROJECT_OBJECTFILES += ${addprefix $(OBJECTDIR)/,$(CONTIKI_TARGET_MAIN:.c=.o)} + +LINKERSCRIPT = $(CONTIKI_CPU)/STM32F103$(SUBTARGET).ld + +STARTUP=${addprefix $(OBJECTDIR)/,startup-STM32F10x.o} + +# JTAG program upload +OPENOCD = openocd +OPENOCD_DIR = $(CONTIKI_CPU_ARM)/openocd/ +OPENOCD_CFG = arm7_wig.cfg + +# USB program upload +SAMIAM=Sam_I_Am +SAMIAM_TTY=/dev/ttyACM0 + +ARCH_FLAGS= -march=armv7-m -mthumb + +CFLAGSNO = -I. -I$(CONTIKI)/core -I$(CONTIKI_CPU) -I$(CONTIKI_CPU)/loader \ + -I$(CONTIKI_CPU)/dbg-io \ + -I$(CONTIKI_CPU)/FWLib/FWLib/library/inc/ \ + -I$(CONTIKI)/platform/$(TARGET) \ + ${addprefix -I,$(APPDIRS)} \ + -DWITH_UIP -DWITH_ASCII -DMCK=$(MCK) \ + -Wall $(ARCH_FLAGS) -g -D SUBTARGET=$(SUBTARGET) + +CFLAGS += $(CFLAGSNO) -O -DRUN_AS_SYSTEM -DROM_RUN +LDFLAGS += -L $(CONTIKI_CPU) -T $(LINKERSCRIPT) -nostartfiles + +CDEPFLAGS = $(CFLAGS) -D __MAKING_DEPS__ + + + + +### Setup directory search path for source files + +CUSTOM_RULE_C_TO_OBJECTDIR_O=yes +CUSTOM_RULE_C_TO_O=yes + +%.o: %.c + $(CC) $(CFLAGS) $< -c + +$(OBJECTDIR)/%.o: %.c + $(CC) $(CFLAGS) -c $< -o $@ + + +CUSTOM_RULE_S_TO_OBJECTDIR_O = yes +%.o: %.S + $(CC) $(CFLAGS) $< -c + +$(OBJECTDIR)/%.o: %.S + $(CC) $(CFLAGS) $< -c -o $@ + + +CUSTOM_RULE_C_TO_CO=yes + +%.co: %.c + $(CC) $(CFLAGS) $< -c -o $@ + +CUSTOM_RULE_C_TO_CE=yes + +%.ce: %.o + $(LD) $(LDFLAGS) --relocatable -T $(CONTIKI_CPU)/merge-rodata.ld $< -o $@ + $(STRIP) -K _init -K _fini --strip-unneeded -g -x $@ + +CUSTOM_RULE_LINK=yes + +%-stripped.o: %.c + $(CC) $(CFLAGS) -c $< -o $@ + $(STRIP) --strip-unneeded -g -x $@ + +%-stripped.o: %.o + $(STRIP) --strip-unneeded -g -x -o $@ $< + +%.o: ${CONTIKI_TARGET}/loader/%.S + $(AS) -o $(notdir $(<:.S=.o)) $< + +%-nosyms.$(TARGET): %.co $(PROJECT_OBJECTFILES) contiki-$(TARGET).a $(STARTUP) # $(OBJECTDIR)/empty-symbols.o + $(CC) $(LDFLAGS) $(CFLAGS) -nostartfiles -o $@ $(filter-out %.a,$^) $(filter %.a,$^) -lc $(filter %.a,$^) + + +%.ihex: %.$(TARGET) + $(OBJCOPY) $^ -O ihex $@ + +%.bin: %.$(TARGET) + $(OBJCOPY) -O binary $< $@ + +.PHONY: symbols.c +ifdef CORE +%.$(TARGET): %.co $(PROJECT_OBJECTFILES) contiki-$(TARGET).a $(STARTUP) $(OBJECTDIR)/symbols.o + $(CC) $(LDFLAGS) $(CFLAGS) -nostartfiles -o $@ $(filter-out %.a,$^) $(filter %.a,$^) -lc $(filter %.a,$^) + +symbols.c: $(CORE) + $(NM) $< | awk -f $(CONTIKI_CPU)/builtins.awk -f ../../tools/mknmlist > symbols.c + +else +%.$(TARGET): %-nosyms.$(TARGET) + ln -sf $< $@ +endif + +empty-symbols.c: + @${CONTIKI}/tools/make-empty-symbols + + + + +upload_ocd_%: %.bin + # Clear lock bits + $(OPENOCD) -s $(OPENOCD_DIR) -f $(OPENOCD_CFG) -c init -c "reset halt;sleep 250;flash probe 0;stm32x mass_erase 0; sleep 500;flash write_bank 0 $< 0;reset halt;resume;sleep 500;exit" + + +upload_%: %.ihex + # Clear lock bits + $(SAMIAM) "open $(SAMIAM_TTY) , writew 0xffffff64 5a000004" + $(SAMIAM) "open $(SAMIAM_TTY) , writew 0xffffff64 5a002004" + $(SAMIAM) "open $(SAMIAM_TTY) , flash $< , go" + +ocd_reset: + $(OPENOCD) -s $(OPENOCD_DIR) -f $(OPENOCD_CFG) -c init -c "reset halt;resume" -c exit + +# Don't use core/loader/elfloader.c, use elfloader-otf.c instead +$(OBJECTDIR)/elfloader.o: + echo -n >$@ + +clean: clean_cpu + +.PHONY: stm32test_clean + +clean_cpu: + -rm -rf $(BUILTSRCDIR) + +.PRECIOUS: %-nosyms.$(TARGET) diff --git a/cpu/arm/stm32f103/STM32F103CB.ld b/cpu/arm/stm32f103/STM32F103CB.ld new file mode 100644 index 000000000..5335184d6 --- /dev/null +++ b/cpu/arm/stm32f103/STM32F103CB.ld @@ -0,0 +1,119 @@ +MEMORY +{ + CODE (rx) : ORIGIN = 0x8000000, LENGTH = 128K + DATA (xrw) : ORIGIN = 0x20000000, LENGTH = 20K +} + +/* Section Definitions */ + +SECTIONS +{ + +/* Make sure the vector table is at address 0 */ + +.vectrom : +{ + KEEP(*(.isr_vector)) +} >CODE =0 + +.text : +{ + KEEP(*(.init)) + *(.text .text.*) + KEEP(*(.fini)) +} >CODE =0 + +. = ALIGN(4); + +.rodata : + { + *(.rodata .rodata.*) + *(.gnu.linkonce.r.*) + } >CODE + + _etext = . ; + PROVIDE (etext = .); + + .data : + { + _data = . ; + *(.data) + _edata = . ; + PROVIDE (edata = .); + } >DATA AT >CODE + . = ALIGN(4); + + +/* .bss section which is used for uninitialized data */ + + .bss : + { + __bss_start = . ; + __bss_start__ = . ; + *(.bss) + *(COMMON) + __bss_end = . ; + __bss_end__ = . ; + *(.noinit) + } >DATA + . = ALIGN(4); + + _end = .; + PROVIDE (end = .); + +Main_Stack_Size = 0x00000200; +Process_Stack_Size = 0x00000200; + +Stack_Size = Main_Stack_Size + Process_Stack_Size; + .stack ORIGIN(DATA) + LENGTH(DATA) - Stack_Size : + { + __stack_start__ = . ; + Main_Stack_Start = . ; + . += Main_Stack_Size; + Main_Stack_End = . ; + Process_Stack_Start = . ; + . += Process_Stack_Size; + Process_Stack_End = . ; + . = ALIGN(4); + __stack_end__ = . ; + Top_Stack = .; + } >DATA + +__heap_start__ = __bss_end__ ; +__heap_end__ = __stack_start__ ; + + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/cpu/arm/stm32f103/debug-uart.c b/cpu/arm/stm32f103/debug-uart.c new file mode 100644 index 000000000..d8ff3d8b1 --- /dev/null +++ b/cpu/arm/stm32f103/debug-uart.c @@ -0,0 +1,184 @@ +#include +#include +#include +#include +#include +#include + +#ifndef DBG_UART +#define DBG_UART USART1 +#endif + +#ifndef DBG_DMA_NO +#define DBG_DMA_NO 1 +#endif + +#ifndef DBG_DMA_CHANNEL_NO +#define DBG_DMA_CHANNEL_NO 4 +#endif + + +#define _DBG_DMA_NAME(x) DMA##x +#define DBG_DMA_NAME(x) _DBG_DMA_NAME(x) +#define DBG_DMA DBG_DMA_NAME(DBG_DMA_NO) + +#define _DMA_CHANNEL_NAME(x,c) DMA ## x ## _Channel ## c +#define DMA_CHANNEL_NAME(x,c) _DMA_CHANNEL_NAME(x,c) +#define DBG_DMA_CHANNEL DMA_CHANNEL_NAME(DBG_DMA_NO, DBG_DMA_CHANNEL_NO) + +#define _DBG_DMA_CHANNEL_IFCR_CGIF(c) DMA_IFCR_CGIF ## c +#define _XDBG_DMA_CHANNEL_IFCR_CGIF(c) _DBG_DMA_CHANNEL_IFCR_CGIF(c) +#define DBG_DMA_CHANNEL_IFCR_CGIF \ +_XDBG_DMA_CHANNEL_IFCR_CGIF(DBG_DMA_CHANNEL_NO) + + +#ifndef DBG_XMIT_BUFFER_LEN +#define DBG_XMIT_BUFFER_LEN 1024 +#endif + + +static unsigned char xmit_buffer[DBG_XMIT_BUFFER_LEN]; +#define XMIT_BUFFER_END &xmit_buffer[DBG_XMIT_BUFFER_LEN] +void +dbg_setup_uart_default() +{ + RCC->APB2ENR |= (RCC_APB2ENR_AFIOEN + | RCC_APB2ENR_IOPAEN| RCC_APB2ENR_IOPBEN + | RCC_APB2ENR_USART1EN ); + RCC->AHBENR |= RCC_AHBENR_DMA1EN; + AFIO_REMAP( AFIO_MAPR_USART1_REMAP, AFIO_MAPR_USART1_REMAP); + GPIO_CONF_OUTPUT_PORT(B,6,ALT_PUSH_PULL,50); + GPIO_CONF_INPUT_PORT(B,7,FLOATING); + + USART1->CR1 = USART_CR1_UE; + + USART1->CR2 = 0; + USART1->CR3 = USART_CR3_DMAT; + USART1->CR1 |= USART_CR1_TE; + USART1->BRR= 0x1a1; +} + +/* Valid data in head to tail-1 */ +/* Read position */ +static unsigned char * volatile xmit_buffer_head = xmit_buffer; + +/* Write position */ +static unsigned char * volatile xmit_buffer_tail = xmit_buffer; + +/* xmit_buffer_head == xmit_buffer_tail means empty so we can only store + DBG_XMIT_BUFFER_LEN-1 characters */ + +volatile unsigned char dma_running = 0; +static unsigned char * volatile dma_end; +void +DMA1_Channel4_handler() __attribute__((interrupt)); + + +static void +update_dma(void) +{ + if (xmit_buffer_tail == xmit_buffer_head) return; + DBG_DMA_CHANNEL->CCR = (DMA_Priority_Low | + DMA_PeripheralDataSize_Byte | + DMA_MemoryDataSize_Byte | + DMA_PeripheralInc_Disable | + DMA_MemoryInc_Enable | + DMA_Mode_Normal | + DMA_DIR_PeripheralDST | + DMA_CCR4_TCIE + ); + DBG_DMA_CHANNEL->CPAR = (u32)&DBG_UART->DR; + DBG_DMA_CHANNEL->CMAR = (u32)xmit_buffer_head; + if (xmit_buffer_head < xmit_buffer_tail) { + DBG_DMA_CHANNEL->CNDTR = xmit_buffer_tail - xmit_buffer_head; + dma_end = xmit_buffer_tail; + } else { + DBG_DMA_CHANNEL->CNDTR = XMIT_BUFFER_END - xmit_buffer_head; + dma_end = xmit_buffer; + } + NVIC_ENABLE_INT(DMA1_Channel4_IRQChannel); + NVIC_SET_PRIORITY(DMA1_Channel4_IRQChannel, 2); + DBG_DMA_CHANNEL->CCR |=DMA_CCR4_EN; +} + + + +void +DMA1_Channel4_handler() +{ + DBG_DMA->IFCR = DBG_DMA_CHANNEL_IFCR_CGIF; + xmit_buffer_head = dma_end; + if (xmit_buffer_tail == xmit_buffer_head) { + dma_running = 0; + return; + } + update_dma(); +} + +unsigned int +dbg_send_bytes(const unsigned char *seq, unsigned int len) +{ + /* Since each of the pointers should be read atomically + there's no need to disable interrupts */ + unsigned char *head = xmit_buffer_head; + unsigned char *tail = xmit_buffer_tail; + if (tail >= head) { + /* Free space wraps */ + unsigned int xfer_len = XMIT_BUFFER_END - tail; + unsigned int free = DBG_XMIT_BUFFER_LEN - (tail - head) - 1; + if (len > free) len = free; + if (xfer_len < len) { + memcpy(tail, seq, xfer_len); + seq += xfer_len; + xfer_len = len - xfer_len; + memcpy(xmit_buffer, seq, xfer_len); + tail = xmit_buffer + xfer_len; + } else { + memcpy(tail, seq, len); + tail += len; + if (tail == XMIT_BUFFER_END) tail = xmit_buffer; + } + } else { + /* Free space continuous */ + unsigned int free = (head - tail) - 1; + if (len > free) len = free; + memcpy(tail, seq, len); + tail += len; + } + xmit_buffer_tail = tail; + if (!dma_running) { + dma_running = 1; + update_dma(); + } + return len; +} + +static unsigned char dbg_write_overrun = 0; + +void +dbg_putchar(const char ch) +{ + if (dbg_write_overrun) { + if (dbg_send_bytes((const unsigned char*)"^",1) != 1) return; + } + dbg_write_overrun = 0; + if (dbg_send_bytes((const unsigned char*)&ch,1) != 1) { + dbg_write_overrun = 1; + } +} + +void +dbg_blocking_putchar(const char ch) +{ + if (dbg_write_overrun) { + while (dbg_send_bytes((const unsigned char*)"^",1) != 1); + } + dbg_write_overrun = 0; + while (dbg_send_bytes((const unsigned char*)&ch,1) != 1); +} + +void +dbg_drain() +{ + while(xmit_buffer_tail != xmit_buffer_head); +} diff --git a/cpu/arm/stm32f103/debug-uart.h b/cpu/arm/stm32f103/debug-uart.h new file mode 100644 index 000000000..628e99e8f --- /dev/null +++ b/cpu/arm/stm32f103/debug-uart.h @@ -0,0 +1,27 @@ +#ifndef __DEBUG_UART_H__1V2039076V__ +#define __DEBUG_UART_H__1V2039076V__ + +#ifndef dbg_setup_uart +#define dbg_setup_uart dbg_setup_uart_default +#endif + +void +dbg_setup_uart(); + +void +dbg_set_input_handler(void (*handler)(const char *inp, unsigned int len)); + +unsigned int +dbg_send_bytes(const unsigned char *seq, unsigned int len); + + +void +dbg_putchar(const char ch); + +void +dbg_blocking_putchar(const char ch); + +void +dbg_drain(); + +#endif /* __DEBUG_UART_H__1V2039076V__ */ diff --git a/cpu/arm/stm32f103/gpio.h b/cpu/arm/stm32f103/gpio.h new file mode 100644 index 000000000..3e79d8779 --- /dev/null +++ b/cpu/arm/stm32f103/gpio.h @@ -0,0 +1,69 @@ +#ifndef __GPIO_H__LK7NAD1HN8__ +#define __GPIO_H__LK7NAD1HN8__ +#include + +#define _GPIO_INPUT_ANALOG(h,l) 0 + +#define _GPIO_INPUT_FLOATING(h,l) (l) + +#define _GPIO_INPUT_PU_PD(h,l) (h) + +#define _GPIO_OUTPUT_PUSH_PULL(h,l) 0 + +#define _GPIO_OUTPUT_OPEN_DRAIN(h,l) (l) + +#define _GPIO_OUTPUT_ALT_PUSH_PULL(h,l) (h) +#define _GPIO_OUTPUT_ALT_OPEN_DRAIN(h,l) ((h)|(l)) + +#define _GPIO_OUTPUT_SPEED_10(h,l) (l) +#define _GPIO_OUTPUT_SPEED_2(h,l) (h) +#define _GPIO_OUTPUT_SPEED_50(h,l) ((h)|(l)) + +#define _GPIO_INPUT_CNF(bit,mode) \ +_GPIO_INPUT_##mode(_GPIO_CONF_BIT_REG_##bit(GPIO_,_CNF##bit##_1),\ + _GPIO_CONF_BIT_REG_##bit(GPIO_,_CNF##bit##_0)) + +#define _GPIO_OUTPUT_CNF(bit,mode) \ +_GPIO_OUTPUT_##mode(_GPIO_CONF_BIT_REG_##bit(GPIO_,_CNF##bit##_1),\ + _GPIO_CONF_BIT_REG_##bit(GPIO_,_CNF##bit##_0)) + +#define _GPIO_OUTPUT_SPEED(bit,speed) \ +_GPIO_OUTPUT_SPEED_##speed(_GPIO_CONF_BIT_REG_##bit(GPIO_,_MODE##bit##_1),\ + _GPIO_CONF_BIT_REG_##bit(GPIO_,_MODE##bit##_0)) + +#define _GPIO_CONF_BIT_REG_0(a,c) a##CRL##c +#define _GPIO_CONF_BIT_REG_1(a,c) a##CRL##c +#define _GPIO_CONF_BIT_REG_2(a,c) a##CRL##c +#define _GPIO_CONF_BIT_REG_3(a,c) a##CRL##c +#define _GPIO_CONF_BIT_REG_4(a,c) a##CRL##c +#define _GPIO_CONF_BIT_REG_5(a,c) a##CRL##c +#define _GPIO_CONF_BIT_REG_6(a,c) a##CRL##c +#define _GPIO_CONF_BIT_REG_7(a,c) a##CRL##c +#define _GPIO_CONF_BIT_REG_8(a,c) a##CRH##c +#define _GPIO_CONF_BIT_REG_9(a,c) a##CRH##c +#define _GPIO_CONF_BIT_REG_10(a,c) a##CRH##c +#define _GPIO_CONF_BIT_REG_11(a,c) a##CRH##c +#define _GPIO_CONF_BIT_REG_12(a,c) a##CRH##c +#define _GPIO_CONF_BIT_REG_13(a,c) a##CRH##c +#define _GPIO_CONF_BIT_REG_14(a,c) a##CRH##c +#define _GPIO_CONF_BIT_REG_15(a,c) a##CRH##c + +#define _GPIO_CONF_BIT_REG(b) _GPIO_CONF_BIT_REG_##b(,) + + +#define _GPIO_CONF_MASK(bit) (_GPIO_CONF_BIT_REG_##bit(GPIO_,_CNF##bit) \ +|_GPIO_CONF_BIT_REG_##bit(GPIO_,_MODE##bit)) + +#define GPIO_CONF_INPUT_PORT(port,bit,mode) MODIFY_REG(GPIO##port -> _GPIO_CONF_BIT_REG(bit),_GPIO_CONF_MASK(bit), _GPIO_INPUT_CNF(bit,mode)) + + +#define GPIO_CONF_OUTPUT_PORT(port,bit,mode,speed) MODIFY_REG(GPIO##port -> _GPIO_CONF_BIT_REG(bit),_GPIO_CONF_MASK(bit), _GPIO_OUTPUT_CNF(bit,mode) | _GPIO_OUTPUT_SPEED(bit,speed)) + +#ifndef AFIO_MAPR_SWJ_CFG_VALUE +#define AFIO_MAPR_SWJ_CFG_VALUE AFIO_MAPR_SWJ_CFG_RESET +#endif + +#define AFIO_REMAP(mask,value) \ +MODIFY_REG(AFIO->MAPR, AFIO_MAPR_SWJ_CFG | mask, AFIO_MAPR_SWJ_CFG_VALUE | value); + +#endif /* __GPIO_H__LK7NAD1HN8__ */ diff --git a/cpu/arm/stm32f103/nvic.h b/cpu/arm/stm32f103/nvic.h new file mode 100644 index 000000000..cb32440e5 --- /dev/null +++ b/cpu/arm/stm32f103/nvic.h @@ -0,0 +1,16 @@ +#ifndef __NVIC_H__LE94F5JS4D__ +#define __NVIC_H__LE94F5JS4D__ +#include +#include + +#define NVIC_ENABLE_INT(i) WRITE_REG(NVIC->ISER[(i)/32], 1<<((i) & 0x1f)) +#define NVIC_DISABLE_INT(i) WRITE_REG(NVIC->ICER[(i)/32], 1<<((i) & 0x1f)) +#define NVIC_SET_PENDING(i) WRITE_REG(NVIC->ISPR[(i)/32], 1<<((i) & 0x1f)) +#define NVIC_CLEAR_PENDING(i) WRITE_REG(NVIC->ICPR[(i)/32], 1<<((i) & 0x1f)) + +#define NVIC_SET_PRIORITY(i,p) \ +MODIFY_REG(NVIC->IPR[(i)/4], 0xf<<(((i)&3)*8), (p)<<(((i)&3)*8)) + +#define NVIC_SET_SYSTICK_PRI(p) MODIFY_REG(SCB->SHPR[2], 0xf<<24, (p)<<24) + +#endif /* __NVIC_H__LE94F5JS4D__ */ diff --git a/cpu/arm/stm32f103/rtimer-arch.h b/cpu/arm/stm32f103/rtimer-arch.h new file mode 100644 index 000000000..cbd95b4e2 --- /dev/null +++ b/cpu/arm/stm32f103/rtimer-arch.h @@ -0,0 +1,19 @@ +/** + * \file + * Header file for the STM32F103-specific rtimer code + * \author + * Simon Berg + */ + +#ifndef __RTIMER_ARCH_H__ +#define __RTIMER_ARCH_H__ + +#include "sys/rtimer.h" + +#define RTIMER_ARCH_SECOND (MCK/1024) + +void rtimer_arch_set(rtimer_clock_t t); + +rtimer_clock_t rtimer_arch_now(void); + +#endif /* __RTIMER_ARCH_H__ */ diff --git a/cpu/arm/stm32f103/sdcard-arch.c b/cpu/arm/stm32f103/sdcard-arch.c new file mode 100644 index 000000000..348d48213 --- /dev/null +++ b/cpu/arm/stm32f103/sdcard-arch.c @@ -0,0 +1,359 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +process_event_t sdcard_inserted_event; + +process_event_t sdcard_removed_event; + +static struct process *event_process = NULL; + +#if 0 +#undef TXT +#define TXT(x) x +#undef DBG +#define DBG(x) printf x +#endif + +static void +init_spi() +{ + SPI1->CR1 &= ~SPI_CR1_SPE; + RCC->APB2ENR |= RCC_APB2ENR_IOPAEN; + GPIO_CONF_INPUT_PORT(A,0,FLOATING); + GPIO_CONF_INPUT_PORT(A,1,FLOATING); + GPIO_CONF_OUTPUT_PORT(A,4,PUSH_PULL,50); + GPIOA->BSRR = GPIO_BSRR_BS4; + GPIO_CONF_OUTPUT_PORT(A,5,ALT_PUSH_PULL,50); + GPIO_CONF_INPUT_PORT(A,6,FLOATING); + GPIO_CONF_OUTPUT_PORT(A,7,ALT_PUSH_PULL,50); + RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; + SPI1->CR2 = SPI_CR2_SSOE; + SPI1->CR1 = (SPI_CR1_SPE + | (SPI_CR1_BR_2) /* fPCLK / 32 */ + | SPI_CR1_MSTR + | SPI_CR1_CPOL | SPI_CR1_CPHA + | SPI_CR1_SSM | SPI_CR1_SSI); + +} + +void +if_spiInit(hwInterface *iface) +{ + unsigned int i; + GPIOA->BSRR = GPIO_BSRR_BS4; + for(i=0;i<20;i++) { + if_spiSend(iface, 0xff); + } + GPIOA->BSRR = GPIO_BSRR_BR4; +} +/* Borrowed from at91_spi.c (c)2006 Martin Thomas */ + +esint8 +if_initInterface(hwInterface* file, eint8* opts) +{ + euint32 sc; + if_spiInit(file); + if(sd_Init(file)<0) { + DBG((TXT("Card failed to init, breaking up...\n"))); + return(-1); + } + + if(sd_State(file)<0){ + DBG((TXT("Card didn't return the ready state, breaking up...\n") + )); + return(-2); + } + + + + sd_getDriveSize(file, &sc); + file->sectorCount = sc/512; + DBG((TXT("Card Capacity is %lu Bytes (%lu Sectors)\n"), sc, file->sectorCount)); + + + return(0); +} + +/* Borrowed from lpc2000_spi.c (c)2005 Martin Thomas */ + +esint8 +if_readBuf(hwInterface* file,euint32 address,euint8* buf) +{ + return(sd_readSector(file,address,buf,512)); +} + +esint8 +if_writeBuf(hwInterface* file,euint32 address,euint8* buf) +{ + return(sd_writeSector(file,address, buf)); +} + +esint8 +if_setPos(hwInterface* file,euint32 address) +{ + return(0); +} + + +euint8 +if_spiSend(hwInterface *iface, euint8 outgoing) +{ + euint8 ingoing; + SPI1->DR = outgoing; + while(!(SPI1->SR & SPI_SR_RXNE)); + ingoing = SPI1->DR; + /* printf(">%02x <%02x\n", outgoing, ingoing); */ + return ingoing; +} + +#define MAX_FDS 4 + +static EmbeddedFileSystem sdcard_efs; +static File file_descriptors[MAX_FDS]; + +static int +find_free_fd() +{ + int fd; + for (fd = 0; fd < MAX_FDS; fd++) { + if (!file_getAttr(&file_descriptors[fd], FILE_STATUS_OPEN)) { + return fd; + } + } + return -1; +} + +static File * +get_file(int fd) +{ + if (sdcard_efs.myCard.sectorCount == 0) return NULL; + if (fd >= MAX_FDS || fd < 0) return NULL; + if (!file_getAttr(&file_descriptors[fd], FILE_STATUS_OPEN)) return NULL; + return &file_descriptors[fd]; +} + +int +cfs_open (const char *name, int flags) +{ + eint8 mode; + int fd; + if (sdcard_efs.myCard.sectorCount == 0) return -1; + fd = find_free_fd(); + if (fd < 0) return -1; + if (flags == CFS_READ) { + mode = MODE_READ; + } else { + mode = MODE_APPEND; + } + if (file_fopen(&file_descriptors[fd], &sdcard_efs.myFs, + (char*)name, mode) < 0) { + return -1; + } + return fd; +} + +void +cfs_close(int fd) +{ + File *file = get_file(fd); + if (!file) return; + file_fclose(file); + fs_flushFs(&sdcard_efs.myFs); +} + +int +cfs_read (int fd, void *buf, unsigned int len) +{ + File *file = get_file(fd); + if (!file) return 0; + return file_read(file, len, (euint8*)buf); +} + +int +cfs_write (int fd, const void *buf, unsigned int len) +{ + File *file = get_file(fd); + if (!file) return 0; + return file_write(file, len, (euint8*)buf); +} + +cfs_offset_t +cfs_seek (int fd, cfs_offset_t offset, int whence) +{ + File *file = get_file(fd); + if (!file) return 0; + /* TODO take whence int account */ + if (file_setpos(file, offset) != 0) return -1; + return file->FilePtr; +} + +int +cfs_remove(const char *name) +{ + return (rmfile(&sdcard_efs.myFs,(euint8*)name) == 0) ? 0 : -1; +} + +/* Cause a compile time error if expr is false */ +#ifdef __GNUC__ +#define COMPILE_TIME_CHECK(expr) \ +(void) (__builtin_choose_expr ((expr), 0, ((void)0))+3) +#else +#define COMPILE_TIME_CHECK(expr) +#endif + +#define MAX_DIR_LISTS 4 +DirList dir_lists[MAX_DIR_LISTS]; + +static DirList * +find_free_dir_list() +{ + unsigned int l; + for(l = 0; l < MAX_DIR_LISTS; l++) { + if (dir_lists[l].fs == NULL) { + return &dir_lists[l]; + } + } + return NULL; +} + +int +cfs_opendir (struct cfs_dir *dirp, const char *name) +{ + DirList *dirs; + COMPILE_TIME_CHECK(sizeof(DirList*) <= sizeof(struct cfs_dir)); + if (sdcard_efs.myCard.sectorCount == 0) return -1; + dirs = find_free_dir_list(); + if (!dirs) return -1; + if (ls_openDir(dirs, &sdcard_efs.myFs, (eint8*)name) != 0) { + dirs->fs = NULL; + return -1; + } + *(DirList**)dirp = dirs; + return 0; +} + +int +cfs_readdir (struct cfs_dir *dirp, struct cfs_dirent *dirent) +{ + euint8 *start; + euint8 *end; + char *to = dirent->name; + DirList *dirs = *(DirList**)dirp; + if (sdcard_efs.myCard.sectorCount == 0) return 1; + if (ls_getNext(dirs) != 0) return 1; + start = dirs->currentEntry.FileName; + end = start + 7; + while(end > start) { + if (*end > ' ') { + end++; + break; + } + end--; + } + while(start < end) { + *to++ = *start++; + } + start = dirs->currentEntry.FileName + 8; + end = start + 3; + if (*start > ' ') { + *to++ = '.'; + *to++ = *start++; + while(start < end && *start > ' ') { + *to++ = *start++; + } + } + *to = '\0'; + if (dirs->currentEntry.Attribute & ATTR_DIRECTORY) { + dirent->size = 0; + } else { + dirent->size = dirs->currentEntry.FileSize; + } + return 0; +} + +void +cfs_closedir (struct cfs_dir *dirp) +{ + (*(DirList**)dirp)->fs = NULL; +} + + +PROCESS(sdcard_process, "SD card process"); + +PROCESS_THREAD(sdcard_process, ev , data) +{ + int fd; + static struct etimer timer; + PROCESS_BEGIN(); + /* Mark all file descriptors as free */ + for (fd = 0; fd < MAX_FDS; fd++) { + file_setAttr(&file_descriptors[fd], FILE_STATUS_OPEN,0); + } + /* Card not inserted */ + sdcard_efs.myCard.sectorCount = 0; + init_spi(); + + etimer_set(&timer, CLOCK_SECOND); + while(1) { + PROCESS_WAIT_EVENT_UNTIL(ev == PROCESS_EVENT_EXIT || + ev== PROCESS_EVENT_TIMER || ev == PROCESS_EVENT_POLL); + if (ev == PROCESS_EVENT_EXIT) break; + if (ev == PROCESS_EVENT_TIMER) { + if (!(GPIOA->IDR & (1<<0))) { + if (sdcard_efs.myCard.sectorCount == 0) { + etimer_set(&timer,CLOCK_SECOND/2); + PROCESS_WAIT_EVENT_UNTIL(ev== PROCESS_EVENT_TIMER); + if (efs_init(&sdcard_efs,0) == 0) { + if (event_process) { + process_post(event_process, sdcard_inserted_event, NULL); + } + printf("SD card inserted\n"); + } else { + printf("SD card insertion failed\n"); + } + } + } else { + if (sdcard_efs.myCard.sectorCount != 0) { + /* Card removed */ + fs_umount(&sdcard_efs.myFs); + sdcard_efs.myCard.sectorCount = 0; + if (event_process) { + process_post(event_process, sdcard_removed_event, NULL); + } + printf("SD card removed\n"); + } + } + etimer_set(&timer, CLOCK_SECOND); + + } + } + PROCESS_END(); +} + +void +sdcard_init() +{ + sdcard_inserted_event = process_alloc_event(); + sdcard_removed_event = process_alloc_event(); + process_start(&sdcard_process, NULL); +} + +int +sdcard_ready() +{ + return sdcard_efs.myCard.sectorCount > 0; +} + +void +sdcard_event_process(struct process *p) +{ + event_process = p; +} diff --git a/cpu/arm/stm32f103/startup-STM32F10x.c b/cpu/arm/stm32f103/startup-STM32F10x.c new file mode 100644 index 000000000..4e6f602aa --- /dev/null +++ b/cpu/arm/stm32f103/startup-STM32F10x.c @@ -0,0 +1,284 @@ +#include +#include + + +extern int main(void); + +typedef void (*ISR_func)(void); + + +#define SECTION(x) __attribute__ ((section(#x))) +#define ISR_VECTOR_SECTION SECTION(.isr_vector) +static void sys_reset(void) __attribute__((naked)); +void NMI_handler(void) __attribute__((interrupt)); +void HardFault_handler(void) __attribute__((interrupt)); +void MemManage_handler(void) __attribute__((interrupt)); +void BusFault_handler(void) __attribute__((interrupt)); +void UsageFault_handler(void) __attribute__((interrupt)); + +static void unhandled_int(void) __attribute__((interrupt)); + +#define UNHANDLED_ALIAS __attribute__((weak, alias("unhandled_int"))); +void Main_Stack_End(void); +void HardFault_handler(void)__attribute__((weak, alias("dHardFault_handler"))); +void MemManage_handler(void)__attribute__((weak, alias("dMemManage_handler"))); +void BusFault_handler(void) __attribute__((weak, alias("dBusFault_handler"))); +void UsageFault_handler(void)__attribute__((weak, alias("dUsageFault_handler"))); + void Reserved_handler(void) UNHANDLED_ALIAS; + void SVCall_handler(void) UNHANDLED_ALIAS; + void DebugMonitor_handler(void) UNHANDLED_ALIAS; + void PendSV_handler(void) UNHANDLED_ALIAS; + void SysTick_handler(void) UNHANDLED_ALIAS; + void WWDG_handler(void) UNHANDLED_ALIAS; + void PVD_handler(void) UNHANDLED_ALIAS; + void TAMPER_handler(void) UNHANDLED_ALIAS; + void RTC_handler(void) UNHANDLED_ALIAS; + void FLASH_handler(void) UNHANDLED_ALIAS; + void RCC_handler(void) UNHANDLED_ALIAS; + void EXTI0_handler(void) UNHANDLED_ALIAS; + void EXTI1_handler(void) UNHANDLED_ALIAS; + void EXTI2_handler(void) UNHANDLED_ALIAS; + void EXTI3_handler(void) UNHANDLED_ALIAS; + void EXTI4_handler(void) UNHANDLED_ALIAS; + void DMA1_Channel1_handler(void) UNHANDLED_ALIAS; + void DMA1_Channel2_handler(void) UNHANDLED_ALIAS; + void DMA1_Channel3_handler(void) UNHANDLED_ALIAS; + void DMA1_Channel4_handler(void) UNHANDLED_ALIAS; + void DMA1_Channel5_handler(void) UNHANDLED_ALIAS; + void DMA1_Channel6_handler(void) UNHANDLED_ALIAS; + void DMA1_Channel7_handler(void) UNHANDLED_ALIAS; + void ADC1_2_handler(void) UNHANDLED_ALIAS; + void USB_HP_CAN_TX_handler(void) UNHANDLED_ALIAS; + void USB_LP_CAN_RX0_handler(void) UNHANDLED_ALIAS; + void CAN_RX1_handler(void) UNHANDLED_ALIAS; + void CAN_SCE_handler(void) UNHANDLED_ALIAS; + void EXTI9_5_handler(void) UNHANDLED_ALIAS; + void TIM1_BRK_handler(void) UNHANDLED_ALIAS; + void TIM1_UP_handler(void) UNHANDLED_ALIAS; + void TIM1_TRG_COM_handler(void) UNHANDLED_ALIAS; + void TIM1_CC_handler(void) UNHANDLED_ALIAS; + void TIM2_handler(void) UNHANDLED_ALIAS; + void TIM3_handler(void) UNHANDLED_ALIAS; + void TIM4_handler(void) UNHANDLED_ALIAS; + void I2C1_EV_handler(void) UNHANDLED_ALIAS; + void I2C1_ER_handler(void) UNHANDLED_ALIAS; + void I2C2_EV_handler(void) UNHANDLED_ALIAS; + void I2C2_ER_handler(void) UNHANDLED_ALIAS; + void SPI1_handler(void) UNHANDLED_ALIAS; + void SPI2_handler(void) UNHANDLED_ALIAS; + void USART1_handler(void) UNHANDLED_ALIAS; + void USART2_handler(void) UNHANDLED_ALIAS; + void USART3_handler(void) UNHANDLED_ALIAS; + void EXTI15_10_handler(void) UNHANDLED_ALIAS; + void RTCAlarm_handler(void) UNHANDLED_ALIAS; + void USBWakeup_handler(void) UNHANDLED_ALIAS; + void TIM8_BRK_handler(void) UNHANDLED_ALIAS; + void TIM8_UP_handler(void) UNHANDLED_ALIAS; + void TIM8_TRG_COM_handler(void) UNHANDLED_ALIAS; + void TIM8_CC_handler(void) UNHANDLED_ALIAS; + void ADC3_handler(void) UNHANDLED_ALIAS; + void FSMC_handler(void) UNHANDLED_ALIAS; + void SDIO_handler(void) UNHANDLED_ALIAS; + void TIM5_handler(void) UNHANDLED_ALIAS; + void SPI3_handler(void) UNHANDLED_ALIAS; + void UART4_handler(void) UNHANDLED_ALIAS; + void UART5_handler(void) UNHANDLED_ALIAS; + void TIM6_handler(void) UNHANDLED_ALIAS; + void TIM7_handler(void) UNHANDLED_ALIAS; + void DMA2_Channel1_handler(void) UNHANDLED_ALIAS; + void DMA2_Channel2_handler(void) UNHANDLED_ALIAS; + void DMA2_Channel3_handler(void) UNHANDLED_ALIAS; + void DMA2_Channel4_5_handler(void) UNHANDLED_ALIAS; + +const ISR_func isr_vector[76] ISR_VECTOR_SECTION = + { + Main_Stack_End, + sys_reset, + NMI_handler, + HardFault_handler, + MemManage_handler, + BusFault_handler, + UsageFault_handler, + Reserved_handler, + Reserved_handler, + Reserved_handler, + Reserved_handler, + SVCall_handler, + DebugMonitor_handler, + Reserved_handler, + PendSV_handler, + SysTick_handler, + WWDG_handler, + PVD_handler, + TAMPER_handler, + RTC_handler, + FLASH_handler, + RCC_handler, + EXTI0_handler, + EXTI1_handler, + EXTI2_handler, + EXTI3_handler, + EXTI4_handler, + DMA1_Channel1_handler, + DMA1_Channel2_handler, + DMA1_Channel3_handler, + DMA1_Channel4_handler, + DMA1_Channel5_handler, + DMA1_Channel6_handler, + DMA1_Channel7_handler, + ADC1_2_handler, + USB_HP_CAN_TX_handler, + USB_LP_CAN_RX0_handler, + CAN_RX1_handler, + CAN_SCE_handler, + EXTI9_5_handler, + TIM1_BRK_handler, + TIM1_UP_handler, + TIM1_TRG_COM_handler, + TIM1_CC_handler, + TIM2_handler, + TIM3_handler, + TIM4_handler, + I2C1_EV_handler, + I2C1_ER_handler, + I2C2_EV_handler, + I2C2_ER_handler, + SPI1_handler, + SPI2_handler, + USART1_handler, + USART2_handler, + USART3_handler, + EXTI15_10_handler, + RTCAlarm_handler, + USBWakeup_handler, + TIM8_BRK_handler, + TIM8_UP_handler, + TIM8_TRG_COM_handler, + TIM8_CC_handler, + ADC3_handler, + FSMC_handler, + SDIO_handler, + TIM5_handler, + SPI3_handler, + UART4_handler, + UART5_handler, + TIM6_handler, + TIM7_handler, + DMA2_Channel1_handler, + DMA2_Channel2_handler, + DMA2_Channel3_handler, + DMA2_Channel4_5_handler + }; + + + + +extern uint8_t _data[]; +extern uint8_t _etext[]; +extern uint8_t _edata[]; + +static void +copy_initialized(void) +{ + uint8_t *ram = _data; + uint8_t *rom = _etext; + while(ram < _edata) { + *ram++ = *rom++; + } +} + +extern uint8_t __bss_start[]; +extern uint8_t __bss_end[]; + +static void +clear_bss(void) +{ + uint8_t *m = __bss_start; + while(m < __bss_end) { + *m++ = 0; + } +} + +static void +start_hse_clock(void) +{ + /* Start external oscillator */ + RCC->CR |= RCC_CR_HSEON; + /* Wait for oscillator to stabilize */ + while(!(RCC->CR & RCC_CR_HSERDY)); +} + +static void +use_pll() +{ + RCC->CFGR = (RCC_CFGR_MCO_NOCLOCK + | RCC_CFGR_PLLMULL6 /* PLL at 48MHz */ + | RCC_CFGR_PLLSRC /* PLL runs on HSE */ + | RCC_CFGR_PPRE2_DIV1 /* APB2 at 48MHz */ + | RCC_CFGR_PPRE1_DIV2 /* APB1 at 24MHz */ + | RCC_CFGR_HPRE_DIV1 /* AHB at 48 MHz */ + | RCC_CFGR_USBPRE /* USB clock at same speed as PLL */ + ); + RCC->CR |= RCC_CR_PLLON; + /* Wait for PLL */ + while(!(RCC->CR & RCC_CR_PLLRDY)); + /* Switch to PLL as system clock */ + MODIFY_REG(RCC->CFGR, RCC_CFGR_SW,RCC_CFGR_SW_PLL); +} + +static void +enable_fault_exceptions(void) +{ + SCB->SHCSR |= (SCB_SHCSR_MEMFAULTENA | SCB_SHCSR_BUSFAULTENA + | SCB_SHCSR_USGFAULTENA); +} + +static void +sys_reset(void) +{ + copy_initialized(); + clear_bss(); + enable_fault_exceptions(); + start_hse_clock(); + use_pll(); + main(); + while(1); + +} + +void +NMI_handler(void) +{ + while(1); +} + + +static void +unhandled_int(void) +{ + while(1); +} + +static void +dHardFault_handler(void) +{ + while(1); +} + +static void +dUsageFault_handler(void) +{ + while(1); +} + +static void +dMemManage_handler(void) +{ + while(1); +} + +static void +dBusFault_handler(void) +{ + while(1); +} diff --git a/cpu/arm/stm32f103/stm32f10x_conf.h b/cpu/arm/stm32f103/stm32f10x_conf.h new file mode 100644 index 000000000..34213bcea --- /dev/null +++ b/cpu/arm/stm32f103/stm32f10x_conf.h @@ -0,0 +1,27 @@ +#define _RCC +#define _DMA +#define _GPIOA +#define _GPIOB +#define _GPIOC +#define _BKP +#define _AFIO +#define _USART1 +#define _NVIC +#define _SysTick +#define _USB +#define _TIM2 +#define _TIM3 +#define _DMA1_Channel1 +#define _DMA1_Channel2 +#define _DMA1_Channel3 +#define _DMA1_Channel4 +#define _DMA1_Channel5 +#define _DMA1_Channel6 +#define _DMA2_Channel1 +#define _DMA2_Channel2 +#define _DMA2_Channel3 +#define _DMA2_Channel4 +#define _DMA2_Channel5 +#define _SPI1 +#define _SPI2 +#define _EXTI diff --git a/cpu/arm/stm32f103/usb-arch.c b/cpu/arm/stm32f103/usb-arch.c new file mode 100644 index 000000000..c7bbd802c --- /dev/null +++ b/cpu/arm/stm32f103/usb-arch.c @@ -0,0 +1,1184 @@ +#include +#include +#include +#include +#include +#include + +/* #define DEBUG */ +#ifdef DEBUG +#define PRINTF(...) printf(__VA_ARGS__) +#else +#define PRINTF(...) +#endif +typedef struct +{ + vu32 EPR[8]; + u32 RESERVED[8]; + vu32 CNTR; + vu32 ISTR; + vu32 FNR; + vu32 DADDR; + vu32 BTABLE; +} USB_TypeDef; + +#define USB_BASE (APB1PERIPH_BASE + 0x5c00) +#define USB_MEM_BASE (APB1PERIPH_BASE + 0x6000) +#define USB_MEM_SIZE (512) +#define USB ((volatile USB_TypeDef *) USB_BASE) + +typedef struct { + vu32 ADDR_TX; + vu32 COUNT_TX; + vu32 ADDR_RX; + vu32 COUNT_RX; +} USB_HW_Buffer; + +#define USB_EP0_BUF_SIZE (2*CTRL_EP_SIZE) + +#define USB_EP1_BUF_SIZE (2*USB_EP1_SIZE) + +#define USB_EP2_BUF_SIZE (2*USB_EP2_SIZE) + +#define USB_EP3_BUF_SIZE (2*USB_EP3_SIZE) + +#define USB_EP4_BUF_SIZE (2*USB_EP4_SIZE) + +#define USB_EP5_BUF_SIZE (2*USB_EP5_SIZE) + +#define USB_EP6_BUF_SIZE (2*USB_EP6_SIZE) + +#define USB_EP7_BUF_SIZE (2*USB_EP7_SIZE) + + + +#ifndef MAX_CTRL_DATA +#define MAX_CTRL_DATA 128 +#endif +/* Double buffered IN endpoint */ +#define ADDR_TX_0 ADDR_TX +#define ADDR_TX_1 ADDR_RX +#define COUNT_TX_0 COUNT_TX +#define COUNT_TX_1 COUNT_RX + +/* Double buffered OUT endpoint */ +#define ADDR_RX_0 ADDR_TX +#define ADDR_RX_1 ADDR_RX +#define COUNT_RX_0 COUNT_TX +#define COUNT_RX_1 COUNT_RX + +#define USB_EPxR_EP_TYPE_BULK 0 +#define USB_EPxR_EP_TYPE_CONTROL USB_EP0R_EP_TYPE_0 +#define USB_EPxR_EP_TYPE_ISO USB_EP0R_EP_TYPE_1 +#define USB_EPxR_EP_TYPE_INTERRUPT (USB_EP0R_EP_TYPE_1|USB_EP0R_EP_TYPE_0) + +#define USB_EPxR_EP_DBL_BUF USB_EP0R_EP_KIND +#define USB_EPxR_EP_STATUS_OUT USB_EP0R_EP_KIND + +#define USB_EPxR_STAT_RX_DISABLED 0 +#define USB_EPxR_STAT_RX_STALL USB_EP0R_STAT_RX_0 +#define USB_EPxR_STAT_RX_NAK USB_EP0R_STAT_RX_1 +#define USB_EPxR_STAT_RX_VALID (USB_EP0R_STAT_RX_1|USB_EP0R_STAT_RX_0) + +#define USB_EPxR_STAT_TX_DISABLED 0 +#define USB_EPxR_STAT_TX_STALL USB_EP0R_STAT_TX_0 +#define USB_EPxR_STAT_TX_NAK USB_EP0R_STAT_TX_1 +#define USB_EPxR_STAT_TX_VALID (USB_EP0R_STAT_TX_1|USB_EP0R_STAT_TX_0) + +#define USB_EPxR_SW_BUF_TX USB_EP0R_DTOG_RX +#define USB_EPxR_SW_BUF_RX USB_EP0R_DTOG_TX + +static const uint16_t ep_buffer_size[8] = + { + USB_EP0_BUF_SIZE, + USB_EP1_BUF_SIZE, + USB_EP2_BUF_SIZE, + USB_EP3_BUF_SIZE, + USB_EP4_BUF_SIZE, + USB_EP5_BUF_SIZE, + USB_EP6_BUF_SIZE, + USB_EP7_BUF_SIZE + }; + +#define USB_EP_BUF_SIZE(ep) ep_buffer_size[ep] +#define USB_EP_BUF_OFFSET(ep) ep_buffer_offset[ep] +#define USB_EP_BUF_ADDR(ep) (u32*)(USB_MEM_BASE + ep_buffer_offset[ep]*2); +#define USB_EP_BUF_DESC(ep) ((USB_HW_Buffer*)(USB_MEM_BASE + 16 * (ep))) + +#define USB_EP0_OFFSET (8*USB_MAX_ENDPOINTS) +#define USB_EP1_OFFSET (USB_EP0_OFFSET + USB_EP0_BUF_SIZE) +#define USB_EP2_OFFSET (USB_EP1_OFFSET + USB_EP1_BUF_SIZE) +#define USB_EP3_OFFSET (USB_EP2_OFFSET + USB_EP2_BUF_SIZE) +#define USB_EP4_OFFSET (USB_EP3_OFFSET + USB_EP3_BUF_SIZE) +#define USB_EP5_OFFSET (USB_EP4_OFFSET + USB_EP4_BUF_SIZE) +#define USB_EP6_OFFSET (USB_EP5_OFFSET + USB_EP5_BUF_SIZE) +#define USB_EP7_OFFSET (USB_EP6_OFFSET + USB_EP6_BUF_SIZE) + +#if (USB_EP7_OFFSET+USB_EP7_BUF_SIZE) > USB_MEM_SIZE +#error USB endpoints buffers does not fit in USB memory +#endif +static const uint16_t ep_buffer_offset[8] = + { + USB_EP0_OFFSET, + USB_EP1_OFFSET, + USB_EP2_OFFSET, + USB_EP3_OFFSET, + USB_EP4_OFFSET, + USB_EP5_OFFSET, + USB_EP6_OFFSET, + USB_EP7_OFFSET + }; + +#define USB_EP_BUF_CAPACITY(s) ((((s) <64)?((s)/2):(0x20 | ((s)/64)))<<10) + +typedef struct _USBEndpoint USBEndpoint; +struct _USBEndpoint +{ + uint16_t status; + uint8_t addr; + uint8_t flags; + USBBuffer *buffer; /* NULL if no current buffer */ + struct process *event_process; + uint16_t events; + uint16_t xfer_size; +}; + +#define USB_EP_FLAGS_TYPE_MASK 0x03 +#define USB_EP_FLAGS_TYPE_BULK 0x00 +#define USB_EP_FLAGS_TYPE_CONTROL 0x01 +#define USB_EP_FLAGS_TYPE_ISO 0x02 +#define USB_EP_FLAGS_TYPE_INTERRUPT 0x03 + +#define IS_EP_TYPE(ep, type) (((ep)->flags & USB_EP_FLAGS_TYPE_MASK) == (type)) +#define IS_CONTROL_EP(ep) IS_EP_TYPE(ep, USB_EP_FLAGS_TYPE_CONTROL) +#define IS_BULK_EP(ep) IS_EP_TYPE(ep, USB_EP_FLAGS_TYPE_BULK) +#define IS_INTERRUPT_EP(ep) IS_EP_TYPE(ep, USB_EP_FLAGS_TYPE_INTERRUPT) + +#define USB_EP_FLAGS_ENABLED 0x04 + +/* A packet has been received but the data is still in hardware buffer */ +#define USB_EP_FLAGS_RECV_PENDING 0x08 +/* The pending packet is a SETUP packet */ +#define USB_EP_FLAGS_SETUP_PENDING 0x10 + +/* The data in the hardware buffer is being transmitted */ +#define USB_EP_FLAGS_TRANSMITTING 0x20 + +/* The receiver is waiting for a packet */ +#define USB_EP_FLAGS_RECEIVING 0x40 + +/* For bulk endpoints. Both buffers are busy are in use, either by + hardware or software. */ +#define USB_EP_FLAGS_DOUBLE 0x80 + +/* States for double buffered reception: + +Packets being received 0 1 2 1 0 0 +Packets pending 0 0 0 1 2 1 + +RECVING 0 1 1 1 0 0 +RECV_PENDING 0 0 0 1 1 1 +DOUBLE 0 0 1 0 1 0 +*/ + +/* States for double buffered transmission: + +Packets being transmitted 0 1 2 + +TRANSMITTING 0 1 1 +DOUBLE 0 0 1 +*/ + +/* Index in endpoint array */ +#define EP_INDEX(addr) ((addr) & 0x7f) + +/* Get address of endpoint struct */ +#define EP_STRUCT(addr) (&usb_endpoints[EP_INDEX(addr)]) + +/* Number of hardware endpoint */ +#define EP_HW_NUM(addr) ((addr) & 0x7f) + +#define USB_DISABLE_INT \ + NVIC_DISABLE_INT(USB_LP_CAN_RX0_IRQChannel);\ + NVIC_DISABLE_INT(USB_HP_CAN_TX_IRQChannel) + +#define USB_ENABLE_INT \ + NVIC_ENABLE_INT(USB_LP_CAN_RX0_IRQChannel);\ + NVIC_ENABLE_INT(USB_HP_CAN_TX_IRQChannel) + +static inline uint32_t +usb_save_disable_int() +{ + uint32_t v = NVIC->ISER[0]; + NVIC->ICER[0] = (1<ISER[0] = + v & (1<events |= e; + if (ep->event_process) { + process_poll(ep->event_process); + } +} + + +static void +usb_arch_reset(void) +{ + unsigned int e; + for (e = 0; e < USB_MAX_ENDPOINTS; e++) { + if (usb_endpoints[e].flags &USB_EP_FLAGS_ENABLED) { + USBBuffer *buffer = usb_endpoints[e].buffer; + usb_endpoints[e].flags = 0; + while(buffer) { + buffer->flags &= ~USB_BUFFER_SUBMITTED; + buffer = buffer->next; + } + } + } + usb_arch_setup_control_endpoint(0); + USB->DADDR = 0x80; +} + +void +usb_arch_setup(void) +{ + unsigned int i; + RCC->APB1RSTR |= RCC_APB1RSTR_USBRST; + RCC->APB2ENR |= (RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPAEN); + RCC->APB1ENR |= (RCC_APB1ENR_USBEN); + RCC->APB1RSTR &= ~RCC_APB1RSTR_USBRST; + + GPIO_CONF_OUTPUT_PORT(A,11,ALT_PUSH_PULL,50); + GPIO_CONF_OUTPUT_PORT(A,12,ALT_PUSH_PULL,50); + GPIO_CONF_OUTPUT_PORT(A,10, PUSH_PULL, 2); + GPIOA->BSRR = GPIO_BSRR_BR10; + + /* Turn on analog part */ + USB->CNTR &= ~USB_CNTR_PDWN; + + for (i = 0; i < 24; i++) asm("nop"::); /* Wait at least 1us */ + /* Release reset */ + USB->CNTR &= ~USB_CNTR_FRES; + /* Clear any interrupts */ + USB->ISTR = ~(USB_ISTR_PMAOVR |USB_ISTR_ERR | USB_ISTR_WKUP | USB_ISTR_SUSP + | USB_ISTR_RESET); + + for(i = 0; i < USB_MAX_ENDPOINTS; i++) { + usb_endpoints[i].flags = 0; + usb_endpoints[i].event_process = 0; + } + /* Put buffer table at beginning of buffer memory */ + USB->BTABLE = 0; + usb_arch_reset(); + GPIOA->BSRR = GPIO_BSRR_BS10; + USB->CNTR |= (USB_CNTR_CTRM | USB_CNTR_PMAOVRM | USB_CNTR_ERRM + | USB_CNTR_WKUPM| USB_CNTR_SUSPM | USB_CNTR_RESETM); + NVIC_SET_PRIORITY(USB_LP_CAN_RX0_IRQChannel, 4); + NVIC_ENABLE_INT(USB_LP_CAN_RX0_IRQChannel); +} + +#define EPR_RW (USB_EP0R_EP_TYPE|USB_EP0R_EP_KIND|USB_EP0R_EA) +#define EPR_W0 (USB_EP0R_CTR_RX|USB_EP0R_CTR_TX) +#define EPR_TOGGLE (USB_EP0R_DTOG_RX | USB_EP0R_STAT_RX \ + | USB_EP0R_DTOG_TX | USB_EP0R_STAT_TX) + +#define EPR_INVARIANT(epr) ((epr & (EPR_RW)) | EPR_W0) + +#define EPR_TOGGLE_SET(epr, mask, set) \ +((((epr) & (EPR_RW | (mask))) | EPR_W0) ^ (set)) + +static void +usb_arch_setup_endpoint(unsigned char addr) +{ + USBEndpoint *ep = EP_STRUCT(addr); + ep->status = 0; + ep->flags = USB_EP_FLAGS_ENABLED; + ep->buffer = 0; + ep->addr = addr; + ep->events = 0; + ep->xfer_size = 0; +}; + +void +usb_arch_setup_control_endpoint(unsigned char addr) +{ + USB_HW_Buffer *buf_desc; + unsigned int ei = EP_HW_NUM(addr); + unsigned int epr; + USBEndpoint *ep = EP_STRUCT(addr); + usb_arch_setup_endpoint(addr); + ep->flags |= USB_EP_FLAGS_TYPE_CONTROL; + + buf_desc = USB_EP_BUF_DESC(ei); + buf_desc->ADDR_TX = USB_EP_BUF_OFFSET(ei); + buf_desc->COUNT_TX = USB_EP_BUF_SIZE(ei)/2; + buf_desc->ADDR_RX = USB_EP_BUF_OFFSET(ei) + USB_EP_BUF_SIZE(ei)/2; + buf_desc->COUNT_RX = USB_EP_BUF_CAPACITY(USB_EP_BUF_SIZE(ei)/2); + ep->xfer_size = USB_EP_BUF_SIZE(ei)/2; + epr = USB->EPR[EP_HW_NUM(addr)]; + /* Clear interrupt flags */ + epr &= ~(USB_EP0R_CTR_RX | USB_EP0R_CTR_TX); + /* NACK both directions */ + epr ^= USB_EPxR_STAT_RX_NAK | USB_EPxR_STAT_TX_NAK; + /* Set control type */ + epr = ((epr & ~(USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND)) + | USB_EPxR_EP_TYPE_CONTROL); + /* Set address */ + epr = ((epr & ~USB_EP0R_EA) | addr); + USB->EPR[EP_HW_NUM(addr)] = epr; +} + +void +usb_arch_setup_bulk_endpoint(unsigned char addr) +{ + USB_HW_Buffer *buf_desc; + unsigned int ei = EP_HW_NUM(addr); + unsigned int epr; + USBEndpoint *ep = EP_STRUCT(addr); + usb_arch_setup_endpoint(addr); + ep->flags |= USB_EP_FLAGS_TYPE_BULK; + + buf_desc = USB_EP_BUF_DESC(ei); + buf_desc->ADDR_TX = USB_EP_BUF_OFFSET(ei); + buf_desc->ADDR_RX = USB_EP_BUF_OFFSET(ei) + USB_EP_BUF_SIZE(ei)/2; + epr = USB->EPR[ei]; + if (addr & 0x80) { + /* IN */ + buf_desc->COUNT_TX_0 = 0; + buf_desc->COUNT_TX_1 = 0; + /* VALID transmission */ + epr ^= USB_EPxR_STAT_TX_VALID; + } else { + /* OUT */ + buf_desc->COUNT_RX_0 = USB_EP_BUF_CAPACITY(USB_EP_BUF_SIZE(ei)/2); + buf_desc->COUNT_RX_1 = USB_EP_BUF_CAPACITY(USB_EP_BUF_SIZE(ei)/2); + + /* VALID reception */ + epr ^= USB_EPxR_STAT_RX_VALID; + } + ep->xfer_size = USB_EP_BUF_SIZE(ei)/2; + /* Clear interrupt flags */ + epr &= ~(USB_EP0R_CTR_RX | USB_EP0R_CTR_TX); + /* Set bulk type */ + epr = ((epr & ~(USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND)) + | USB_EPxR_EP_TYPE_BULK | USB_EPxR_EP_DBL_BUF); + /* Set address */ + epr = ((epr & ~USB_EP0R_EA) | addr); + USB->EPR[ei] = epr; + +} + +void +usb_arch_setup_interrupt_endpoint(unsigned char addr) +{ + USB_HW_Buffer *buf_desc; + unsigned int ei = EP_HW_NUM(addr); + unsigned int epr; + USBEndpoint *ep = EP_STRUCT(addr); + usb_arch_setup_endpoint(addr); + ep->flags |= USB_EP_FLAGS_TYPE_INTERRUPT; + + epr = USB->EPR[EP_HW_NUM(addr)]; + + buf_desc = USB_EP_BUF_DESC(ei); + if (addr & 0x80) { + /* IN */ + buf_desc->ADDR_TX = USB_EP_BUF_OFFSET(ei); + buf_desc->COUNT_TX = USB_EP_BUF_SIZE(ei); + epr ^= USB_EPxR_STAT_TX_NAK; + } else { + /* OUT */ + buf_desc->ADDR_RX = USB_EP_BUF_OFFSET(ei); + buf_desc->COUNT_RX = USB_EP_BUF_CAPACITY(USB_EP_BUF_SIZE(ei)); + epr ^= USB_EPxR_STAT_RX_NAK; + } + ep->xfer_size = USB_EP_BUF_SIZE(ei); + /* Clear interrupt flags */ + epr &= ~(USB_EP0R_CTR_RX | USB_EP0R_CTR_TX); + /* Set control type */ + epr = ((epr & ~(USB_EP0R_EP_TYPE | USB_EP0R_EP_KIND)) + | USB_EPxR_EP_TYPE_INTERRUPT); + /* Set address */ + epr = ((epr & ~USB_EP0R_EA) | addr); + USB->EPR[EP_HW_NUM(addr)] = epr; +} + +void +usb_arch_disable_endpoint(uint8_t addr) +{ + unsigned int epr; + USBEndpoint *ep = EP_STRUCT(addr); + ep->flags &= ~USB_EP_FLAGS_ENABLED; + + epr = USB->EPR[EP_HW_NUM(addr)]; + + epr ^= USB_EPxR_STAT_TX_DISABLED | USB_EPxR_STAT_RX_DISABLED; + /* Clear interrupt flags */ + epr &= ~(USB_EP0R_CTR_RX | USB_EP0R_CTR_TX); + USB->EPR[EP_HW_NUM(addr)] = epr; +} + +inline void +stall_bulk_in(unsigned int hw_ep) +{ + volatile uint32_t *eprp = &USB->EPR[hw_ep]; + *eprp = (*eprp & (EPR_RW | USB_EP0R_STAT_TX_1)) | EPR_W0; + PRINTF("HALT IN\n"); +} + +inline void +stall_bulk_out(unsigned int hw_ep) +{ + volatile uint32_t *eprp = &USB->EPR[hw_ep]; + *eprp = (*eprp & ((EPR_RW | USB_EP0R_STAT_RX_1) & ~USB_EP0R_CTR_RX)) |EPR_W0; + PRINTF("HALT OUT\n"); +} + + +#define USB_READ_BLOCK 0x01 /* The currently submitted buffers + can't hold the received data, wait + for more buffers. No data was read + from the hardware buffer */ +#define USB_READ_NOTIFY 0x02 /* Some buffers that had the + USB_BUFFER_NOTIFY flags set were + released */ +#define USB_READ_FAIL 0x04 /* The received data doesn't match the + submitted buffers. The hardware + buffer is discarded. */ + +inline unsigned int +ep_capacity(unsigned int count) +{ + return (((count & USB_COUNT0_RX_NUM_BLOCK)>>10) + * ((count & USB_COUNT0_RX_BLSIZE) ? 32 : 2)); +} + +/* Skip buffers until mask and flags matches*/ +static USBBuffer * +skip_buffers_until(USBBuffer *buffer, unsigned int mask, unsigned int flags, + unsigned int *resp) +{ + while(buffer && !((buffer->flags & mask) == flags)) { + USBBuffer *next = buffer->next; + buffer->flags &= ~USB_BUFFER_SUBMITTED ; + buffer->flags |= USB_BUFFER_FAILED; + if (buffer->flags & USB_BUFFER_NOTIFY) *resp |= USB_READ_NOTIFY; + buffer = next; + } + return buffer; +} + +static void +read_hw_buffer(USBBuffer *buffer, unsigned int offset, unsigned int len) +{ +#ifdef USB_STM32F103_ENABLE_ALT_COPY + if (buffer->flags & USB_BUFFER_ARCH_ALT_COPY) { + copy_from_hw_buffer(buffer, offset, len); + } else +#endif + { + uint8_t *data = buffer->data; + const uint32_t *hw_data = ((u32*)USB_MEM_BASE) + offset/2; + buffer->data += len; + if (offset & 1) { + *data++ = *hw_data++ >> 8; + len--; + } + while(len >= 2) { + *((uint16_t*)data) = *hw_data++; + data += 2; + len -= 2; + } + if (len == 1) { + *data++ = *hw_data; + } + } +} + + +#define USB_WRITE_BLOCK 0x01 +#define USB_WRITE_NOTIFY 0x02 + +static void +write_hw_buffer(USBBuffer *buffer,unsigned int offset, unsigned int len) +{ +#ifdef USB_STM32F103_ENABLE_ALT_COPY + if (buffer->flags & USB_BUFFER_ARCH_ALT_COPY) { + copy_to_hw_buffer(buffer, offset, len); + } else +#endif + { + const uint8_t *data = buffer->data; + uint32_t *hw_data = ((u32*)USB_MEM_BASE) + offset/2; + buffer->data += len; + if (offset & 1) { + *hw_data = (*hw_data & 0xff) | (*data++ << 8); + hw_data++; + len--; + } + while(len >= 2) { + *hw_data++ = *((uint16_t*)data) ; + data += 2; + len -= 2; + } + if (len == 1) { + *hw_data = *data++; + } + } +} + +static unsigned int +get_receive_capacity(USBBuffer *buffer) +{ + unsigned int capacity = 0; + while(buffer && !(buffer->flags & (USB_BUFFER_IN| USB_BUFFER_SETUP))) { + capacity += buffer->left; + buffer = buffer->next; + } + return capacity; +} + +static int +handle_pending_receive(USBEndpoint *ep) +{ + int short_packet; + unsigned int len; + unsigned int copy; + unsigned int res = 0; + unsigned int hw_offset; + unsigned int hw_ep = EP_HW_NUM(ep->addr); + USBBuffer *buffer = ep->buffer; + unsigned int flags = ep->flags; + USB_HW_Buffer *buf_desc = USB_EP_BUF_DESC(hw_ep); + PRINTF("handle_pending_receive:\n"); + if (!(flags & USB_EP_FLAGS_ENABLED) || !buffer) return USB_READ_BLOCK; + switch(flags & USB_EP_FLAGS_TYPE_MASK) { + case USB_EP_FLAGS_TYPE_CONTROL: + len = buf_desc->COUNT_RX & USB_COUNT0_RX_COUNT0_RX; + if (flags & USB_EP_FLAGS_SETUP_PENDING) { + /* Discard buffers until we find a SETUP buffer */ + buffer = + skip_buffers_until(buffer, USB_BUFFER_SETUP, USB_BUFFER_SETUP, &res); + ep->buffer = buffer; + if (!buffer || buffer->left < len) { + res |= USB_READ_BLOCK; + return res; + } + /* SETUP buffer must fit in a single buffer */ + if (buffer->left < len) { + buffer->flags |= USB_BUFFER_FAILED; + buffer->flags &= ~USB_BUFFER_SUBMITTED ; + if (buffer->flags & USB_BUFFER_NOTIFY) res |= USB_READ_NOTIFY; + ep->buffer = buffer->next; + res |= USB_READ_FAIL; + return res; + } + } else { + if (buffer->flags & (USB_BUFFER_SETUP|USB_BUFFER_IN)) { + buffer->flags |= USB_BUFFER_FAILED; + + buffer->flags &= ~USB_BUFFER_SUBMITTED ; + if (buffer->flags & USB_BUFFER_NOTIFY) res |= USB_READ_NOTIFY; + ep->buffer = buffer->next; + res |= USB_READ_FAIL; + return res; + } + + if (len == 0) { + /* Status OUT */ + if (buffer->left > 0) { + buffer->flags |= USB_BUFFER_FAILED; + res |= USB_READ_FAIL; + } + buffer->flags &= ~USB_BUFFER_SUBMITTED ; + if (buffer->flags & USB_BUFFER_NOTIFY) res |= USB_READ_NOTIFY; + ep->buffer = buffer->next; + return res; + } + if (get_receive_capacity(buffer) < len) return USB_READ_BLOCK; + } + hw_offset = buf_desc->ADDR_RX; + break; + case USB_EP_FLAGS_TYPE_INTERRUPT: + len = buf_desc->COUNT_RX & USB_COUNT0_RX_COUNT0_RX; + if (get_receive_capacity(buffer) < len) return USB_READ_BLOCK; + hw_offset = buf_desc->ADDR_RX; + break; + case USB_EP_FLAGS_TYPE_BULK: + if (USB->EPR[hw_ep] & USB_EPxR_SW_BUF_RX) { + len = buf_desc->COUNT_RX_1 & USB_COUNT0_RX_COUNT0_RX; + hw_offset = buf_desc->ADDR_RX_1; + } else { + len = buf_desc->COUNT_RX_0 & USB_COUNT0_RX_COUNT0_RX; + hw_offset = buf_desc->ADDR_RX_0; + } + if (get_receive_capacity(buffer) < len) return USB_READ_BLOCK; + break; + case USB_EP_FLAGS_TYPE_ISO: + len = buf_desc->COUNT_RX & USB_COUNT0_RX_COUNT0_RX; + if (get_receive_capacity(buffer) < len) return USB_READ_BLOCK; + hw_offset = buf_desc->ADDR_RX; + } + /* printf("handle_pending_receive: %d %04x\n", len, ep->flags); */ + short_packet = len < ep->xfer_size; + + do { + if (buffer->left < len) { + copy = buffer->left; + } else { + copy = len; + } + len -= copy; + buffer->left -= copy; + read_hw_buffer(buffer, hw_offset, copy); + hw_offset += copy; + + if (len == 0) break; + + /* Release buffer */ + buffer->flags &= ~(USB_BUFFER_SUBMITTED | USB_BUFFER_SHORT_PACKET); + if (buffer->flags & USB_BUFFER_NOTIFY) res |= USB_READ_NOTIFY; + /* Use next buffer. */ + buffer = buffer->next; + } while(1); + + if (short_packet) { + buffer->flags |= USB_BUFFER_SHORT_PACKET; + } + + if ((buffer->left == 0) + || (buffer->flags & USB_BUFFER_PACKET_END) + || (short_packet && (buffer->flags & USB_BUFFER_SHORT_END))) { + /* Release buffer */ + buffer->flags &= ~USB_BUFFER_SUBMITTED; + if (buffer->flags & USB_BUFFER_NOTIFY) res |= USB_READ_NOTIFY; + /* Use next buffer. */ + buffer = buffer->next; + } + + ep->buffer = buffer; + if (IS_BULK_EP(ep)) { + USB->EPR[hw_ep] = EPR_INVARIANT(USB->EPR[hw_ep]) | USB_EPxR_SW_BUF_RX; + } + + /* PRINTF("read_endpoint %d %d\n", (int)hw_offset-buf_desc->ADDR_RX, (int)buf_desc->ADDR_RX); */ + return res; +} + + +static void +start_receive(USBEndpoint *ep) +{ + unsigned int hw_ep = EP_HW_NUM(ep->addr); + uint32_t epr = (USB->EPR[hw_ep] | EPR_W0); + uint32_t epr_mask = EPR_RW | EPR_W0; + switch(ep->flags & USB_EP_FLAGS_TYPE_MASK) { + case USB_EP_FLAGS_TYPE_CONTROL: + case USB_EP_FLAGS_TYPE_INTERRUPT: + { + unsigned int capacity = get_receive_capacity(ep->buffer); + if (capacity <= ep->xfer_size) { + /* This is the last OUT packet of the data stage */ + epr ^= USB_EPxR_STAT_TX_NAK; + } else { + epr ^= USB_EPxR_STAT_TX_STALL; + } + epr ^= USB_EPxR_STAT_RX_VALID; + epr_mask |= USB_EP0R_STAT_TX | USB_EP0R_STAT_RX; + } + break; + case USB_EP_FLAGS_TYPE_BULK: + case USB_EP_FLAGS_TYPE_ISO: + break; + } + ep->flags |= USB_EP_FLAGS_RECEIVING; + USB->EPR[hw_ep] = epr & epr_mask; +} + +static unsigned int +get_transmit_length(USBBuffer *buffer) +{ + unsigned int length = 0; + while(buffer && (buffer->flags & USB_BUFFER_IN)) { + length += buffer->left; + buffer = buffer->next; + } + return length; +} + +static int +start_transmit(USBEndpoint *ep) +{ + unsigned int hw_start; + unsigned int res = 0; + USBBuffer *buffer = ep->buffer; + unsigned int len; + unsigned int hw_offset; + volatile uint32_t *hw_countp; + unsigned int hw_ep = EP_HW_NUM(ep->addr); + uint32_t epr = USB->EPR[hw_ep]; + unsigned int ep_flags = ep->flags; + USB_HW_Buffer *buf_desc = USB_EP_BUF_DESC(hw_ep); + len = ep->xfer_size; + if (!(ep_flags & USB_EP_FLAGS_ENABLED) || !buffer) return USB_WRITE_BLOCK; + /* PRINTF("start_transmit: %02x\n", ep->addr); */ + switch(ep_flags & USB_EP_FLAGS_TYPE_MASK) { + case USB_EP_FLAGS_TYPE_CONTROL: + + if (get_transmit_length(ep->buffer) <= len) { + /* This is the last IN packet of the data stage */ + USB->EPR[hw_ep] = USB_EPxR_EP_STATUS_OUT + | EPR_TOGGLE_SET(epr, USB_EP0R_STAT_RX, USB_EPxR_STAT_RX_NAK); + } else { + USB->EPR[hw_ep] = USB_EPxR_EP_STATUS_OUT + | EPR_TOGGLE_SET(epr, USB_EP0R_STAT_RX, USB_EPxR_STAT_RX_STALL); + } + hw_offset = buf_desc->ADDR_TX; + hw_countp = &buf_desc->COUNT_TX; + break; + case USB_EP_FLAGS_TYPE_BULK: + if (buffer->flags & USB_BUFFER_HALT) { + if (ep->status & 0x01) return USB_READ_BLOCK; + ep->status |= 0x01; + stall_bulk_in(hw_ep); + return USB_READ_BLOCK; + } + if (USB->EPR[hw_ep] & USB_EPxR_SW_BUF_TX) { + hw_offset = buf_desc->ADDR_TX_1; + hw_countp = &buf_desc->COUNT_TX_1; + } else { + hw_offset = buf_desc->ADDR_TX_0; + hw_countp = &buf_desc->COUNT_TX_0; + } + break; + } + hw_start = hw_offset; + while (buffer) { + unsigned int copy; + if (buffer->left < len) { + copy = buffer->left; + } else { + copy = len; + } + len -= copy; + buffer->left -= copy; + write_hw_buffer(buffer, hw_offset, copy); + hw_offset += copy; + if (buffer->left == 0) { + if (buffer->flags & USB_BUFFER_SHORT_END) { + if (len == 0) { + /* Avoid endless loop */ + buffer->flags &= ~USB_BUFFER_SHORT_END; + /* Send zero length packet. */ + break; + } else { + len = 0; + } + } + /* Release buffer */ + buffer->flags &= ~USB_BUFFER_SUBMITTED; + if (buffer->flags & USB_BUFFER_NOTIFY) res = USB_WRITE_NOTIFY; + /* Use next buffer. */ + buffer = buffer->next; + } + if (len == 0) break; + } + ep->buffer = buffer; + if (ep->flags & USB_EP_FLAGS_TRANSMITTING) { + ep->flags |= USB_EP_FLAGS_DOUBLE; + } else { + ep->flags |= USB_EP_FLAGS_TRANSMITTING; + } + *hw_countp = hw_offset - hw_start; + /* printf("start_transmit: %02x %d %04lx\n", ep->addr, hw_offset - hw_start, USB->EPR[hw_ep]); */ + switch(ep->flags & USB_EP_FLAGS_TYPE_MASK) { + case USB_EP_FLAGS_TYPE_CONTROL: + case USB_EP_FLAGS_TYPE_INTERRUPT: + USB->EPR[hw_ep] = + EPR_TOGGLE_SET(epr, USB_EP0R_STAT_TX, USB_EPxR_STAT_TX_VALID); + break; + case USB_EP_FLAGS_TYPE_BULK: + USB->EPR[hw_ep] = EPR_INVARIANT(USB->EPR[hw_ep]) | USB_EPxR_SW_BUF_TX; + break; + case USB_EP_FLAGS_TYPE_ISO: + break; + } +/* printf("start_transmit: %04x\n", USB->EPR[hw_ep]); */ + return res; +} + +static void +start_transfer(USBEndpoint *ep) +{ + int res; + while (1) { + if (!(ep->addr & 0x80) && (IS_BULK_EP(ep) || IS_INTERRUPT_EP(ep))) { + if (ep->buffer && (ep->buffer->flags & USB_BUFFER_HALT)) { + if (ep->status & 0x01) return ; + ep->status |= 0x01; + stall_bulk_out(EP_HW_NUM(ep->addr)); + return; + } + } + if (!(ep->flags & USB_EP_FLAGS_RECV_PENDING)) break; + res = handle_pending_receive(ep); + if (res & USB_READ_NOTIFY) { + notify_ep_process(ep, USB_EP_EVENT_NOTIFICATION); + } + if (res & USB_READ_BLOCK) return; + if (ep->flags & USB_EP_FLAGS_DOUBLE) { + ep->flags &= ~USB_EP_FLAGS_DOUBLE; + } else { + ep->flags &= ~(USB_EP_FLAGS_RECV_PENDING|USB_EP_FLAGS_SETUP_PENDING); + } + if (res & USB_READ_FAIL) { + /* Only fails for control endpoints */ + usb_arch_control_stall(ep->addr); + return; + } + } + if (ep->addr == 0x02) + PRINTF("start EPR: %04x ep->flags: %02x\n", + (unsigned int)USB->EPR[EP_HW_NUM(ep->addr)], + (unsigned int)ep->flags); + if (ep->flags & (USB_EP_FLAGS_TRANSMITTING | USB_EP_FLAGS_RECEIVING)) { + if (!IS_BULK_EP(ep) || (ep->flags & USB_EP_FLAGS_DOUBLE)) { + PRINTF("Busy\n"); + return; + } + } + if (ep->status & 0x01) return; /* Don't start transfer if halted */ + if (ep->buffer) { + if (ep->buffer->flags & USB_BUFFER_IN) { + res = start_transmit(ep); + if (res & USB_READ_NOTIFY) { + notify_ep_process(ep, USB_EP_EVENT_NOTIFICATION); + } + } else { + start_receive(ep); + } + } +} + + +static void +transfer_complete(unsigned int hw_ep) { + uint32_t epr = USB->EPR[hw_ep]; + USBEndpoint *ep = &usb_endpoints[hw_ep]; + if (epr &USB_EP0R_CTR_RX) { + PRINTF("Received packet %lx %04x\n", USB_EP_BUF_DESC(hw_ep)->COUNT_RX, (int)USB->EPR[hw_ep]); + if (epr & USB_EP0R_SETUP) { + PRINTF("SETUP\n"); + ep->flags |= USB_EP_FLAGS_SETUP_PENDING; + } + + if (IS_BULK_EP(ep)) { + if ((epr ^ (epr >> 8)) & USB_EP0R_DTOG_TX) { + ep->flags &= ~USB_EP_FLAGS_DOUBLE; + } else { + ep->flags |= USB_EP_FLAGS_DOUBLE; + ep->flags &= ~USB_EP_FLAGS_RECEIVING; + } + } else { + ep->flags &= ~USB_EP_FLAGS_RECEIVING; + } + ep->flags |= USB_EP_FLAGS_RECV_PENDING; + if (IS_CONTROL_EP(ep)) epr &= ~USB_EPxR_EP_STATUS_OUT; + USB->EPR[hw_ep] = EPR_INVARIANT(epr) & ~USB_EP0R_CTR_RX; +#if 0 + if (ep->flags & USB_EP_FLAGS_DOUBLE) { + printf("Double\n"); + } +#endif + + start_transfer(ep); + } + if (epr &USB_EP0R_CTR_TX) { + PRINTF("Sent packet\n"); + if (ep->flags & USB_EP_FLAGS_DOUBLE) { + ep->flags &= ~USB_EP_FLAGS_DOUBLE; + } else { + ep->flags &= ~USB_EP_FLAGS_TRANSMITTING; + } + USB->EPR[hw_ep] = EPR_INVARIANT(USB->EPR[hw_ep]) & ~USB_EP0R_CTR_TX; + start_transfer(ep); + } + +} + + +void +usb_set_ep_event_process(unsigned char addr, struct process *p) +{ + USBEndpoint *ep = &usb_endpoints[EP_INDEX(addr)]; + ep->event_process = p; +} + +/* Select what process should be polled when a global event occurs */ +void +usb_arch_set_global_event_process(struct process *p) +{ + event_process = p; +} + +unsigned int +usb_arch_get_global_events(void) +{ + unsigned int e; + USB_DISABLE_INT; + e = events; + events = 0; + USB_DISABLE_INT; + return e; +} + +unsigned int +usb_get_ep_events(unsigned char addr) +{ + unsigned int e; + unsigned int ei = EP_HW_NUM(addr); + USB_DISABLE_INT; + e = usb_endpoints[ei].events; + usb_endpoints[ei].events = 0; + USB_ENABLE_INT; + return e; +} + + +void +usb_submit_recv_buffer(unsigned char ep_addr, USBBuffer *buffer) +{ + USBBuffer **tailp; + USBEndpoint *ep = &usb_endpoints[EP_INDEX(ep_addr)]; + if (!(ep->flags & USB_EP_FLAGS_ENABLED)) return; + /* PRINTF("buffer: %p\n", ep->buffer); */ + /* dbg_drain(); */ + USB_DISABLE_INT; + tailp = (USBBuffer**)&ep->buffer; + while(*tailp) { + tailp = &(*tailp)->next; + } + *tailp = buffer; + while(buffer) { + buffer->flags |= USB_BUFFER_SUBMITTED; + buffer = buffer->next; + } + start_transfer(ep); + + USB_ENABLE_INT; +} + +void +usb_submit_xmit_buffer(unsigned char ep_addr, USBBuffer *buffer) +{ + USBBuffer **tailp; + USBEndpoint *ep = &usb_endpoints[EP_INDEX(ep_addr)]; + if (!(ep->flags & USB_EP_FLAGS_ENABLED)) return; + /* PRINTF("usb_submit_xmit_buffer %d\n", buffer->left); */ + USB_DISABLE_INT; + tailp = (USBBuffer**)&ep->buffer; + while(*tailp) { + tailp = &(*tailp)->next; + } + *tailp = buffer; + while(buffer) { + buffer->flags |= USB_BUFFER_SUBMITTED | USB_BUFFER_IN; + buffer = buffer->next; + } + start_transfer(ep); + USB_ENABLE_INT; +} + +void +usb_arch_discard_all_buffers(unsigned char ep_addr) +{ + uint32_t ints; + USBBuffer *buffer; + volatile USBEndpoint *ep = &usb_endpoints[EP_INDEX(ep_addr)]; + ints = usb_save_disable_int(); + buffer = ep->buffer; + ep->buffer = NULL; +#if 0 + /* Set both directions to NAK */ + USB->EPR[EP_HW_NUM(ep_addr)] = + EPR_TOGGLE_SET(USB->EPR[EP_HW_NUM(ep_addr)], + USB_EP0R_STAT_RX|USB_EP0R_STAT_TX, + USB_EPxR_STAT_TX_NAK| USB_EPxR_STAT_RX_NAK); + ep->flags &= ~(USB_EP_FLAGS_RECV_PENDING|USB_EP_FLAGS_SETUP_PENDING); +#endif + ep->flags &= ~(USB_EP_FLAGS_RECV_PENDING | USB_EP_FLAGS_SETUP_PENDING + | USB_EP_FLAGS_DOUBLE); + usb_restore_int(ints); + while(buffer) { + buffer->flags &= ~USB_BUFFER_SUBMITTED; + buffer = buffer->next; + } +} +uint16_t +usb_arch_get_ep_status(uint8_t addr) +{ + if (EP_INDEX(addr) > USB_MAX_ENDPOINTS) return 0; + return usb_endpoints[EP_INDEX(addr)].status; +} + +void +usb_arch_set_configuration(uint8_t usb_configuration_value) +{ + /* Nothing needs to be done */ +} + +void +usb_arch_control_stall(unsigned char addr) +{ + if (EP_INDEX(addr) > USB_MAX_ENDPOINTS) return; + uint32_t epr = USB->EPR[EP_HW_NUM(addr)]; + USB->EPR[EP_HW_NUM(addr)] = EPR_TOGGLE_SET(epr,USB_EP0R_STAT_RX|USB_EP0R_STAT_TX, USB_EPxR_STAT_RX_STALL | USB_EPxR_STAT_TX_STALL); +} + +/* Not for control endpoints */ +void +usb_arch_halt_endpoint(unsigned char ep_addr, int halt) +{ + if (EP_INDEX(ep_addr) > USB_MAX_ENDPOINTS) return; + if (!usb_endpoints[EP_INDEX(ep_addr)].flags & USB_EP_FLAGS_ENABLED) return; + USB_DISABLE_INT; + if (halt) { + if (!(usb_endpoints[EP_INDEX(ep_addr)].status & 0x01)) { + usb_endpoints[EP_INDEX(ep_addr)].status |= 0x01; + if (ep_addr & 0x80) { + stall_bulk_in(EP_HW_NUM(ep_addr)); + } else { + stall_bulk_out(EP_HW_NUM(ep_addr)); + } + } + } else { + USBEndpoint *ep = &usb_endpoints[EP_INDEX(ep_addr)]; + if (ep->status & 0x01) { + ep->status &= ~0x01; + PRINTF("HALT clear restart EPR: %04x %p %p\n", + (unsigned int)USB->EPR[EP_HW_NUM(ep_addr)], + ep->buffer, ep->buffer->next); + /* Restore toggle state for double buffered endpoint */ + if (IS_BULK_EP(ep)) { + volatile uint32_t *eprp = &USB->EPR[EP_HW_NUM(ep_addr)]; + if (ep_addr & 0x80) { + ep->flags &= ~(USB_EP_FLAGS_DOUBLE |USB_EP_FLAGS_TRANSMITTING); + + *eprp =(EPR_TOGGLE_SET(*eprp,(USB_EP0R_STAT_TX | USB_EP0R_DTOG_TX + | USB_EPxR_SW_BUF_TX), + USB_EPxR_STAT_TX_VALID)); + } else { + ep->flags &= ~(USB_EP_FLAGS_DOUBLE | USB_EP_FLAGS_RECEIVING + | USB_EP_FLAGS_RECV_PENDING); + + *eprp =(EPR_TOGGLE_SET(*eprp,(USB_EP0R_STAT_RX | USB_EP0R_DTOG_RX + | USB_EPxR_SW_BUF_RX), + USB_EPxR_STAT_RX_VALID|USB_EPxR_SW_BUF_RX)); + *eprp = EPR_INVARIANT(*eprp) | USB_EPxR_SW_BUF_RX; + + } + } + /* Release HALT buffer */ + if (ep->buffer && (ep->buffer->flags & USB_BUFFER_HALT)) { + ep->buffer->flags &= ~USB_BUFFER_SUBMITTED; + if (ep->buffer->flags & USB_BUFFER_NOTIFY) { + notify_ep_process(ep,USB_EP_EVENT_NOTIFICATION); + } + ep->buffer = ep->buffer->next; + } + /* Restart transmission */ + start_transfer(&usb_endpoints[EP_INDEX(ep_addr)]); + PRINTF("HALT clear restart EPR: %04x %p %p\n", + (unsigned int)USB->EPR[EP_HW_NUM(ep_addr)], + ep->buffer, ep->buffer->next); + + } + } + USB_ENABLE_INT; +} + +void +usb_arch_set_address(unsigned char addr) +{ + USB->DADDR = 0x80 | addr; +} + +void +USB_HP_CAN_TX_handler(void) __attribute__((interrupt)); + +void +USB_HP_CAN_TX_handler(void) +{ + uint32_t status = USB->ISTR; + if (status & USB_ISTR_CTR) { + transfer_complete(status & USB_ISTR_EP_ID); + } +} + +void +USB_LP_CAN_RX0_handler(void) __attribute__((interrupt)); +void +USB_LP_CAN_RX0_handler(void) +{ + uint32_t status = USB->ISTR; + if (status & USB_ISTR_CTR) { + transfer_complete(status & USB_ISTR_EP_ID); + /* PRINTF("Transfer complete ep %ld\n", status & USB_ISTR_EP_ID); */ + } else if (status & USB_ISTR_PMAOVR) { + PRINTF("PMAOVR\n"); + USB->ISTR &= ~USB_ISTR_PMAOVR; + } else if (status & USB_ISTR_ERR) { + PRINTF("ERR\n"); + USB->ISTR &= ~USB_ISTR_ERR; + } else if (status & USB_ISTR_WKUP) { + PRINTF("WKUP\n"); + USB->ISTR &= ~USB_ISTR_WKUP; + USB->CNTR &= ~USB_CNTR_FSUSP; + notify_process(USB_EVENT_RESUME); + } else if (status & USB_ISTR_SUSP) { + PRINTF("SUSP\n"); + USB->ISTR &= ~USB_ISTR_SUSP; + USB->CNTR |= USB_CNTR_FSUSP; + notify_process(USB_EVENT_SUSPEND); + } else if (status & USB_ISTR_RESET) { + PRINTF("RESET\n"); + USB->ISTR &= ~USB_ISTR_RESET; + usb_arch_reset(); + notify_process(USB_EVENT_RESET); + } +} + +void +usb_arch_toggle_SW_BUF_RX() +{ + USB->EPR[2] = EPR_INVARIANT(USB->EPR[2]) | USB_EPxR_SW_BUF_RX; +} + +int +usb_arch_send_pending(uint8_t ep_addr) +{ + return usb_endpoints[EP_INDEX(ep_addr)].flags & USB_EP_FLAGS_TRANSMITTING; +} diff --git a/cpu/arm/stm32f103/usb-stm32f103.h b/cpu/arm/stm32f103/usb-stm32f103.h new file mode 100644 index 000000000..627aad615 --- /dev/null +++ b/cpu/arm/stm32f103/usb-stm32f103.h @@ -0,0 +1,17 @@ +#include + +#ifdef USB_STM32F103_ENABLE_ALT_COPY +/* Use an alternate data copying function */ +#define USB_BUFFER_ARCH_ALT_COPY USB_BUFFER_ARCH_FLAG_1 + +/* Copy len bytes of data from the buffer to dedicated USB + memory. buffer->data must be updated */ +extern void +copy_to_hw_buffer(USBBuffer *buffer,unsigned int offset, unsigned int len); + +/* Copy len bytes of data to the buffer from dedicated USB memory. + buffer->data must be updated */ +extern void +copy_from_hw_buffer(USBBuffer *buffer,unsigned int offset, unsigned int len); +#endif +