diff --git a/F0-nolib/README b/F0-nolib/README deleted file mode 100644 index 7b53ef9..0000000 --- a/F0-nolib/README +++ /dev/null @@ -1 +0,0 @@ -This directory contains examples for F0 without any library diff --git a/F0-nolib/uart_blink_dma/Makefile b/F0-nolib/uart_blink_dma/Makefile new file mode 100644 index 0000000..f652305 --- /dev/null +++ b/F0-nolib/uart_blink_dma/Makefile @@ -0,0 +1,137 @@ +BINARY = uartblink +BOOTPORT ?= /dev/ttyUSB0 +BOOTSPEED ?= 115200 +# MCU FAMILY +FAMILY = F0 +# MCU code +MCU = F030x4 +DEFS = -DEBUG +# change this linking script depending on particular MCU model, +# for example, if you have STM32F103VBT6, you should write: +LDSCRIPT = ld/stm32f030f.ld + +INDEPENDENT_HEADERS= + +FP_FLAGS ?= -msoft-float +ASM_FLAGS = -mthumb -mcpu=cortex-m0 -march=armv6-m -mtune=cortex-m0 +ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS) + +############################################################################### +# Executables +PREFIX ?= /opt/bin/arm-none-eabi + +RM := rm -f +RMDIR := rmdir +CC := $(PREFIX)-gcc +LD := $(PREFIX)-gcc +AR := $(PREFIX)-ar +AS := $(PREFIX)-as +OBJCOPY := $(PREFIX)-objcopy +OBJDUMP := $(PREFIX)-objdump +GDB := $(PREFIX)-gdb +STFLASH := $(shell which st-flash) +STBOOT := $(shell which stm32flash) + +############################################################################### +# Source files +OBJDIR = mk +LDSCRIPT ?= $(BINARY).ld +SRC := $(wildcard *.c) +OBJS := $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) +STARTUP = $(OBJDIR)/startup.o +OBJS += $(STARTUP) +DEPS := $(OBJS:.o=.d) + +INC_DIR ?= ../inc + +INCLUDE := -I$(INC_DIR)/F0 -I$(INC_DIR)/cm +LIB_DIR := $(INC_DIR)/ld + +############################################################################### +# C flags +CFLAGS += -O2 -g -MD -D__thumb2__=1 +CFLAGS += -Wall -Werror -Wextra -Wshadow -Wimplicit-function-declaration +CFLAGS += -Wredundant-decls $(INCLUDE) +# -Wmissing-prototypes -Wstrict-prototypes +CFLAGS += -fno-common -ffunction-sections -fdata-sections + +############################################################################### +# Linker flags +LDFLAGS += --static -nostartfiles +#--specs=nano.specs +LDFLAGS += -L$(LIB_DIR) +LDFLAGS += -T$(LDSCRIPT) +LDFLAGS += -Wl,-Map=$(OBJDIR)/$(BINARY).map +LDFLAGS += -Wl,--gc-sections + +############################################################################### +# Used libraries +LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group +LDLIBS += $(shell $(CC) $(CFLAGS) -print-libgcc-file-name) + +DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU) + +#.SUFFIXES: .elf .bin .hex .srec .list .map .images +#.SECONDEXPANSION: +#.SECONDARY: + +ELF := $(OBJDIR)/$(BINARY).elf +LIST := $(OBJDIR)/$(BINARY).list +BIN := $(BINARY).bin +HEX := $(BINARY).hex + +all: bin list + +elf: $(ELF) +bin: $(BIN) +hex: $(HEX) +list: $(LIST) + +ifneq ($(MAKECMDGOALS),clean) +-include $(DEPS) +endif + +$(OBJDIR): + mkdir $(OBJDIR) + +$(STARTUP): $(INC_DIR)/startup/vector.c + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $< + +$(OBJDIR)/%.o: %.c + @echo " CC $<" + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $< + +#$(OBJDIR)/%.d: %.c $(OBJDIR) +# $(CC) -MM -MG $< | sed -e 's,^\([^:]*\)\.o[ ]*:,$(@D)/\1.o $(@D)/\1.d:,' >$@ + +$(BIN): $(ELF) + @echo " OBJCOPY $(BIN)" + $(OBJCOPY) -Obinary $(ELF) $(BIN) + +$(HEX): $(ELF) + @echo " OBJCOPY $(HEX)" + $(OBJCOPY) -Oihex $(ELF) $(HEX) + +$(LIST): $(ELF) + @echo " OBJDUMP $(LIST)" + $(OBJDUMP) -S $(ELF) > $(LIST) + +$(ELF): $(OBJDIR) $(OBJS) + @echo " LD $(ELF)" + $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) + +clean: + @echo " CLEAN" + $(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map + @rmdir $(OBJDIR) 2>/dev/null || true + + +flash: $(BIN) + @echo " FLASH $(BIN)" + $(STFLASH) write $(BIN) 0x8000000 + +boot: $(BIN) + @echo " LOAD $(BIN) through bootloader" + $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) + +.PHONY: clean flash boot diff --git a/F0-nolib/uart_blink_dma/Readme.md b/F0-nolib/uart_blink_dma/Readme.md new file mode 100644 index 0000000..141b4a0 --- /dev/null +++ b/F0-nolib/uart_blink_dma/Readme.md @@ -0,0 +1,7 @@ +Code for STM32F030F4 chinese board +USART Rx by interrupts, Tx by DMA +- Toggle onboard green LED once per second. +- Echo received by USART1 data (not more than 64 bytes including '\n') on B115200: + - if PA6 not connected to ground echo text directly + - otherwice echo it reversly +- Light up LED on PA5 (opendrain) when receive data and turn it off when send. diff --git a/F0-nolib/uart_blink_dma/ld/stm32f030f.ld b/F0-nolib/uart_blink_dma/ld/stm32f030f.ld new file mode 100644 index 0000000..f8b61f1 --- /dev/null +++ b/F0-nolib/uart_blink_dma/ld/stm32f030f.ld @@ -0,0 +1,12 @@ +/* Linker script for STM32F030f4, 16K flash, 4K RAM. */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K +} + +/* Include the common ld script. */ +INCLUDE stm32f0.ld + diff --git a/F0-nolib/uart_blink_dma/main.c b/F0-nolib/uart_blink_dma/main.c new file mode 100644 index 0000000..0c513bd --- /dev/null +++ b/F0-nolib/uart_blink_dma/main.c @@ -0,0 +1,91 @@ +/* + * main.c + * + * Copyright 2017 Edward V. Emelianoff + * + * 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; either version 2 of the License, or + * (at your option) any later version. + * + * 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., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ + +#include "stm32f0.h" +#include "usart.h" + +volatile uint32_t Tms = 0; + +/* Called when systick fires */ +void sys_tick_handler(void){ + ++Tms; +} + +static void gpio_setup(void){ + /* Enable clocks to the GPIO subsystems (A&B) */ + RCC->AHBENR |= RCC_AHBENR_GPIOAEN; + /* Set green leds (PA5 & PA5) as output */ + GPIOA->MODER = GPIO_MODER_MODER4_O | GPIO_MODER_MODER5_O; + GPIOA->OTYPER = 1 << 5; // PA5 - opendrain, PA4 - pushpull + /* PA6 - switch blink rate (pullup input) */ + GPIOA->PUPDR = GPIO_PUPDR_PUPDR6_0; +} + +/** + * reverce line + */ +char *rline(char *in, int L){ + static char out[UARTBUFSZ]; + if(L > UARTBUFSZ - 1) return in; + char *optr = out, *iptr = &in[L-1]; + for(; L > 0; --L) *optr++ = *iptr--; + *optr = '\n'; + return out; +} + +int main(void){ + uint32_t lastT = 0; + int L = 0, dummyctr = 0; + uint32_t ostctr = 0; + char *txt; + sysreset(); + SysTick_Config(6000, 1); + gpio_setup(); + USART1_config(); + //StartHSE(); + pin_set(GPIOA, 1<<5); // clear extern LED + /* Do nothing in main loop */ + while (1){ + if(lastT > Tms || Tms - lastT > 499){ + pin_toggle(GPIOA, 1<<4); // blink by onboard LED once per second + lastT = Tms; + } + if(usart1rx()){ // usart1 received data, store in in buffer + L = usart1_getline(&txt); + if(!pin_read(GPIOA, 1<<6)){ // there's a jumper: reverse string + txt = rline(txt, L); + } + pin_clear(GPIOA, 1<<5); // set extern LED + } + if(L){ // text waits for sending + if(ALL_OK == usart1_send(txt, L)){ + L = 0; + pin_set(GPIOA, 1<<5); // clear extern LED + } + }else if(ostctr != Tms){ + ostctr = Tms; + if(++dummyctr > 5000){ // once per 5 seconds + dummyctr = 0; + if(ALL_OK != usart1_send("Dummy text\n", 11)) pin_toggle(GPIOA, 1<<5); + } + } + } +} diff --git a/F0-nolib/uart_blink_dma/uartblink.bin b/F0-nolib/uart_blink_dma/uartblink.bin new file mode 100755 index 0000000..87da4f5 Binary files /dev/null and b/F0-nolib/uart_blink_dma/uartblink.bin differ diff --git a/F0-nolib/uart_blink_dma/usart.c b/F0-nolib/uart_blink_dma/usart.c new file mode 100644 index 0000000..5ee9e03 --- /dev/null +++ b/F0-nolib/uart_blink_dma/usart.c @@ -0,0 +1,154 @@ +/* + * usart.c + * + * Copyright 2017 Edward V. Emelianov + * + * 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; either version 2 of the License, or + * (at your option) any later version. + * + * 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., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ + +#include "usart.h" +#include // memcpy + +extern volatile uint32_t Tms; + +static int datalen[2] = {0,0}; // received data line length (including '\n') + +int linerdy = 0, // received data ready + dlen = 0, // length of data (including '\n') in current buffer + bufovr = 0, // input buffer overfull + txrdy = 1 // transmission done +; + +static int rbufno = 0; // current rbuf number +static char rbuf[2][UARTBUFSZ], tbuf[UARTBUFSZ]; // receive & transmit buffers +static char *recvdata = NULL; + +void USART1_config(){ + /* Enable the peripheral clock of GPIOA */ + RCC->AHBENR |= RCC_AHBENR_GPIOAEN; + /* GPIO configuration for USART1 signals */ + /* (1) Select AF mode (10) on PA9 and PA10 */ + /* (2) AF1 for USART1 signals */ + GPIOA->MODER = (GPIOA->MODER & ~(GPIO_MODER_MODER9|GPIO_MODER_MODER10))\ + | (GPIO_MODER_MODER9_1 | GPIO_MODER_MODER10_1); /* (1) */ + GPIOA->AFR[1] = (GPIOA->AFR[1] &~ (GPIO_AFRH_AFRH1 | GPIO_AFRH_AFRH2))\ + | (1 << (1 * 4)) | (1 << (2 * 4)); /* (2) */ + /* Enable the peripheral clock USART1 */ + RCC->APB2ENR |= RCC_APB2ENR_USART1EN; + /* Configure USART1 */ + /* (1) oversampling by 16, 115200 baud */ + /* (2) 8 data bit, 1 start bit, 1 stop bit, no parity */ + USART1->BRR = 480000 / 1152; /* (1) */ + USART1->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; /* (2) */ + /* polling idle frame Transmission */ + while(!(USART1->ISR & USART_ISR_TC)){} + USART1->ICR |= USART_ICR_TCCF; /* clear TC flag */ + USART1->CR1 |= USART_CR1_RXNEIE; /* enable TC, TXE & RXNE interrupt */ + RCC->AHBENR |= RCC_AHBENR_DMA1EN; + DMA1_Channel2->CPAR = (uint32_t) &(USART1->TDR); // periph + DMA1_Channel2->CMAR = (uint32_t) tbuf; // mem + DMA1_Channel2->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq + USART1->CR3 = USART_CR3_DMAT; + NVIC_SetPriority(DMA1_Channel2_3_IRQn, 3); + NVIC_EnableIRQ(DMA1_Channel2_3_IRQn); + /* Configure IT */ + /* (3) Set priority for USART1_IRQn */ + /* (4) Enable USART1_IRQn */ + NVIC_SetPriority(USART1_IRQn, 0); /* (3) */ + NVIC_EnableIRQ(USART1_IRQn); /* (4) */ +} + +void usart1_isr(){ + #ifdef CHECK_TMOUT + static uint32_t tmout = 0; + #endif + if(USART1->ISR & USART_ISR_RXNE){ // RX not emty - receive next char + #ifdef CHECK_TMOUT + if(tmout && Tms >= tmout){ // set overflow flag + bufovr = 1; + datalen[rbufno] = 0; + } + tmout = Tms + TIMEOUT_MS; + if(!tmout) tmout = 1; // prevent 0 + #endif + // read RDR clears flag + uint8_t rb = USART1->RDR; + if(datalen[rbufno] < UARTBUFSZ){ // put next char into buf + rbuf[rbufno][datalen[rbufno]++] = rb; + if(rb == '\n'){ // got newline - line ready + linerdy = 1; + dlen = datalen[rbufno]; + recvdata = rbuf[rbufno]; + // prepare other buffer + rbufno = !rbufno; + datalen[rbufno] = 0; + #ifdef CHECK_TMOUT + // clear timeout at line end + tmout = 0; + #endif + } + }else{ // buffer overrun + bufovr = 1; + datalen[rbufno] = 0; + #ifdef CHECK_TMOUT + tmout = 0; + #endif + } + } +} + +void dma1_channel2_3_isr(){ + if(DMA1->ISR & DMA_ISR_TCIF2){ // Tx + DMA1->IFCR |= DMA_IFCR_CTCIF2; // clear TC flag + txrdy = 1; + } +} + +/** + * return length of received data (without trailing zero + */ +int usart1_getline(char **line){ + if(bufovr){ + bufovr = 0; + linerdy = 0; + return 0; + } + *line = recvdata; + linerdy = 0; + return dlen; +} + +TXstatus usart1_send(const char *str, int len){ + if(!txrdy) return LINE_BUSY; + if(len > UARTBUFSZ) return STR_TOO_LONG; + txrdy = 0; + DMA1_Channel2->CCR &= ~DMA_CCR_EN; + memcpy(tbuf, str, len); + DMA1_Channel2->CNDTR = len; + DMA1_Channel2->CCR |= DMA_CCR_EN; // start transmission + return ALL_OK; +} + +TXstatus usart1_send_blocking(const char *str, int len){ + if(!txrdy) return LINE_BUSY; + int i; + for(i = 0; i < len; ++i){ + USART1->TDR = *str++; + while(!(USART1->ISR & USART_ISR_TXE)); + } + txrdy = 1; + return ALL_OK; +} diff --git a/F0-nolib/uart_blink_dma/usart.h b/F0-nolib/uart_blink_dma/usart.h new file mode 100644 index 0000000..ee27f42 --- /dev/null +++ b/F0-nolib/uart_blink_dma/usart.h @@ -0,0 +1,51 @@ +/* + * usart.h + * + * Copyright 2017 Edward V. Emelianov + * + * 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; either version 2 of the License, or + * (at your option) any later version. + * + * 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., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ +#pragma once +#ifndef __USART_H__ +#define __USART_H__ + +#include "stm32f0.h" + +// input and output buffers size +#define UARTBUFSZ (64) +// timeout between data bytes +#define TIMEOUT_MS (1500) +// check timeout +#define CHECK_TMOUT + +typedef enum{ + ALL_OK, + LINE_BUSY, + STR_TOO_LONG +} TXstatus; + +#define usart1rx() (linerdy) +#define usart1ovr() (bufovr) + +extern int linerdy, bufovr, txrdy; + +void USART1_config(); +int usart1_getline(char **line); +TXstatus usart1_send(const char *str, int len); +TXstatus usart1_send_blocking(const char *str, int len); + + +#endif // __USART_H__ diff --git a/F0-nolib/uart_nucleo/Makefile b/F0-nolib/uart_nucleo/Makefile new file mode 100644 index 0000000..c581875 --- /dev/null +++ b/F0-nolib/uart_nucleo/Makefile @@ -0,0 +1,137 @@ +BINARY = usart +BOOTPORT ?= /dev/ttyUSB0 +BOOTSPEED ?= 115200 +# MCU FAMILY +FAMILY = F0 +# MCU code +MCU = F042x6 +DEFS += -DEBUG +# change this linking script depending on particular MCU model, +# for example, if you have STM32F103VBT6, you should write: +LDSCRIPT = ld/stm32f042k.ld + +INDEPENDENT_HEADERS= + +FP_FLAGS ?= -msoft-float +ASM_FLAGS = -mthumb -mcpu=cortex-m0 -march=armv6-m -mtune=cortex-m0 +ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS) + +############################################################################### +# Executables +PREFIX ?= /opt/bin/arm-none-eabi + +RM := rm -f +RMDIR := rmdir +CC := $(PREFIX)-gcc +LD := $(PREFIX)-gcc +AR := $(PREFIX)-ar +AS := $(PREFIX)-as +OBJCOPY := $(PREFIX)-objcopy +OBJDUMP := $(PREFIX)-objdump +GDB := $(PREFIX)-gdb +STFLASH := $(shell which st-flash) +STBOOT := $(shell which stm32flash) + +############################################################################### +# Source files +OBJDIR = mk +LDSCRIPT ?= $(BINARY).ld +SRC := $(wildcard *.c) +OBJS := $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) +STARTUP = $(OBJDIR)/startup.o +OBJS += $(STARTUP) +DEPS := $(OBJS:.o=.d) + +INC_DIR ?= ../inc + +INCLUDE := -I$(INC_DIR)/F0 -I$(INC_DIR)/cm +LIB_DIR := $(INC_DIR)/ld + +############################################################################### +# C flags +CFLAGS += -O2 -g -MD -D__thumb2__=1 +CFLAGS += -Wall -Werror -Wextra -Wshadow -Wimplicit-function-declaration +CFLAGS += -Wredundant-decls $(INCLUDE) +# -Wmissing-prototypes -Wstrict-prototypes +CFLAGS += -fno-common -ffunction-sections -fdata-sections + +############################################################################### +# Linker flags +LDFLAGS += --static -nostartfiles +#--specs=nano.specs +LDFLAGS += -L$(LIB_DIR) +LDFLAGS += -T$(LDSCRIPT) +LDFLAGS += -Wl,-Map=$(OBJDIR)/$(BINARY).map +LDFLAGS += -Wl,--gc-sections + +############################################################################### +# Used libraries +LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group +LDLIBS += $(shell $(CC) $(CFLAGS) -print-libgcc-file-name) + +DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU) + +#.SUFFIXES: .elf .bin .hex .srec .list .map .images +#.SECONDEXPANSION: +#.SECONDARY: + +ELF := $(OBJDIR)/$(BINARY).elf +LIST := $(OBJDIR)/$(BINARY).list +BIN := $(BINARY).bin +HEX := $(BINARY).hex + +all: bin list + +elf: $(ELF) +bin: $(BIN) +hex: $(HEX) +list: $(LIST) + +ifneq ($(MAKECMDGOALS),clean) +-include $(DEPS) +endif + +$(OBJDIR): + mkdir $(OBJDIR) + +$(STARTUP): $(INC_DIR)/startup/vector.c + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $< + +$(OBJDIR)/%.o: %.c + @echo " CC $<" + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) $(ARCH_FLAGS) -o $@ -c $< + +#$(OBJDIR)/%.d: %.c $(OBJDIR) +# $(CC) -MM -MG $< | sed -e 's,^\([^:]*\)\.o[ ]*:,$(@D)/\1.o $(@D)/\1.d:,' >$@ + +$(BIN): $(ELF) + @echo " OBJCOPY $(BIN)" + $(OBJCOPY) -Obinary $(ELF) $(BIN) + +$(HEX): $(ELF) + @echo " OBJCOPY $(HEX)" + $(OBJCOPY) -Oihex $(ELF) $(HEX) + +$(LIST): $(ELF) + @echo " OBJDUMP $(LIST)" + $(OBJDUMP) -S $(ELF) > $(LIST) + +$(ELF): $(OBJDIR) $(OBJS) + @echo " LD $(ELF)" + $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) + +clean: + @echo " CLEAN" + $(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map + @rmdir $(OBJDIR) 2>/dev/null || true + + +flash: $(BIN) + @echo " FLASH $(BIN)" + $(STFLASH) write $(BIN) 0x8000000 + +boot: $(BIN) + @echo " LOAD $(BIN) through bootloader" + $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) + +.PHONY: clean flash boot diff --git a/F0-nolib/uart_nucleo/Readme b/F0-nolib/uart_nucleo/Readme new file mode 100644 index 0000000..4ad00ad --- /dev/null +++ b/F0-nolib/uart_nucleo/Readme @@ -0,0 +1,9 @@ +This is a simple USART over DMA application with software end of string control. +Speed 115200. Received string echoes back. +run +DEFS=-DCHECK_TMOUT make +to add timeout 1.5s for each letter + +DEFS="-DCHECK_TMOUT -DTIMEOUT_MS=xx" make +to make another timeout + diff --git a/F0-nolib/uart_nucleo/ld/stm32f042k.ld b/F0-nolib/uart_nucleo/ld/stm32f042k.ld new file mode 100644 index 0000000..e747253 --- /dev/null +++ b/F0-nolib/uart_nucleo/ld/stm32f042k.ld @@ -0,0 +1,12 @@ +/* Linker script for STM32F042x6, 32K flash, 6K RAM. */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K +} + +/* Include the common ld script. */ +INCLUDE stm32f0.ld + diff --git a/F0-nolib/uart_nucleo/main.c b/F0-nolib/uart_nucleo/main.c new file mode 100644 index 0000000..815b3f2 --- /dev/null +++ b/F0-nolib/uart_nucleo/main.c @@ -0,0 +1,95 @@ +/* + * main.c + * + * Copyright 2017 Edward V. Emelianoff + * + * 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; either version 2 of the License, or + * (at your option) any later version. + * + * 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., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ + +#include "stm32f0.h" +#include "usart.h" + +volatile uint32_t Tms = 0; + +/* Called when systick fires */ +void sys_tick_handler(void){ + ++Tms; +} + +static void gpio_setup(void){ + // Set green led (PB3) as output + RCC->AHBENR |= RCC_AHBENR_GPIOBEN; + GPIOB->MODER = GPIO_MODER_MODER3_O; +} + +void printi(int16_t val){ + char buf[6], rbuf[5]; + int l = 0, bpos = 0; + if(!val){ + buf[0] = '0'; + l = 1; + }else{ + if(val < 0){ + buf[0] = '-'; + bpos = 1; + val = -val; + } + while(val){ + rbuf[l++] = val % 10 + '0'; + val /= 10; + } + int i; + bpos += l; + for(i = 0; i < l; ++i){ + buf[--bpos] = rbuf[i]; + } + } + while(ALL_OK != usart2_send_blocking(buf, l+bpos)); + while(ALL_OK != usart2_send_blocking("\n", 1)); +} + +int main(void){ + uint32_t lastT = 0, dctr = 0; + int16_t L = 0; + char *txt; + sysreset(); + SysTick_Config(6000, 1); + gpio_setup(); + usart2_setup(); + + while (1){ + if(lastT > Tms || Tms - lastT > 499){ + pin_toggle(GPIOB, 1<<3); // blink by onboard LED once per second + lastT = Tms; + } + if(usart2rx()){ // usart1 received data, store in in buffer + L = usart2_getline(&txt); + printi(L); + // do something with received data + } + if(L){ // text waits for sending + if(ALL_OK == usart2_send(txt, L)){ + L = 0; + } + } + if(dctr > Tms || Tms - dctr > 4999){// once per 5 seconds + dctr = Tms; + while(ALL_OK != usart2_send_blocking("Dummy text\n", 11)); + } + } + return 0; +} + diff --git a/F0-nolib/uart_nucleo/usart.bin b/F0-nolib/uart_nucleo/usart.bin new file mode 100755 index 0000000..1445acf Binary files /dev/null and b/F0-nolib/uart_nucleo/usart.bin differ diff --git a/F0-nolib/uart_nucleo/usart.c b/F0-nolib/uart_nucleo/usart.c new file mode 100644 index 0000000..876b113 --- /dev/null +++ b/F0-nolib/uart_nucleo/usart.c @@ -0,0 +1,152 @@ +/*us + * usart.c + * + * Copyright 2017 Edward V. Emelianoff + * + * 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; either version 2 of the License, or + * (at your option) any later version. + * + * 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., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ +#include "stm32f0.h" +#include "usart.h" +#include + +extern volatile uint32_t Tms; +static int datalen[2] = {0,0}; // received data line length (including '\n') + +int linerdy = 0, // received data ready + dlen = 0, // length of data (including '\n') in current buffer + bufovr = 0, // input buffer overfull + txrdy = 1 // transmission done +; + + +int rbufno = 0; // current rbuf number +static char rbuf[UARTBUFSZ][2], tbuf[UARTBUFSZ]; // receive & transmit buffers +static char *recvdata = NULL; + +/** + * return length of received data (without trailing zero + */ +int usart2_getline(char **line){ + if(bufovr){ + bufovr = 0; + linerdy = 0; + return 0; + } + *line = recvdata; + linerdy = 0; + return dlen; +} + +TXstatus usart2_send(const char *str, int len){ + if(!txrdy) return LINE_BUSY; + if(len > UARTBUFSZ) return STR_TOO_LONG; + txrdy = 0; + memcpy(tbuf, str, len); + DMA1_Channel4->CCR &= ~DMA_CCR_EN; + DMA1_Channel4->CNDTR = len; + DMA1_Channel4->CCR |= DMA_CCR_EN; // start transmission + return ALL_OK; +} + +TXstatus usart2_send_blocking(const char *str, int len){ + if(!txrdy) return LINE_BUSY; + int i; + bufovr = 0; + for(i = 0; i < len; ++i){ + USART2->TDR = *str++; + while(!(USART2->ISR & USART_ISR_TXE)); + } + txrdy = 1; + return ALL_OK; +} + + +// Nucleo's USART2 connected to VCP proxy of st-link +void usart2_setup(){ + // setup pins: PA2 (Tx - AF1), PA15 (Rx - AF1) + RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_DMAEN; + // AF mode (AF1) + GPIOA->MODER = (GPIOA->MODER & ~(GPIO_MODER_MODER2|GPIO_MODER_MODER15))\ + | (GPIO_MODER_MODER2_1 | GPIO_MODER_MODER15_1); + GPIOA->AFR[0] = (GPIOA->AFR[0] &~GPIO_AFRH_AFRH2) | 1 << (2 * 4); // PA2 + GPIOA->AFR[1] = (GPIOA->AFR[1] &~GPIO_AFRH_AFRH7) | 1 << (7 * 4); // PA15 + // DMA: Tx - Ch4 + DMA1_Channel4->CPAR = (uint32_t) &USART2->TDR; // periph + DMA1_Channel4->CMAR = (uint32_t) tbuf; // mem + DMA1_Channel4->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq + // Tx CNDTR set @ each transmission due to data size + NVIC_SetPriority(DMA1_Channel4_5_IRQn, 3); + NVIC_EnableIRQ(DMA1_Channel4_5_IRQn); + NVIC_SetPriority(USART2_IRQn, 0); + // setup usart2 + RCC->APB1ENR |= RCC_APB1ENR_USART2EN; // clock + // oversampling by16, 115200bps (fck=48mHz) + //USART2_BRR = 0x1a1; // 48000000 / 115200 + USART2->BRR = 480000 / 1152; + USART2->CR3 = USART_CR3_DMAT; // enable DMA Tx + USART2->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; // 1start,8data,nstop; enable Rx,Tx,USART + while(!(USART2->ISR & USART_ISR_TC)); // polling idle frame Transmission + USART2->ICR |= USART_ICR_TCCF; // clear TC flag + USART2->CR1 |= USART_CR1_RXNEIE; + NVIC_EnableIRQ(USART2_IRQn); +} + + +void dma1_channel4_5_isr(){ + if(DMA1->ISR & DMA_ISR_TCIF4){ // Tx + DMA1->IFCR |= DMA_IFCR_CTCIF4; // clear TC flag + txrdy = 1; + } +} + +void usart2_isr(){ + #ifdef CHECK_TMOUT + static uint32_t tmout = 0; + #endif + if(USART2->ISR & USART_ISR_RXNE){ // RX not emty - receive next char + #ifdef CHECK_TMOUT + if(tmout && Tms >= tmout){ // set overflow flag + bufovr = 1; + datalen[rbufno] = 0; + } + tmout = Tms + TIMEOUT_MS; + if(!tmout) tmout = 1; // prevent 0 + #endif + // read RDR clears flag + uint8_t rb = USART2->RDR; + if(datalen[rbufno] < UARTBUFSZ){ // put next char into buf + rbuf[rbufno][datalen[rbufno]++] = rb; + if(rb == '\n'){ // got newline - line ready + linerdy = 1; + dlen = datalen[rbufno]; + recvdata = rbuf[rbufno]; + // prepare other buffer + rbufno = !rbufno; + datalen[rbufno] = 0; + #ifdef CHECK_TMOUT + // clear timeout at line end + tmout = 0; + #endif + } + }else{ // buffer overrun + bufovr = 1; + datalen[rbufno] = 0; + #ifdef CHECK_TMOUT + tmout = 0; + #endif + } + } +} diff --git a/F0-nolib/uart_nucleo/usart.h b/F0-nolib/uart_nucleo/usart.h new file mode 100644 index 0000000..34a1388 --- /dev/null +++ b/F0-nolib/uart_nucleo/usart.h @@ -0,0 +1,48 @@ +/* + * usart.h + * + * Copyright 2017 Edward V. Emelianoff + * + * 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; either version 2 of the License, or + * (at your option) any later version. + * + * 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., 51 Franklin Street, Fifth Floor, Boston, + * MA 02110-1301, USA. + */ +#pragma once +#ifndef __USART_H__ +#define __USART_H__ + +// input and output buffers size +#define UARTBUFSZ (64) +// timeout between data bytes +#ifndef TIMEOUT_MS +#define TIMEOUT_MS (1500) +#endif + +typedef enum{ + ALL_OK, + LINE_BUSY, + STR_TOO_LONG +} TXstatus; + +#define usart2rx() (linerdy) +#define usart2ovr() (bufovr) + +extern int linerdy, bufovr, txrdy; + +void usart2_setup(); +int usart2_getline(char **line); +TXstatus usart2_send(const char *str, int len); +TXstatus usart2_send_blocking(const char *str, int len); + +#endif // __USART_H__