mirror of
https://github.com/eddyem/stm32samples.git
synced 2025-12-06 02:35:23 +03:00
add usart over DMA Rx/Tx for G070
This commit is contained in:
parent
17c4367b9c
commit
8d0a16612d
@ -81,7 +81,8 @@ TRUE_INLINE void StartHSEHSI(int isHSE){
|
||||
| RCC_PLLCFGR_PLLSRC_HSE;
|
||||
}else{ // 64MHz from HSI16
|
||||
RCC->PLLCFGR = (8<<8) | (1<<4)
|
||||
| RCC_PLLCFGR_PLLREN | RCC_PLLCFGR_PLLPEN /* | RCC_PLLCFGR_PLLQEN */
|
||||
// enable P and/or Q if need
|
||||
| RCC_PLLCFGR_PLLREN /* | RCC_PLLCFGR_PLLPEN | RCC_PLLCFGR_PLLQEN */
|
||||
| RCC_PLLCFGR_PLLSRC_HSI;
|
||||
}
|
||||
RCC->CR |= RCC_CR_PLLON;
|
||||
|
||||
@ -33,13 +33,6 @@ void WEAK sv_call_handler(void);
|
||||
void WEAK pend_sv_handler(void);
|
||||
void WEAK sys_tick_handler(void);
|
||||
|
||||
#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__)
|
||||
void WEAK mem_manage_handler(void);
|
||||
void WEAK bus_fault_handler(void);
|
||||
void WEAK usage_fault_handler(void);
|
||||
void WEAK debug_monitor_handler(void);
|
||||
#endif
|
||||
|
||||
#if defined STM32G0
|
||||
void WEAK wwdg_isr(void);
|
||||
void WEAK rtc_isr(void);
|
||||
@ -67,7 +60,7 @@ void WEAK spi1_isr(void);
|
||||
void WEAK spi2_3_isr(void);
|
||||
void WEAK usart1_isr(void);
|
||||
void WEAK usart2_isr(void);
|
||||
void WEAK usart3_6_isr(void);
|
||||
void WEAK usart3_4_isr(void);
|
||||
void WEAK cec_can_isr(void);
|
||||
void WEAK usb_isr(void);
|
||||
#else
|
||||
|
||||
@ -32,71 +32,43 @@ void null_handler(void);
|
||||
* symbols. */
|
||||
#if defined STM32G0
|
||||
#include "stm32g0xx.h"
|
||||
|
||||
#define NVIC_WWDG_IRQ 0
|
||||
#define NVIC_RTC_IRQ 2
|
||||
#define NVIC_FLASH_IRQ 3
|
||||
#define NVIC_RCC_IRQ 4
|
||||
#define NVIC_EXTI0_1_IRQ 5
|
||||
#define NVIC_EXTI2_3_IRQ 6
|
||||
#define NVIC_EXTI4_15_IRQ 7
|
||||
#define NVIC_DMA1_CHANNEL1_IRQ 9
|
||||
#define NVIC_DMA1_CHANNEL2_3_IRQ 10
|
||||
#define NVIC_DMAMUX_IRQ 11
|
||||
#define NVIC_ADC_COMP_IRQ 12
|
||||
#define NVIC_TIM1_BRK_UP_TRG_COM_IRQ 13
|
||||
#define NVIC_TIM1_CC_IRQ 14
|
||||
#define NVIC_TIM3_4_IRQ 16
|
||||
#define NVIC_TIM6_DAC_IRQ 17
|
||||
#define NVIC_TIM7_IRQ 18
|
||||
#define NVIC_TIM14_IRQ 19
|
||||
#define NVIC_TIM15_IRQ 20
|
||||
#define NVIC_TIM16_IRQ 21
|
||||
#define NVIC_TIM17_IRQ 22
|
||||
#define NVIC_I2C1_IRQ 23
|
||||
#define NVIC_I2C2_3_IRQ 24
|
||||
#define NVIC_SPI1_IRQ 25
|
||||
#define NVIC_SPI2_3_IRQ 26
|
||||
#define NVIC_USART1_IRQ 27
|
||||
#define NVIC_USART2_IRQ 28
|
||||
#define NVIC_USART3_6_IRQ 29
|
||||
#define NVIC_CEC_CAN_IRQ 30
|
||||
#define NVIC_USB_IRQ 31
|
||||
#else
|
||||
#error "Not supported STM32 family"
|
||||
#endif
|
||||
|
||||
#define NVIC_IRQ_COUNT 32
|
||||
|
||||
#if defined STM32G070xx
|
||||
#define IRQ_HANDLERS \
|
||||
[NVIC_WWDG_IRQ] = wwdg_isr, \
|
||||
[NVIC_RTC_IRQ] = rtc_isr, \
|
||||
[NVIC_FLASH_IRQ] = flash_isr, \
|
||||
[NVIC_RCC_IRQ] = rcc_isr, \
|
||||
[NVIC_EXTI0_1_IRQ] = exti0_1_isr, \
|
||||
[NVIC_EXTI2_3_IRQ] = exti2_3_isr, \
|
||||
[NVIC_EXTI4_15_IRQ] = exti4_15_isr, \
|
||||
[NVIC_DMA1_CHANNEL1_IRQ] = dma1_channel1_isr, \
|
||||
[NVIC_DMA1_CHANNEL2_3_IRQ] = dma1_channel2_3_isr, \
|
||||
[NVIC_DMAMUX_IRQ] = dmamux_isr, \
|
||||
[NVIC_ADC_COMP_IRQ] = adc_comp_isr, \
|
||||
[NVIC_TIM1_BRK_UP_TRG_COM_IRQ] = tim1_brk_up_trg_com_isr, \
|
||||
[NVIC_TIM1_CC_IRQ] = tim1_cc_isr, \
|
||||
[NVIC_TIM3_4_IRQ] = tim3_4_isr, \
|
||||
[NVIC_TIM6_DAC_IRQ] = tim6_dac_isr, \
|
||||
[NVIC_TIM7_IRQ] = tim7_isr, \
|
||||
[NVIC_TIM14_IRQ] = tim14_isr, \
|
||||
[NVIC_TIM15_IRQ] = tim15_isr, \
|
||||
[NVIC_TIM16_IRQ] = tim16_isr, \
|
||||
[NVIC_TIM17_IRQ] = tim17_isr, \
|
||||
[NVIC_I2C1_IRQ] = i2c1_isr, \
|
||||
[NVIC_I2C2_3_IRQ] = i2c2_3_isr, \
|
||||
[NVIC_SPI1_IRQ] = spi1_isr, \
|
||||
[NVIC_SPI2_3_IRQ] = spi2_3_isr, \
|
||||
[NVIC_USART1_IRQ] = usart1_isr, \
|
||||
[NVIC_USART2_IRQ] = usart2_isr, \
|
||||
[NVIC_USART3_6_IRQ] = usart3_6_isr, \
|
||||
[NVIC_CEC_CAN_IRQ] = cec_can_isr, \
|
||||
[NVIC_USB_IRQ] = usb_isr
|
||||
[WWDG_IRQn] = wwdg_isr, \
|
||||
[RTC_TAMP_IRQn] = rtc_isr, \
|
||||
[FLASH_IRQn] = flash_isr, \
|
||||
[RCC_IRQn] = rcc_isr, \
|
||||
[EXTI0_1_IRQn] = exti0_1_isr, \
|
||||
[EXTI2_3_IRQn] = exti2_3_isr, \
|
||||
[EXTI4_15_IRQn] = exti4_15_isr, \
|
||||
[DMA1_Channel1_IRQn] = dma1_channel1_isr, \
|
||||
[DMA1_Channel2_3_IRQn] = dma1_channel2_3_isr, \
|
||||
[DMA1_Ch4_7_DMAMUX1_OVR_IRQn] = dmamux_isr, \
|
||||
[ADC1_IRQn] = adc_comp_isr, \
|
||||
[TIM1_BRK_UP_TRG_COM_IRQn] = tim1_brk_up_trg_com_isr, \
|
||||
[TIM1_CC_IRQn] = tim1_cc_isr, \
|
||||
[TIM3_IRQn] = tim3_4_isr, \
|
||||
[TIM6_IRQn] = tim6_dac_isr, \
|
||||
[TIM7_IRQn] = tim7_isr, \
|
||||
[TIM14_IRQn] = tim14_isr, \
|
||||
[TIM15_IRQn] = tim15_isr, \
|
||||
[TIM16_IRQn] = tim16_isr, \
|
||||
[TIM17_IRQn] = tim17_isr, \
|
||||
[I2C1_IRQn] = i2c1_isr, \
|
||||
[I2C2_IRQn] = i2c2_3_isr, \
|
||||
[SPI1_IRQn] = spi1_isr, \
|
||||
[SPI2_IRQn] = spi2_3_isr, \
|
||||
[USART1_IRQn] = usart1_isr, \
|
||||
[USART2_IRQn] = usart2_isr, \
|
||||
[USART3_4_IRQn] = usart3_4_isr
|
||||
#else
|
||||
#error "Not supported STM32 family"
|
||||
#error "Not supported STM32G0 MCU"
|
||||
#endif
|
||||
|
||||
|
||||
@ -121,15 +93,6 @@ vector_table_t vector_table __attribute__ ((section(".vector_table"))) = {
|
||||
.reset = reset_handler,
|
||||
.nmi = nmi_handler,
|
||||
.hard_fault = hard_fault_handler,
|
||||
|
||||
/* Those are defined only on CM3 or CM4 */
|
||||
#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__)
|
||||
.memory_manage_fault = mem_manage_handler,
|
||||
.bus_fault = bus_fault_handler,
|
||||
.usage_fault = usage_fault_handler,
|
||||
.debug_monitor = debug_monitor_handler,
|
||||
#endif
|
||||
|
||||
.sv_call = sv_call_handler,
|
||||
.pend_sv = pend_sv_handler,
|
||||
.systick = sys_tick_handler,
|
||||
@ -171,20 +134,12 @@ void null_handler(void)
|
||||
/* Do nothing. */
|
||||
}
|
||||
|
||||
|
||||
#pragma weak nmi_handler = null_handler
|
||||
#pragma weak hard_fault_handler = blocking_handler
|
||||
#pragma weak sv_call_handler = null_handler
|
||||
#pragma weak pend_sv_handler = null_handler
|
||||
#pragma weak sys_tick_handler = null_handler
|
||||
|
||||
#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__)
|
||||
#pragma weak mem_manage_handler = blocking_handler
|
||||
#pragma weak bus_fault_handler = blocking_handler
|
||||
#pragma weak usage_fault_handler = blocking_handler
|
||||
#pragma weak debug_monitor_handler = null_handler
|
||||
#endif
|
||||
|
||||
#if defined STM32G0
|
||||
#pragma weak wwdg_isr = blocking_handler
|
||||
#pragma weak rtc_isr = blocking_handler
|
||||
@ -212,7 +167,7 @@ void null_handler(void)
|
||||
#pragma weak spi2_3_isr = blocking_handler
|
||||
#pragma weak usart1_isr = blocking_handler
|
||||
#pragma weak usart2_isr = blocking_handler
|
||||
#pragma weak usart3_6_isr = blocking_handler
|
||||
#pragma weak usart3_4_isr = blocking_handler
|
||||
#pragma weak cec_can_isr = blocking_handler
|
||||
#pragma weak usb_isr = blocking_handler
|
||||
#endif
|
||||
|
||||
143
G0:G070/usart/Makefile
Normal file
143
G0:G070/usart/Makefile
Normal file
@ -0,0 +1,143 @@
|
||||
BINARY = usart
|
||||
BOOTPORT ?= /dev/ttyUSB0
|
||||
BOOTSPEED ?= 115200
|
||||
# MCU FAMILY
|
||||
FAMILY = G0
|
||||
# MCU code
|
||||
MCU = G070xx
|
||||
DEFS = -DEBUG -g3
|
||||
# change this linking script depending on particular MCU model,
|
||||
# for example, if you have STM32F103VBT6, you should write:
|
||||
LDSCRIPT = stm32g070xb.ld
|
||||
|
||||
INDEPENDENT_HEADERS=
|
||||
|
||||
FP_FLAGS ?= -msoft-float
|
||||
ASM_FLAGS = -mthumb -mcpu=cortex-m0plus -march=armv6-m -mtune=cortex-m0plus
|
||||
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)/Fx -I$(INC_DIR)/cm
|
||||
LIB_DIR := $(INC_DIR)/ld
|
||||
|
||||
###############################################################################
|
||||
# C flags
|
||||
CFLAGS += -O2 -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)
|
||||
|
||||
openocd:
|
||||
openocd -f openocd.cfg
|
||||
dbg:
|
||||
arm-none-eabi-gdb $(ELF) -ex 'target remote localhost:3333' -ex 'monitor reset halt'
|
||||
|
||||
|
||||
.PHONY: clean flash boot openocd dbg
|
||||
1
G0:G070/usart/README
Normal file
1
G0:G070/usart/README
Normal file
@ -0,0 +1 @@
|
||||
USART3 @ PD8/PD9
|
||||
69
G0:G070/usart/main.c
Normal file
69
G0:G070/usart/main.c
Normal file
@ -0,0 +1,69 @@
|
||||
/*
|
||||
* This file is part of the usart project.
|
||||
* Copyright 2023 Edward V. Emelianov <edward.emelianoff@gmail.com>.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stm32g0.h>
|
||||
#include "usart.h"
|
||||
|
||||
// KEY (intpullup->0) - PC0
|
||||
// LED - PC8
|
||||
|
||||
volatile uint32_t Tms = 0;
|
||||
|
||||
/* Called when systick fires */
|
||||
void sys_tick_handler(void){
|
||||
++Tms;
|
||||
}
|
||||
|
||||
static void gpio_setup(void){
|
||||
RCC->IOPENR |= RCC_IOPENR_GPIOCEN; // enable PC
|
||||
// set PC8 as opendrain output, PC0 is pullup input, other as default (AIN)
|
||||
GPIOC->MODER = (0xffffffff & ~(GPIO_MODER_MODE8 | GPIO_MODER_MODE0)) | GPIO_MODER_MODER8_O;
|
||||
GPIOC->PUPDR = GPIO_PUPDR0_PU; // pullup
|
||||
GPIOC->OTYPER = GPIO_OTYPER_OT8; // open drain
|
||||
}
|
||||
|
||||
int main(void){
|
||||
StartHSE();
|
||||
SysTick_Config(8000); // 1ms counter
|
||||
gpio_setup();
|
||||
usart3_setup();
|
||||
uint32_t T = 0;
|
||||
int sent = 0;
|
||||
/* Do nothing in main loop */
|
||||
while (1){
|
||||
if(Tms - T > 499){ // blink LED
|
||||
T = Tms;
|
||||
pin_toggle(GPIOC, 1<<8);
|
||||
usart3_sendbuf();
|
||||
}
|
||||
if(pin_read(GPIOC, 1<<0) == 0){ // key pressed - send data over USART
|
||||
if(!sent){
|
||||
usart3_sendstr("Button pressed\n");
|
||||
sent = 1;
|
||||
}
|
||||
}else sent = 0;
|
||||
int wasbo = 0;
|
||||
char *rcv = usart3_getline(&wasbo);
|
||||
if(wasbo) usart3_sendstr("Buffer overflow occured @ last message\n");
|
||||
if(rcv){
|
||||
usart3_sendstr("\nI got: ");
|
||||
usart3_sendstr(rcv);
|
||||
usart3_send("\n\n", 2);
|
||||
}
|
||||
}
|
||||
}
|
||||
89
G0:G070/usart/openocd.cfg
Normal file
89
G0:G070/usart/openocd.cfg
Normal file
@ -0,0 +1,89 @@
|
||||
# script for stm32g0x family
|
||||
|
||||
#
|
||||
# stm32g0 devices support SWD transports only.
|
||||
#
|
||||
source [find interface/stlink.cfg]
|
||||
source [find target/swj-dp.tcl]
|
||||
source [find mem_helper.tcl]
|
||||
|
||||
if { [info exists CHIPNAME] } {
|
||||
set _CHIPNAME $CHIPNAME
|
||||
} else {
|
||||
set _CHIPNAME stm32g0x
|
||||
}
|
||||
|
||||
set _ENDIAN little
|
||||
|
||||
# Work-area is a space in RAM used for flash programming
|
||||
# Smallest proposed target has 8kB ram, use 4kB by default to avoid surprises
|
||||
if { [info exists WORKAREASIZE] } {
|
||||
set _WORKAREASIZE $WORKAREASIZE
|
||||
} else {
|
||||
set _WORKAREASIZE 0x1000
|
||||
}
|
||||
|
||||
#jtag scan chain
|
||||
if { [info exists CPUTAPID] } {
|
||||
set _CPUTAPID $CPUTAPID
|
||||
} else {
|
||||
# Section 37.5.5 - corresponds to Cortex-M0+
|
||||
set _CPUTAPID 0x0bc11477
|
||||
}
|
||||
|
||||
swj_newdap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID
|
||||
dap create $_CHIPNAME.dap -chain-position $_CHIPNAME.cpu
|
||||
|
||||
set _TARGETNAME $_CHIPNAME.cpu
|
||||
target create $_TARGETNAME cortex_m -endian $_ENDIAN -dap $_CHIPNAME.dap
|
||||
|
||||
$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0
|
||||
|
||||
set _FLASHNAME $_CHIPNAME.flash
|
||||
flash bank $_FLASHNAME stm32l4x 0 0 0 0 $_TARGETNAME
|
||||
|
||||
# reasonable default
|
||||
adapter speed 2000
|
||||
|
||||
adapter srst delay 100
|
||||
if {[using_jtag]} {
|
||||
jtag_ntrst_delay 100
|
||||
}
|
||||
|
||||
reset_config srst_nogate
|
||||
|
||||
if {![using_hla]} {
|
||||
# if srst is not fitted use SYSRESETREQ to
|
||||
# perform a soft reset
|
||||
cortex_m reset_config sysresetreq
|
||||
}
|
||||
|
||||
proc stm32g0x_default_reset_start {} {
|
||||
# Reset clock is HSI16 (16 MHz)
|
||||
adapter speed 2000
|
||||
}
|
||||
|
||||
proc stm32g0x_default_examine_end {} {
|
||||
# DBGMCU_CR |= DBG_STANDBY | DBG_STOP
|
||||
mmw 0x40015804 0x00000006 0
|
||||
|
||||
# Stop watchdog counters during halt
|
||||
# DBGMCU_APB1_FZ |= DBG_IWDG_STOP | DBG_WWDG_STOP
|
||||
mmw 0x40015808 0x00001800 0
|
||||
}
|
||||
|
||||
proc stm32g0x_default_reset_init {} {
|
||||
# Increase clock to 64 Mhz
|
||||
mmw 0x40022000 0x00000002 0x00000005 ;# FLASH_ACR: Latency = 2
|
||||
mww 0x4002100C 0x30000802 ;# RCC_PLLCFGR = PLLR=/2, PLLN=8, PLLM=/1, PLLSRC=0x2
|
||||
mmw 0x40021000 0x01000000 0x00000000 ;# RCC_CR |= PLLON
|
||||
mmw 0x40021008 0x00000002 0x00000005 ;# RCC_CFGR: SW=PLLRCLK
|
||||
|
||||
# Boost JTAG frequency
|
||||
adapter speed 4000
|
||||
}
|
||||
|
||||
# Default hooks
|
||||
$_TARGETNAME configure -event examine-end { stm32g0x_default_examine_end }
|
||||
$_TARGETNAME configure -event reset-start { stm32g0x_default_reset_start }
|
||||
$_TARGETNAME configure -event reset-init { stm32g0x_default_reset_init }
|
||||
BIN
G0:G070/usart/usart.bin
Executable file
BIN
G0:G070/usart/usart.bin
Executable file
Binary file not shown.
172
G0:G070/usart/usart.c
Normal file
172
G0:G070/usart/usart.c
Normal file
@ -0,0 +1,172 @@
|
||||
/*
|
||||
* This file is part of the usart project.
|
||||
* Copyright 2023 Edward V. Emelianov <edward.emelianoff@gmail.com>.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stm32g0.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "usart.h"
|
||||
|
||||
// RX/TX DMA->CCR without EN flag
|
||||
#define DMARXCCR (DMA_CCR_MINC | DMA_CCR_TCIE | DMA_CCR_TEIE)
|
||||
#define DMATXCCR (DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE | DMA_CCR_TEIE)
|
||||
|
||||
static int txrdy = 1, rxrdy = 0; // transmission done, next line received
|
||||
static int bufovr = 0, wasbufovr = 0; // Rx buffer overflow or error flag -> delete next line
|
||||
static int rbufno = 0, tbufno = 0; // current buf number
|
||||
static char rbuf[2][UARTBUFSZ], tbuf[2][UARTBUFSZ]; // receive & transmit buffers
|
||||
static int rxlen[2] = {0}, txlen[2] = {0};
|
||||
|
||||
char *usart3_getline(int *wasbo){
|
||||
if(wasbo) *wasbo = wasbufovr;
|
||||
wasbufovr = 0;
|
||||
if(!rxrdy) return NULL;
|
||||
rxrdy = 0; // clear ready flag
|
||||
return rbuf[!rbufno]; // current buffer is in filling stage, return old - filled - buffer
|
||||
}
|
||||
|
||||
// USART3 @ PD8 (Tx) and PD9 (Rx) - both AF0
|
||||
void usart3_setup(){
|
||||
RCC->IOPENR |= RCC_IOPENR_GPIODEN; // enable PD
|
||||
RCC->AHBENR |= RCC_AHBENR_DMA1EN; // enable DMA1
|
||||
// set PD8 and PD9 as AF
|
||||
GPIOD->MODER = (GPIOD->MODER & ~(GPIO_MODER_MODE8 | GPIO_MODER_MODE9))
|
||||
| GPIO_MODER_MODER8_AF | GPIO_MODER_MODER9_AF;
|
||||
// AF0 for USART3 @ PD8/PD9
|
||||
GPIOD->AFR[1] = GPIOD->AFR[1] & ~(GPIO_AFRH_AFSEL8 | GPIO_AFRH_AFSEL9);
|
||||
// enable USART3 clocking
|
||||
RCC->APBENR1 |= RCC_APBENR1_USART3EN;
|
||||
// baudrate 115200
|
||||
USART3->BRR = 640000 / 1152;
|
||||
// eol character: '/n'
|
||||
USART3->CR2 = USART_CR2_ADD_VAL('\n');
|
||||
// enable DMA transmission
|
||||
USART3->CR3 = USART_CR3_DMAT | USART_CR3_DMAR;
|
||||
// set up DMA channels: 2 - Tx, 3 - Rx
|
||||
// Tx channel: mem++, mem->periph, 8bit, compl.&err. irq
|
||||
DMA1_Channel2->CCR = DMATXCCR;
|
||||
DMA1_Channel2->CPAR = (uint32_t) &USART3->TDR; // peripherial address
|
||||
// Rx channel: mem++, periph->mem, 8bit, compl.&err. irq
|
||||
DMA1_Channel3->CCR = DMARXCCR;
|
||||
DMA1_Channel3->CPAR = (uint32_t) &USART3->RDR; // peripherial address
|
||||
DMA1_Channel3->CNDTR = UARTBUFSZ;
|
||||
DMA1_Channel3->CMAR = (uint32_t)&rbuf[rbufno];
|
||||
// set up DMAMUX channels: 55 - USART3_TX, 54 - USART3_RX
|
||||
// enumeration of DMAMUX starts from 0 (DMA - from 1)!
|
||||
DMAMUX1_Channel1->CCR = 55;
|
||||
DMAMUX1_Channel2->CCR = 54;
|
||||
// charmatch interrupt, enable transmitter and receiver, enable usart
|
||||
USART3->CR1 = USART_CR1_CMIE | USART_CR1_TE | USART_CR1_RE | USART_CR1_UE;
|
||||
USART3->ICR = 0xffffffff; // clear all flags
|
||||
DMA1_Channel3->CCR = DMARXCCR | DMA_CCR_EN; // start receiving right now
|
||||
NVIC_EnableIRQ(USART3_4_IRQn);
|
||||
NVIC_EnableIRQ(DMA1_Channel2_3_IRQn);
|
||||
}
|
||||
|
||||
static void mymemcpy(char *dest, const char *src, int len){
|
||||
while(len--) *dest++ = *src++;
|
||||
}
|
||||
|
||||
int usart3_send(const char *str, int len){
|
||||
int rest = UARTBUFSZ - txlen[tbufno];
|
||||
if(rest == 0 && !txrdy) return 0; // buffer is full while transmission in process
|
||||
if(len < rest) rest = len;
|
||||
mymemcpy(tbuf[tbufno] + txlen[tbufno], str, rest);
|
||||
txlen[tbufno] += rest;
|
||||
if(!txrdy) return rest;
|
||||
if(txlen[tbufno] == UARTBUFSZ) usart3_sendbuf();
|
||||
if(rest == len) return len;
|
||||
len -= rest;
|
||||
// now fill another - empty - buffer
|
||||
if(len > UARTBUFSZ) len = UARTBUFSZ;
|
||||
mymemcpy(tbuf[tbufno], str + rest, len);
|
||||
txlen[tbufno] = len;
|
||||
return rest + len;
|
||||
}
|
||||
|
||||
int usart3_sendstr(const char *str){
|
||||
int l = strlen(str);
|
||||
return usart3_send(str, l);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief usart3_sendbuf - send current buffer
|
||||
*/
|
||||
void usart3_sendbuf(){
|
||||
if(!txrdy || txlen[tbufno] == 0) return;
|
||||
// set up DMA
|
||||
DMA1_Channel2->CCR = DMATXCCR;
|
||||
DMA1_Channel2->CMAR = (uint32_t)&tbuf[tbufno];
|
||||
DMA1_Channel2->CNDTR = txlen[tbufno];
|
||||
USART3->ICR = USART_ICR_TCCF; // clear TC flag
|
||||
txrdy = 0;
|
||||
// activate DMA
|
||||
DMA1_Channel2->CCR = DMATXCCR | DMA_CCR_EN;
|
||||
tbufno = !tbufno; // swap buffers
|
||||
txlen[tbufno] = 0;
|
||||
}
|
||||
|
||||
// return amount of bytes sents
|
||||
int usart3_send_blocking(const char *str, int len){
|
||||
if(!txrdy) return 0;
|
||||
USART3->CR1 |= USART_CR1_TE;
|
||||
for(int i = 0; i < len; ++i){
|
||||
while(!(USART3->ISR & USART_ISR_TXE_TXFNF));
|
||||
USART3->TDR = *str++;
|
||||
}
|
||||
return len;
|
||||
}
|
||||
|
||||
// interrupt by '\n'
|
||||
void usart3_4_isr(){
|
||||
if(USART3->ISR & USART_ISR_CMF){ // got '\n' @ USART3
|
||||
DMA1_Channel3->CCR = DMARXCCR;
|
||||
if(!bufovr){ // forget about broken line @ buffer overflow
|
||||
rxrdy = 1;
|
||||
int l = UARTBUFSZ - DMA1_Channel3->CNDTR - 1; // strlen
|
||||
rxlen[rbufno] = l;
|
||||
rbuf[rbufno][l] = 0;
|
||||
rbufno = !rbufno;
|
||||
}else{
|
||||
bufovr = 0;
|
||||
wasbufovr = 1;
|
||||
}
|
||||
// reload DMA Rx with next buffer
|
||||
DMA1_Channel3->CMAR = (uint32_t)&rbuf[rbufno];
|
||||
DMA1_Channel3->CNDTR = UARTBUFSZ;
|
||||
DMA1_Channel3->CCR = DMARXCCR | DMA_CCR_EN;
|
||||
}
|
||||
USART3->ICR = 0xffffffff; // clear all flags
|
||||
}
|
||||
|
||||
// ch2 - Tx, ch3 - Rx
|
||||
void dma1_channel2_3_isr(){
|
||||
uint32_t isr = DMA1->ISR;
|
||||
if(isr & (DMA_ISR_TCIF2 | DMA_ISR_TEIF2)){ // transfer complete or error
|
||||
txrdy = 1;
|
||||
//DMA1_Channel2->CCR = DMATXCCR;
|
||||
}
|
||||
if(isr & (DMA_ISR_TCIF3 | DMA_ISR_TEIF3)){ // receive complete or error -> buffer overflow
|
||||
if(rbuf[rbufno][UARTBUFSZ-1] != '\n'){ // last symbol is not a newline
|
||||
bufovr = 1;
|
||||
DMA1_Channel3->CCR = DMARXCCR;
|
||||
DMA1_Channel3->CNDTR = UARTBUFSZ;
|
||||
DMA1_Channel3->CCR = DMARXCCR | DMA_CCR_EN;
|
||||
}
|
||||
}
|
||||
DMA1->IFCR = 0xffffffff; // clear all flags
|
||||
}
|
||||
1
G0:G070/usart/usart.cflags
Normal file
1
G0:G070/usart/usart.cflags
Normal file
@ -0,0 +1 @@
|
||||
-std=c17
|
||||
3
G0:G070/usart/usart.config
Normal file
3
G0:G070/usart/usart.config
Normal file
@ -0,0 +1,3 @@
|
||||
#define EBUG
|
||||
#define STM32G0
|
||||
#define STM32G070xx
|
||||
1
G0:G070/usart/usart.creator
Normal file
1
G0:G070/usart/usart.creator
Normal file
@ -0,0 +1 @@
|
||||
[General]
|
||||
171
G0:G070/usart/usart.creator.user
Normal file
171
G0:G070/usart/usart.creator.user
Normal file
@ -0,0 +1,171 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<!DOCTYPE QtCreatorProject>
|
||||
<!-- Written by QtCreator 8.0.2, 2022-12-22T21:13:47. -->
|
||||
<qtcreator>
|
||||
<data>
|
||||
<variable>EnvironmentId</variable>
|
||||
<value type="QByteArray">{7bd84e39-ca37-46d3-be9d-99ebea85bc0d}</value>
|
||||
</data>
|
||||
<data>
|
||||
<variable>ProjectExplorer.Project.ActiveTarget</variable>
|
||||
<value type="int">0</value>
|
||||
</data>
|
||||
<data>
|
||||
<variable>ProjectExplorer.Project.EditorSettings</variable>
|
||||
<valuemap type="QVariantMap">
|
||||
<value type="bool" key="EditorConfiguration.AutoIndent">true</value>
|
||||
<value type="bool" key="EditorConfiguration.AutoSpacesForTabs">false</value>
|
||||
<value type="bool" key="EditorConfiguration.CamelCaseNavigation">true</value>
|
||||
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.0">
|
||||
<value type="QString" key="language">Cpp</value>
|
||||
<valuemap type="QVariantMap" key="value">
|
||||
<value type="QByteArray" key="CurrentPreferences">CppGlobal</value>
|
||||
</valuemap>
|
||||
</valuemap>
|
||||
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.1">
|
||||
<value type="QString" key="language">QmlJS</value>
|
||||
<valuemap type="QVariantMap" key="value">
|
||||
<value type="QByteArray" key="CurrentPreferences">QmlJSGlobal</value>
|
||||
</valuemap>
|
||||
</valuemap>
|
||||
<value type="int" key="EditorConfiguration.CodeStyle.Count">2</value>
|
||||
<value type="QByteArray" key="EditorConfiguration.Codec">KOI8-R</value>
|
||||
<value type="bool" key="EditorConfiguration.ConstrainTooltips">false</value>
|
||||
<value type="int" key="EditorConfiguration.IndentSize">4</value>
|
||||
<value type="bool" key="EditorConfiguration.KeyboardTooltips">false</value>
|
||||
<value type="int" key="EditorConfiguration.MarginColumn">80</value>
|
||||
<value type="bool" key="EditorConfiguration.MouseHiding">true</value>
|
||||
<value type="bool" key="EditorConfiguration.MouseNavigation">true</value>
|
||||
<value type="int" key="EditorConfiguration.PaddingMode">1</value>
|
||||
<value type="bool" key="EditorConfiguration.PreferSingleLineComments">false</value>
|
||||
<value type="bool" key="EditorConfiguration.ScrollWheelZooming">true</value>
|
||||
<value type="bool" key="EditorConfiguration.ShowMargin">false</value>
|
||||
<value type="int" key="EditorConfiguration.SmartBackspaceBehavior">0</value>
|
||||
<value type="bool" key="EditorConfiguration.SmartSelectionChanging">true</value>
|
||||
<value type="bool" key="EditorConfiguration.SpacesForTabs">true</value>
|
||||
<value type="int" key="EditorConfiguration.TabKeyBehavior">0</value>
|
||||
<value type="int" key="EditorConfiguration.TabSize">8</value>
|
||||
<value type="bool" key="EditorConfiguration.UseGlobal">true</value>
|
||||
<value type="bool" key="EditorConfiguration.UseIndenter">false</value>
|
||||
<value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value>
|
||||
<value type="bool" key="EditorConfiguration.addFinalNewLine">true</value>
|
||||
<value type="bool" key="EditorConfiguration.cleanIndentation">false</value>
|
||||
<value type="bool" key="EditorConfiguration.cleanWhitespace">true</value>
|
||||
<value type="QString" key="EditorConfiguration.ignoreFileTypes">*.md, *.MD, Makefile</value>
|
||||
<value type="bool" key="EditorConfiguration.inEntireDocument">false</value>
|
||||
<value type="bool" key="EditorConfiguration.skipTrailingWhitespace">true</value>
|
||||
</valuemap>
|
||||
</data>
|
||||
<data>
|
||||
<variable>ProjectExplorer.Project.PluginSettings</variable>
|
||||
<valuemap type="QVariantMap">
|
||||
<valuemap type="QVariantMap" key="AutoTest.ActiveFrameworks">
|
||||
<value type="bool" key="AutoTest.Framework.Boost">true</value>
|
||||
<value type="bool" key="AutoTest.Framework.CTest">false</value>
|
||||
<value type="bool" key="AutoTest.Framework.Catch">true</value>
|
||||
<value type="bool" key="AutoTest.Framework.GTest">true</value>
|
||||
<value type="bool" key="AutoTest.Framework.QtQuickTest">true</value>
|
||||
<value type="bool" key="AutoTest.Framework.QtTest">true</value>
|
||||
</valuemap>
|
||||
<valuemap type="QVariantMap" key="AutoTest.CheckStates"/>
|
||||
<value type="int" key="AutoTest.RunAfterBuild">0</value>
|
||||
<value type="bool" key="AutoTest.UseGlobal">true</value>
|
||||
<valuemap type="QVariantMap" key="ClangTools">
|
||||
<value type="bool" key="ClangTools.AnalyzeOpenFiles">true</value>
|
||||
<value type="bool" key="ClangTools.BuildBeforeAnalysis">true</value>
|
||||
<value type="QString" key="ClangTools.DiagnosticConfig">Builtin.DefaultTidyAndClazy</value>
|
||||
<value type="int" key="ClangTools.ParallelJobs">2</value>
|
||||
<valuelist type="QVariantList" key="ClangTools.SelectedDirs"/>
|
||||
<valuelist type="QVariantList" key="ClangTools.SelectedFiles"/>
|
||||
<valuelist type="QVariantList" key="ClangTools.SuppressedDiagnostics"/>
|
||||
<value type="bool" key="ClangTools.UseGlobalSettings">true</value>
|
||||
</valuemap>
|
||||
</valuemap>
|
||||
</data>
|
||||
<data>
|
||||
<variable>ProjectExplorer.Project.Target.0</variable>
|
||||
<valuemap type="QVariantMap">
|
||||
<value type="QString" key="DeviceType">Desktop</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{65a14f9e-e008-4c1b-89df-4eaa4774b6e3}</value>
|
||||
<value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
|
||||
<value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
|
||||
<value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
|
||||
<valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0">
|
||||
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/Big/Data/00__Electronics/STM32/G0-nolib/usart</value>
|
||||
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
|
||||
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
|
||||
<valuelist type="QVariantList" key="GenericProjectManager.GenericMakeStep.BuildTargets">
|
||||
<value type="QString">all</value>
|
||||
</valuelist>
|
||||
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericMakeStep</value>
|
||||
</valuemap>
|
||||
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Сборка</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Сборка</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
|
||||
</valuemap>
|
||||
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
|
||||
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
|
||||
<valuelist type="QVariantList" key="GenericProjectManager.GenericMakeStep.BuildTargets">
|
||||
<value type="QString">clean</value>
|
||||
</valuelist>
|
||||
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericMakeStep</value>
|
||||
</valuemap>
|
||||
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Очистка</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Очистка</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
|
||||
</valuemap>
|
||||
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
|
||||
<value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
|
||||
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.CustomParsers"/>
|
||||
<value type="bool" key="ProjectExplorer.BuildConfiguration.ParseStandardOutput">false</value>
|
||||
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">По умолчанию</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericBuildConfiguration</value>
|
||||
</valuemap>
|
||||
<value type="int" key="ProjectExplorer.Target.BuildConfigurationCount">1</value>
|
||||
<valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
|
||||
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
|
||||
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Развёртывание</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Развёртывание</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
|
||||
</valuemap>
|
||||
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
|
||||
<valuemap type="QVariantMap" key="ProjectExplorer.DeployConfiguration.CustomData"/>
|
||||
<value type="bool" key="ProjectExplorer.DeployConfiguration.CustomDataEnabled">false</value>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.DefaultDeployConfiguration</value>
|
||||
</valuemap>
|
||||
<value type="int" key="ProjectExplorer.Target.DeployConfigurationCount">1</value>
|
||||
<valuemap type="QVariantMap" key="ProjectExplorer.Target.RunConfiguration.0">
|
||||
<valuelist type="QVariantList" key="CustomOutputParsers"/>
|
||||
<value type="int" key="PE.EnvironmentAspect.Base">2</value>
|
||||
<valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
|
||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.CustomExecutableRunConfiguration</value>
|
||||
<value type="QString" key="ProjectExplorer.RunConfiguration.BuildKey"></value>
|
||||
<value type="bool" key="RunConfiguration.UseCppDebugger">false</value>
|
||||
<value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
|
||||
<value type="bool" key="RunConfiguration.UseQmlDebugger">false</value>
|
||||
<value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
|
||||
</valuemap>
|
||||
<value type="int" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
|
||||
</valuemap>
|
||||
</data>
|
||||
<data>
|
||||
<variable>ProjectExplorer.Project.TargetCount</variable>
|
||||
<value type="int">1</value>
|
||||
</data>
|
||||
<data>
|
||||
<variable>ProjectExplorer.Project.Updater.FileVersion</variable>
|
||||
<value type="int">22</value>
|
||||
</data>
|
||||
<data>
|
||||
<variable>Version</variable>
|
||||
<value type="int">22</value>
|
||||
</data>
|
||||
</qtcreator>
|
||||
1
G0:G070/usart/usart.cxxflags
Normal file
1
G0:G070/usart/usart.cxxflags
Normal file
@ -0,0 +1 @@
|
||||
-std=c++17
|
||||
4
G0:G070/usart/usart.files
Normal file
4
G0:G070/usart/usart.files
Normal file
@ -0,0 +1,4 @@
|
||||
main.c
|
||||
usart.c
|
||||
|
||||
usart.h
|
||||
28
G0:G070/usart/usart.h
Normal file
28
G0:G070/usart/usart.h
Normal file
@ -0,0 +1,28 @@
|
||||
/*
|
||||
* This file is part of the usart project.
|
||||
* Copyright 2023 Edward V. Emelianov <edward.emelianoff@gmail.com>.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define UARTBUFSZ (64)
|
||||
|
||||
void usart3_setup();
|
||||
int usart3_send_blocking(const char *str, int len);
|
||||
int usart3_send(const char *str, int len);
|
||||
void usart3_sendbuf();
|
||||
char *usart3_getline(int *wasbo);
|
||||
int usart3_sendstr(const char *str);
|
||||
4
G0:G070/usart/usart.includes
Normal file
4
G0:G070/usart/usart.includes
Normal file
@ -0,0 +1,4 @@
|
||||
.
|
||||
../inc
|
||||
../inc/Fx
|
||||
../inc/cm
|
||||
Loading…
x
Reference in New Issue
Block a user