diff --git a/F303-nolib/Readme.md b/F303-nolib/Readme.md index 7128e4d..4d6b0f6 100644 --- a/F303-nolib/Readme.md +++ b/F303-nolib/Readme.md @@ -3,6 +3,8 @@ Samples for STM32F303 Most of these samples works with [my non-solder devboard](https://github.com/eddyem/stm32samples/tree/master/F0_F1_F3-LQFP48_testboard) -- blink - simple LEDs blink on PB0 and PB1 -- usart1 - read data from USART1 and send it back (blocking sending) -- usarts - work with all three USARTs, send to USART1 data read from other, you can send "2\n" or "3\n" to USART1 for tests of USART2/USART3 +- **blink** - simple LEDs blink on PB0 and PB1 +- **usart1** - read data from USART1 and send it back (blocking sending) +- **usarts** - work with all three USARTs with Tx DMA, send to USART1 data read from other, you can send "2\n" or "3\n" to USART1 for tests of USART2/USART3 +- **floatPrintf** - work with floats, convert floating point number into a string +- **usart1fullDMA** - USART1 Rx and Tx DMA access (Rx terminated by character match of '\n' or buffer overflow). diff --git a/F303-nolib/usart1fullDMA/Makefile b/F303-nolib/usart1fullDMA/Makefile new file mode 100644 index 0000000..7ddce2f --- /dev/null +++ b/F303-nolib/usart1fullDMA/Makefile @@ -0,0 +1,146 @@ +BINARY = usart +BOOTPORT ?= /dev/ttyUSB0 +BOOTSPEED ?= 115200 +# MCU FAMILY +FAMILY ?= F3 +# MCU code +MCU ?= F303xb +# or __ARM_ARCH_7EM__ +ARMARCH = __ARM_ARCH_7M__ +# change this linking script depending on particular MCU model, +LDSCRIPT ?= stm32f303xB.ld +# debug +#DEFS = -DEBUG + +INDEPENDENT_HEADERS= + +FP_FLAGS ?= -mfpu=fpv4-sp-d16 -mfloat-abi=hard -fsingle-precision-constant +ASM_FLAGS ?= -mthumb -mcpu=cortex-m4 +ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS) -D $(ARMARCH) + +############################################################################### +# Executables +#PREFIX ?= arm-none-eabi +# gcc from arm web site +PREFIX ?= /opt/bin/arm-none-eabi +TOOLCHLIB ?= /opt/arm-none-eabi/lib +RM := rm -f +RMDIR := rmdir +CC := $(PREFIX)-gcc +# don't replace ld with gcc: the binary size would be much greater!! +LD := $(PREFIX)-ld +AR := $(PREFIX)-ar +AS := $(PREFIX)-as +SIZE := $(PREFIX)-size +OBJCOPY := $(PREFIX)-objcopy +OBJDUMP := $(PREFIX)-objdump +GDB := $(PREFIX)-gdb +STFLASH := $(shell which st-flash) +STBOOT := $(shell which stm32flash) +DFUUTIL := $(shell which dfu-util) + +############################################################################### +# Source files +OBJDIR := mk +SRC := $(wildcard *.c) +OBJS := $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) +STARTUP := $(OBJDIR)/startup.o +MAP := $(OBJDIR)/$(BINARY).map +OBJS += $(STARTUP) +# dependencies: we need them to recompile files if their headers-dependencies changed +DEPS := $(OBJS:.o=.d) + +INC_DIR ?= ../inc + +INCLUDE := -I$(INC_DIR)/Fx -I$(INC_DIR)/cm +LIB_DIR := $(INC_DIR)/ld + +############################################################################### +# C flags +CFLAGS += -g -gdwarf-2 +CFLAGS += -O2 -D__thumb2__=1 -MD +CFLAGS += -Wall -Werror -Wextra -Wshadow +CFLAGS += -fshort-enums -ffunction-sections -fdata-sections +#CFLAGS += -fno-common -ffunction-sections -fdata-sections -fno-stack-protector +CFLAGS += $(ARCH_FLAGS) + +############################################################################### +# Linker flags +#LDFLAGS += -nostartfiles --static -nostdlib -specs=nosys.specs -specs=nano.specs +LDFLAGS += $(ARCH_FLAGS) +LDFLAGS += -specs=nosys.specs -specs=nano.specs +LDFLAGS += -L$(LIB_DIR) +#LDFLAGS += -L$(TOOLCHLIB) +LDFLAGS += -T$(LDSCRIPT) +LDFLAGS += -Wl,-Map=$(MAP),--cref -Wl,--gc-sections + +############################################################################### +# Used libraries +#LDLIBS += -lc $(shell $(CC) $(CFLAGS) -print-libgcc-file-name) + +DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU) + +ELF := $(OBJDIR)/$(BINARY).elf +LIST := $(OBJDIR)/$(BINARY).list +BIN := $(BINARY).bin +HEX := $(BINARY).hex + +all: bin list size + +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) -o $@ -c $< + +$(OBJDIR)/%.o: %.c + @echo " CC $<" + $(CC) $(CFLAGS) $(DEFS) $(INCLUDE) -o $@ -c $< + +$(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)" + $(CC) $(LDFLAGS) $(OBJS) $(LDLIBS) -o $(ELF) + +size: $(ELF) + $(SIZE) $(ELF) + +clean: + @echo " CLEAN" + $(RM) $(OBJS) $(DEPS) $(ELF) $(HEX) $(LIST) $(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) + +dfuboot: $(BIN) + @echo " LOAD $(BIN) THROUGH DFU" + $(DFUUTIL) -a0 -D $(BIN) -s 0x08000000 + +.PHONY: clean flash boot diff --git a/F303-nolib/usart1fullDMA/Readme b/F303-nolib/usart1fullDMA/Readme new file mode 100644 index 0000000..42fa4bf --- /dev/null +++ b/F303-nolib/usart1fullDMA/Readme @@ -0,0 +1 @@ +Full Rx and Tx DMA, Rx DMA ends on buffer end or when '\n' received by character match interrupt. \ No newline at end of file diff --git a/F303-nolib/usart1fullDMA/hardware.c b/F303-nolib/usart1fullDMA/hardware.c new file mode 100644 index 0000000..c908fb9 --- /dev/null +++ b/F303-nolib/usart1fullDMA/hardware.c @@ -0,0 +1,32 @@ +/* + * This file is part of the F303usartDMA project. + * Copyright 2021 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 3 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, see . + */ + +#include "hardware.h" +#include "usart.h" + +static inline void gpio_setup(){ + RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN; // for USART and LEDs + for(int i = 0; i < 10; ++i) nop(); // don't know why, but next line won't work without a little delay + GPIOB->MODER = GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O; + GPIOB->ODR = 1; +} + +void hw_setup(){ + gpio_setup(); +} + diff --git a/F303-nolib/usart1fullDMA/hardware.h b/F303-nolib/usart1fullDMA/hardware.h new file mode 100644 index 0000000..5e28a1b --- /dev/null +++ b/F303-nolib/usart1fullDMA/hardware.h @@ -0,0 +1,27 @@ +/* + * This file is part of the F303usartDMA project. + * Copyright 2021 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 3 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, see . + */ + +#pragma once +#ifndef __HARDWARE_H__ +#define __HARDWARE_H__ + +#include "stm32f3.h" + +void hw_setup(); + +#endif // __HARDWARE_H__ diff --git a/F303-nolib/usart1fullDMA/main.c b/F303-nolib/usart1fullDMA/main.c new file mode 100644 index 0000000..da42b2f --- /dev/null +++ b/F303-nolib/usart1fullDMA/main.c @@ -0,0 +1,54 @@ +/* + * This file is part of the F303usartDMA project. + * Copyright 2021 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 3 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, see . + */ + +#include "stm32f3.h" +#include "hardware.h" +#include "usart.h" + + +volatile uint32_t Tms = 0; + +void sys_tick_handler(void){ + ++Tms; +} + +int main(void){ + //sysreset(); + if(!StartHSE()) StartHSI(); + SysTick_Config((uint32_t)72000); // 1ms + hw_setup(); + usart_setup(); + uint32_t ctr = Tms; + while(1){ + if(Tms - ctr > 499){ + ctr = Tms; + pin_toggle(GPIOB, 1 << 1 | 1 << 0); // toggle LED @ PB0 + } + if(usart_ovr()) usart_send("Buffer overflow occured!\n"); + if(chk_usart()){ // usart1 received data, store in in buffer + char *txt = NULL; + int r = usart_getline(&txt); + if(r){ + txt[r] = 0; + usart_send("Got data: _"); + usart_send(txt); + usart_send("_\n"); + } + } + } +} diff --git a/F303-nolib/usart1fullDMA/usart.bin b/F303-nolib/usart1fullDMA/usart.bin new file mode 100755 index 0000000..b2e741c Binary files /dev/null and b/F303-nolib/usart1fullDMA/usart.bin differ diff --git a/F303-nolib/usart1fullDMA/usart.c b/F303-nolib/usart1fullDMA/usart.c new file mode 100644 index 0000000..93ca185 --- /dev/null +++ b/F303-nolib/usart1fullDMA/usart.c @@ -0,0 +1,184 @@ +/* + * This file is part of the F303usartDMA project. + * Copyright 2021 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 3 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, see . + */ + +#include "stm32f3.h" +#include "hardware.h" +#include "usart.h" +#include + +extern volatile uint32_t Tms; +static uint32_t lastAccessT = 0; // Tms of last Tx access + +// flags +static volatile uint8_t bufovr = 0, // input buffer overfull + rxrdy = 0, // received data ready + txrdy = 1; // transmission done + +// length of data (including '\n') in current buffer +static volatile int dlen = 0; +static volatile int odatalen[2] = {0}; + +static uint8_t rbufno = 0, tbufno = 0; // current rbuf/tbuf numbers +static char rbuf[2][UARTBUFSZI], tbuf[2][UARTBUFSZO]; // receive & transmit buffers +static char *recvdata = NULL; + +static int transmit_tbuf(); + +// return 1 if overflow was +int usart_ovr(){ + if(bufovr){ + bufovr = 0; + return 1; + } + return 0; +} + +// check if the buffer was filled >10ms ago (transmit it then) +// @return rxrdy flag +int chk_usart(){ + if(Tms - lastAccessT > TRANSMIT_DELAY){ + transmit_tbuf(); + lastAccessT = Tms; + } + int ret = rxrdy; + rxrdy = 0; + return ret; +} + +/** + * return length of received data (without trailing zero + */ +int usart_getline(char **line){ + *line = recvdata; + rxrdy = 0; + recvdata = NULL; + bufovr = 0; + return dlen; +} + +// transmit current tbuf and swap buffers +static int transmit_tbuf(){ + uint32_t p = 1000000; + while(!txrdy && --p); + if(!txrdy) return 0; + register int l = odatalen[tbufno]; + if(!l) return 1; + txrdy = 0; + odatalen[tbufno] = 0; + DMA1_Channel4->CCR &= ~DMA_CCR_EN; + DMA1_Channel4->CMAR = (uint32_t) tbuf[tbufno]; // mem + DMA1_Channel4->CNDTR = l; + DMA1_Channel4->CCR |= DMA_CCR_EN; + tbufno = !tbufno; + return 1; +} + +void usart_putchar(const char ch){ + if(odatalen[tbufno] == UARTBUFSZO) + if(!transmit_tbuf()) return; + tbuf[tbufno][odatalen[tbufno]++] = ch; +} + +void usart_send(const char *str){ + while(*str){ + if(odatalen[tbufno] == UARTBUFSZO) + if(!transmit_tbuf()) return; + tbuf[tbufno][odatalen[tbufno]++] = *str++; + } +} + +void usart_sendn(const char *str, uint32_t L){ + for(uint32_t i = 0; i < L; ++i){ + if(odatalen[tbufno] == UARTBUFSZO) + if(!transmit_tbuf()) return; + tbuf[tbufno][odatalen[tbufno]++] = *str++; + } +} + +// USART1: Rx - PA10 (AF7), Tx - PA9 (AF7) +void usart_setup(){ + // setup pins: + GPIOA->MODER = (GPIOA->MODER & ~(GPIO_MODER_MODER9 | GPIO_MODER_MODER10)) | + GPIO_MODER_MODER9_AF | GPIO_MODER_MODER10_AF; + GPIOA->AFR[1] = (GPIOA->AFR[1] & ~(GPIO_AFRH_AFRH1 | GPIO_AFRH_AFRH2)) | + 7 << (1 * 4) | 7 << (2 * 4); // PA9, PA10 + // clock + RCC->APB2ENR |= RCC_APB2ENR_USART1EN; + RCC->AHBENR |= RCC_AHBENR_DMA1EN; + USART1->ICR = 0xffffffff; // clear all flags + // Tx DMA + DMA1_Channel4->CCR = 0; + DMA1_Channel4->CPAR = (uint32_t) &USART1->TDR; // periph + DMA1_Channel4->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq + // Rx DMA + DMA1_Channel5->CCR = 0; + DMA1_Channel5->CPAR = (uint32_t) &USART1->RDR; // periph + DMA1_Channel5->CMAR = (uint32_t) rbuf[0]; + DMA1_Channel5->CNDTR = UARTBUFSZI; + DMA1_Channel5->CCR |= DMA_CCR_MINC | DMA_CCR_TCIE | DMA_CCR_EN; // 8bit, mem++, per->mem, transcompl irq, enable + // setup usart + USART1->BRR = 720000 / 1152; + USART1->CR3 = USART_CR3_DMAT | USART_CR3_DMAR; // enable DMA Tx/Rx + USART1->CR2 = USART_CR2_ADD_VAL('\n'); // init character match register + USART1->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE | USART_CR1_CMIE; // 1start,8data,nstop; enable Rx,Tx,USART; enable CharacterMatch Irq + uint32_t tmout = 16000000; + while(!(USART1->ISR & USART_ISR_TC)){if(--tmout == 0) break;} // polling idle frame Transmission + USART1->ICR = 0xffffffff; // clear all flags again + NVIC_EnableIRQ(USART1_IRQn); + NVIC_EnableIRQ(DMA1_Channel4_IRQn); + NVIC_EnableIRQ(DMA1_Channel5_IRQn); + NVIC_SetPriority(DMA1_Channel5_IRQn, 0); + NVIC_SetPriority(USART1_IRQn, 4); // set character match priority lower +} + +void usart_stop(){ + RCC->APB2ENR &= ~RCC_APB2ENR_USART1EN; +} + +// USART1 character match interrupt +void usart1_exti25_isr(){ + DMA1_Channel5->CCR &= ~DMA_CCR_EN; // temporaly disable DMA + USART1->ICR = USART_ICR_CMCF; // clear character match flag + recvdata = rbuf[rbufno]; + register int l = UARTBUFSZI - DMA1_Channel5->CNDTR - 1; + if(l > 0){ + recvdata[l] = 0; + dlen = l; + rxrdy = 1; + } + rbufno = !rbufno; + DMA1_Channel5->CMAR = (uint32_t) rbuf[rbufno]; + DMA1_Channel5->CNDTR = UARTBUFSZI; + DMA1_Channel5->CCR |= DMA_CCR_EN; +} + +// USART1 Tx complete +void dma1_channel4_isr(){ + DMA1->IFCR |= DMA_IFCR_CTCIF4; + txrdy = 1; +} + +// USART1 Rx buffer overrun +void dma1_channel5_isr(){ + DMA1_Channel5->CCR &= ~DMA_CCR_EN; + DMA1->IFCR |= DMA_IFCR_CTCIF5; + DMA1_Channel5->CMAR = (uint32_t) rbuf[rbufno]; + DMA1_Channel5->CNDTR = UARTBUFSZI; + bufovr = 1; + DMA1_Channel5->CCR |= DMA_CCR_EN; +} diff --git a/F303-nolib/usart1fullDMA/usart.h b/F303-nolib/usart1fullDMA/usart.h new file mode 100644 index 0000000..13dd6e2 --- /dev/null +++ b/F303-nolib/usart1fullDMA/usart.h @@ -0,0 +1,52 @@ +/* + * This file is part of the F303usartDMA project. + * Copyright 2021 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 3 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, see . + */ + +#pragma once +#ifndef __USART_H__ +#define __USART_H__ + +#include "hardware.h" + +// max pause (ms) from buffer filling and data transmitting +#define TRANSMIT_DELAY (15) + +// input and output buffers size (don't forget trailing zero in input buffer!) +// DMA generates TC irq while last byte isn't in buffer, so, to get 80 symbols excluding '\n' we need 82 bytes in buffer +#define UARTBUFSZI (82) +#define UARTBUFSZO (80) + +// timeout between data bytes +#ifndef TIMEOUT_MS +#define TIMEOUT_MS (1500) +#endif + +// macro for static strings +#define SEND(str) usart_send(str) + +#define newline() usart_putchar('\n') + +int usart_ovr(); +int chk_usart(); +void usart_setup(); +int usart_getline(char **line); +void usart_send(const char *str); +void usart_sendn(const char *str, uint32_t L); +void usart_putchar(const char ch); +void usart_stop(); + +#endif // __USART_H__