From b3df20a08974584076e802d5f7061a8a8cb96930 Mon Sep 17 00:00:00 2001 From: root Date: Thu, 16 Jul 2015 08:35:16 +0100 Subject: initial commit --- .gitignore | 5 + .gitmodules | 3 + Makefile | 11 ++ Makefile.include | 48 +++++ Makefile.rules | 252 ++++++++++++++++++++++++ app/Makefile | 61 ++++++ app/app.ld | 38 ++++ app/gdb.script | 2 + app/i2c.c | 281 ++++++++++++++++++++++++++ app/i2c.h | 2 + app/lcd.c | 478 +++++++++++++++++++++++++++++++++++++++++++++ app/led.c | 48 +++++ app/main.c | 58 ++++++ app/project.h | 21 ++ app/prototypes.h | 63 ++++++ app/ring.c | 68 +++++++ app/ring.h | 7 + app/ticker.c | 51 +++++ app/usart.c | 191 ++++++++++++++++++ board/STM32F103R_BOARD.cfg | 3 + interface/j-link.cfg | 5 + libopencm3 | 1 + stm32-f103.cfg | 6 + 23 files changed, 1703 insertions(+) create mode 100644 .gitignore create mode 100644 .gitmodules create mode 100644 Makefile create mode 100644 Makefile.include create mode 100644 Makefile.rules create mode 100644 app/Makefile create mode 100644 app/app.ld create mode 100644 app/gdb.script create mode 100644 app/i2c.c create mode 100644 app/i2c.h create mode 100644 app/lcd.c create mode 100644 app/led.c create mode 100644 app/main.c create mode 100644 app/project.h create mode 100644 app/prototypes.h create mode 100644 app/ring.c create mode 100644 app/ring.h create mode 100644 app/ticker.c create mode 100644 app/usart.c create mode 100644 board/STM32F103R_BOARD.cfg create mode 100644 interface/j-link.cfg create mode 160000 libopencm3 create mode 100644 stm32-f103.cfg diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..da2d32f --- /dev/null +++ b/.gitignore @@ -0,0 +1,5 @@ +app/*.o +app/*.d +app/*.elf +app/*.map +app/*~ diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..29e93ae --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "libopencm3"] + path = libopencm3 + url = git://github.com/libopencm3/libopencm3.git diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..7b28523 --- /dev/null +++ b/Makefile @@ -0,0 +1,11 @@ +default:app.dummy + +app.dummy: + make -C app + +libopencm3.dummy: + make -C libopencm3 + +clean: + make -C app $@ + make -C libopencm3 $@ diff --git a/Makefile.include b/Makefile.include new file mode 100644 index 0000000..3eccc25 --- /dev/null +++ b/Makefile.include @@ -0,0 +1,48 @@ +## +## This file is part of the libopencm3 project. +## +## Copyright (C) 2009 Uwe Hermann +## Copyright (C) 2010 Piotr Esden-Tempski +## +## This library is free software: you can redistribute it and/or modify +## it under the terms of the GNU Lesser General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## This library 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 Lesser General Public License for more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this library. If not, see . +## + +LIBNAME = opencm3_stm32f1 +DEFS = -DSTM32F1 + +FP_FLAGS ?= -msoft-float +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd + +################################################################################ +# OpenOCD specific variables + +#OOCD ?= openocd +#OOCD_INTERFACE ?= flossjtag +#OOCD_BOARD ?= olimex_stm32_h103 + +OOCD ?= openocd +OOCD_INTERFACE ?= ../interface/j-link.cfg +OOCD_BOARD ?= ../board/STM32F103R_BOARD.cfg + +################################################################################ +# Black Magic Probe specific variables +# Set the BMP_PORT to a serial port and then BMP is used for flashing +BMP_PORT ?= + +################################################################################ +# texane/stlink specific variables +#STLINK_PORT ?= :4242 + + +include ../Makefile.rules diff --git a/Makefile.rules b/Makefile.rules new file mode 100644 index 0000000..0e521e6 --- /dev/null +++ b/Makefile.rules @@ -0,0 +1,252 @@ +# +## This file is part of the libopencm3 project. +## +## Copyright (C) 2009 Uwe Hermann +## Copyright (C) 2010 Piotr Esden-Tempski +## Copyright (C) 2013 Frantisek Burian +## +## This library is free software: you can redistribute it and/or modify +## it under the terms of the GNU Lesser General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## This library 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 Lesser General Public License for more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this library. If not, see . +## + +# Be silent per default, but 'make V=1' will show all compiler calls. +ifneq ($(V),1) +Q := @ +NULL := 2>/dev/null +endif + +############################################################################### +# Executables + +PREFIX ?= arm-none-eabi + +CC := $(PREFIX)-gcc +CXX := $(PREFIX)-g++ +LD := $(PREFIX)-gcc +AR := $(PREFIX)-ar +AS := $(PREFIX)-as +OBJCOPY := $(PREFIX)-objcopy +OBJDUMP := $(PREFIX)-objdump +GDB := $(PREFIX)-gdb +STFLASH = $(shell which st-flash) +STYLECHECK := /checkpatch.pl +STYLECHECKFLAGS := --no-tree -f --terse --mailback +STYLECHECKFILES := $(shell find . -name '*.[ch]') + + +############################################################################### +# Source files + +LDSCRIPT ?= $(BINARY).ld + +#OBJS += $(BINARY).o + + +ifeq ($(strip $(OPENCM3_DIR)),) +# user has not specified the library path, so we try to detect it + +# where we search for the library +LIBPATHS := ./libopencm3 ../libopencm3 + +OPENCM3_DIR := $(wildcard $(LIBPATHS:=/locm3.sublime-project)) +OPENCM3_DIR := $(firstword $(dir $(OPENCM3_DIR))) + +ifeq ($(strip $(OPENCM3_DIR)),) +$(warning Cannot find libopencm3 library in the standard search paths.) +$(error Please specify it through OPENCM3_DIR variable!) +endif +endif + +ifeq ($(V),1) +$(info Using $(OPENCM3_DIR) path to library) +endif + +INCLUDE_DIR = $(OPENCM3_DIR)/include +LIB_DIR = $(OPENCM3_DIR)/lib +SCRIPT_DIR = $(OPENCM3_DIR)/scripts + +############################################################################### +# C flags + +#CFLAGS += -Os -g +CFLAGS += -g +CFLAGS += -Wextra -Wimplicit-function-declaration +CFLAGS += -Wmissing-prototypes -Wstrict-prototypes +CFLAGS += -fno-common -ffunction-sections -fdata-sections + +############################################################################### +# C++ flags + +CXXFLAGS += -Os -g +CXXFLAGS += -Wextra -Wshadow -Wredundant-decls -Weffc++ +CXXFLAGS += -fno-common -ffunction-sections -fdata-sections + +############################################################################### +# C & C++ preprocessor common flags + +CPPFLAGS += -MD +CPPFLAGS += -Wall -Wundef + +INCLUDES = -I$(INCLUDE_DIR) +DEFINES = $(DEFS) + +CPPFLAGS += $(INCLUDES) $(DEFINES) + +############################################################################### +# Linker flags + +LDFLAGS += --static -nostartfiles +LDFLAGS += -L$(LIB_DIR) +LDFLAGS += -T$(LDSCRIPT) +LDFLAGS += -Wl,-Map=$(*).map +LDFLAGS += -Wl,--gc-sections +ifeq ($(V),99) +LDFLAGS += -Wl,--print-gc-sections +endif + +############################################################################### +# Used libraries + +LDLIBS += -l$(LIBNAME) +LDLIBS += -Wl,--start-group -lc -lnosys -lgcc -Wl,--end-group + +############################################################################### +############################################################################### +############################################################################### + +.SUFFIXES: .elf .bin .hex .srec .list .map .images .dfu +.SECONDEXPANSION: +.SECONDARY: + +all: elf + +elf: $(BINARY).elf +bin: $(BINARY).bin +hex: $(BINARY).hex +srec: $(BINARY).srec +list: $(BINARY).list + +images: $(BINARY).images +flash: $(BINARY).flash + +%.images: %.bin %.hex %.srec %.list %.map %.dfu + @#printf "*** $* images generated ***\n" + +%.bin: %.elf + @#printf " OBJCOPY $(*).bin\n" + $(Q)$(OBJCOPY) -Obinary $(*).elf $(*).bin + +%.hex: %.elf + @#printf " OBJCOPY $(*).hex\n" + $(Q)$(OBJCOPY) -Oihex $(*).elf $(*).hex + +%.dfu: %.elf + @#printf " OBJCOPY $(*).dfu\n" + $(Q)$(OBJCOPY) -Obinary $(*).elf $(*).dfu + +%.srec: %.elf + @#printf " OBJCOPY $(*).srec\n" + $(Q)$(OBJCOPY) -Osrec $(*).elf $(*).srec + +%.list: %.elf + @#printf " OBJDUMP $(*).list\n" + $(Q)$(OBJDUMP) -S $(*).elf > $(*).list + +fish: + echo %.elf %.map: $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a + echo $(BINARY).elf + +%.elf %.map: $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a + @#printf " LD $(*).elf\n" + $(Q)$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(*).elf + +%.o: %.c + @#printf " CC $(*).c\n" + $(Q)$(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $(*).o -c $(*).c + +%.o: %.cxx + @#printf " CXX $(*).cxx\n" + $(Q)$(CXX) $(CXXFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $(*).o -c $(*).cxx + +%.o: %.cpp + @#printf " CXX $(*).cpp\n" + $(Q)$(CXX) $(CXXFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $(*).o -c $(*).cpp + +clean: + @#printf " CLEAN\n" + $(Q)$(RM) *.o *.d *.elf *.bin *.hex *.srec *.list *.map *~ *.dfu ${EXTRA_CLEAN} + +stylecheck: $(STYLECHECKFILES:=.stylecheck) +styleclean: $(STYLECHECKFILES:=.styleclean) + +# the cat is due to multithreaded nature - we like to have consistent chunks of text on the output +%.stylecheck: % + $(Q)$(SCRIPT_DIR)$(STYLECHECK) $(STYLECHECKFLAGS) $* > $*.stylecheck; \ + if [ -s $*.stylecheck ]; then \ + cat $*.stylecheck; \ + else \ + rm -f $*.stylecheck; \ + fi; + +%.styleclean: + $(Q)rm -f $*.stylecheck; + + +%.stlink-flash: %.bin + @printf " FLASH $<\n" + $(Q)$(STFLASH) write $(*).bin 0x8000000 + +ifeq ($(STLINK_PORT),) +ifeq ($(BMP_PORT),) +ifeq ($(OOCD_SERIAL),) +%.flash: %.hex + @printf " FLASH $<\n" + @# IMPORTANT: Don't use "resume", only "reset" will work correctly! + $(Q)$(OOCD) -f $(OOCD_INTERFACE) \ + -f $(OOCD_BOARD) \ + -c "init" -c "reset init" \ + -c "flash write_image erase $(*).hex" \ + -c "reset" \ + -c "shutdown" $(NULL) +else +%.flash: %.hex + @printf " FLASH $<\n" + @# IMPORTANT: Don't use "resume", only "reset" will work correctly! + $(Q)$(OOCD) -f $(OOCD_INTERFACE) \ + -f $(OOCD_BOARD) \ + -c "ft2232_serial $(OOCD_SERIAL)" \ + -c "init" -c "reset init" \ + -c "flash write_image erase $(*).hex" \ + -c "reset" \ + -c "shutdown" $(NULL) +endif +else +%.flash: %.elf + @printf " GDB $(*).elf (flash)\n" + $(Q)$(GDB) --batch \ + -ex 'target extended-remote $(BMP_PORT)' \ + -x $(SCRIPT_DIR)/black_magic_probe_flash.scr \ + $(*).elf +endif +else +%.flash: %.elf + @printf " GDB $(*).elf (flash)\n" + $(Q)$(GDB) --batch \ + -ex 'target extended-remote $(STLINK_PORT)' \ + -x $(SCRIPT_DIR)/stlink_flash.scr \ + $(*).elf +endif + +.PHONY: images clean stylecheck styleclean elf bin hex srec list + +-include $(OBJS:.o=.d) diff --git a/app/Makefile b/app/Makefile new file mode 100644 index 0000000..0ed735d --- /dev/null +++ b/app/Makefile @@ -0,0 +1,61 @@ +## +## This file is part of the libopencm3 project. +## +## Copyright (C) 2009 Uwe Hermann +## +## This library is free software: you can redistribute it and/or modify +## it under the terms of the GNU Lesser General Public License as published by +## the Free Software Foundation, either version 3 of the License, or +## (at your option) any later version. +## +## This library 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 Lesser General Public License for more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this library. If not, see . +## + +CPROTO=cproto +PROG=app + +V=1 +default: ${PROG}.elf + +CSRCS=i2c.c lcd.c led.c main.c ring.c ticker.c usart.c + + +BINARY = ${PROG} +OBJS = ${CSRCS:%.c=%.o} + +include ../Makefile.include + +DID=$(shell printf '\#include "id.h"\nID_PRODUCT' | ${CC} -I.. -E - | grep -v ^\# ) + +INCLUDES += -I.. + +#dfu:${PROG}.dfu +# dfu-util -R -a 0 -d 1d6b:${DID} -s 0x08002000:leave -D $< + +program: ${PROG}.hex + echo init | nc -t localhost 4444 + echo reset init | nc -t localhost 4444 + echo flash write_image erase ${PWD}/$< | nc -t localhost 4444 + echo reset run | nc -t localhost 4444 + +ds: + $(Q)$(OOCD) -f $(OOCD_INTERFACE) \ + -f $(OOCD_BOARD) + +debug: ${PROG}.elf + ${PREFIX}-gdb -x gdb.script ${PROG}.elf + +# openocd + +protos: ${CSRCS} + echo -n > prototypes.h + ${CPROTO} $(INCLUDES) $(DEFINES) -e -v ${CSRCS} > prototypes.h.tmp + mv -f prototypes.h.tmp prototypes.h + + diff --git a/app/app.ld b/app/app.ld new file mode 100644 index 0000000..0fb2378 --- /dev/null +++ b/app/app.ld @@ -0,0 +1,38 @@ +/* + * This file is part of the libopencm3 project. + * + * Copyright (C) 2009 Uwe Hermann + * + * This library is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This library 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 Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this library. If not, see . + */ + +/* Linker script for Olimex STM32-H103 (STM32F103RBT6, 128K flash, 20K RAM). */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K +} + +/* Include the common ld script. */ +INCLUDE libopencm3_stm32f1.ld + + + + +/* PROVIDE(_stack = dfu_shared_location ); */ + + + diff --git a/app/gdb.script b/app/gdb.script new file mode 100644 index 0000000..7cf9d09 --- /dev/null +++ b/app/gdb.script @@ -0,0 +1,2 @@ +target remote localhost:3333 +cont diff --git a/app/i2c.c b/app/i2c.c new file mode 100644 index 0000000..74aed9d --- /dev/null +++ b/app/i2c.c @@ -0,0 +1,281 @@ +#include "project.h" + + +#define I2C I2C1 + +#define SCL GPIO6 +#define SDA GPIO7 + +void +i2c_clear_start (uint32_t i2c) +{ + I2C_CR1 (i2c) &= ~(uint32_t) I2C_CR1_START; +} + +#if 0 +static void +i2cp_ds (void) +{ + uint32_t i2c = I2C; + printf ("CR1=%08x CR2=%08x\r\n", (unsigned) I2C_CR1 (i2c), + (unsigned) I2C_CR2 (i2c)); + printf ("SR1=%08x SR2=%08x\r\n", (unsigned) I2C_SR1 (i2c), + (unsigned) I2C_SR2 (i2c)); + + + usart1_drain (); +} +#endif + + + +void +i2cp_start (void) +{ + i2c_send_start (I2C); + while (!((I2C_SR1 (I2C) & I2C_SR1_SB) + & (I2C_SR2 (I2C) & (I2C_SR2_MSL | I2C_SR2_BUSY)))); +} + +void +i2cp_abort_start (void) +{ + i2c_clear_start (I2C); + delay_us (10); +} + +void +i2cp_stop (void) +{ + i2c_send_stop (I2C); +} + + +void +i2cp_abort_stop (void) +{ + i2c_clear_stop (I2C); + delay_us (10); +} + +int +i2cp_send_data (uint8_t v) +{ + uint32_t reg; + + i2c_send_data (I2C, v); + + while (! + ((reg = + I2C_SR1 (I2C)) & (I2C_SR1_BTF | I2C_SR1_BERR | I2C_SR1_ARLO | + I2C_SR1_AF | I2C_SR1_PECERR | I2C_SR1_TIMEOUT | + I2C_SR1_SMBALERT))); + I2C_SR1 (I2C) = + reg & ~(I2C_SR1_BERR | I2C_SR1_ARLO | I2C_SR1_AF | I2C_SR1_PECERR | + I2C_SR1_TIMEOUT | I2C_SR1_SMBALERT); + + + return (reg & I2C_SR1_BTF) ? 0 : -1; +} + +/*0 on success 1 on failure*/ +int +i2cp_start_transaction (uint8_t a, int wnr) +{ + uint32_t reg; + uint32_t __attribute__ ((unused)) dummy; + + i2c_send_start (I2C); + while (!((I2C_SR1 (I2C) & I2C_SR1_SB) + & (I2C_SR2 (I2C) & (I2C_SR2_MSL | I2C_SR2_BUSY)))); + + i2c_send_7bit_address (I2C, a, wnr); + + while (! + ((reg = + I2C_SR1 (I2C)) & (I2C_SR1_ADDR | I2C_SR1_BERR | I2C_SR1_ARLO | + I2C_SR1_AF | I2C_SR1_PECERR | I2C_SR1_TIMEOUT | + I2C_SR1_SMBALERT))); + dummy = I2C_SR2 (I2C); + + I2C_SR1 (I2C) = + reg & ~(I2C_SR1_BERR | I2C_SR1_ARLO | I2C_SR1_AF | I2C_SR1_PECERR | + I2C_SR1_TIMEOUT | I2C_SR1_SMBALERT); + + + return (reg == 0x82) ? 0 : -1; +} + + +static int mutex = 0; + +int +i2cp_lock (void) +{ + if (__sync_add_and_fetch (&mutex, 1) != 1) + { + __sync_sub_and_fetch (&mutex, 1); + return -1; + } + + return 0; +} + + +void +i2cp_unlock (void) +{ + __sync_sub_and_fetch (&mutex, 1); +} + + /*This is stupid, it bit bangs a dummy transaction to get the host i2c controller back in the game */ +static void +i2cp_reset_sm (void) +{ + int i; + + gpio_set_mode (GPIOB, GPIO_MODE_OUTPUT_50_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, GPIO_I2C1_SCL | GPIO_I2C1_SDA); + + gpio_set (GPIOB, GPIO_I2C1_SDA); + gpio_set (GPIOB, GPIO_I2C1_SCL); + delay_us (10); + gpio_clear (GPIOB, GPIO_I2C1_SDA); + delay_us (10); + gpio_clear (GPIOB, GPIO_I2C1_SCL); + + for (i = 0; i < 9; ++i) + { + delay_us (10); + gpio_set (GPIOB, GPIO_I2C1_SCL); + delay_us (10); + gpio_clear (GPIOB, GPIO_I2C1_SCL); + delay_us (10); + } + gpio_set (GPIOB, GPIO_I2C1_SCL); + delay_us (10); + gpio_set (GPIOB, GPIO_I2C1_SDA); + delay_us (10); + +} + +void +i2cp_start_dma (uint8_t * buf, int len) +{ + dma_channel_reset (DMA1, DMA_CHANNEL6); + dma_set_peripheral_address (DMA1, DMA_CHANNEL6, (uint32_t) & I2C1_DR); + dma_set_memory_address (DMA1, DMA_CHANNEL6, (uint32_t) buf); + dma_set_number_of_data (DMA1, DMA_CHANNEL6, len); + dma_set_read_from_memory (DMA1, DMA_CHANNEL6); + dma_enable_memory_increment_mode (DMA1, DMA_CHANNEL6); + dma_set_peripheral_size (DMA1, DMA_CHANNEL6, DMA_CCR_PSIZE_8BIT); + dma_set_memory_size (DMA1, DMA_CHANNEL6, DMA_CCR_MSIZE_8BIT); + dma_set_priority (DMA1, DMA_CHANNEL6, DMA_CCR_PL_MEDIUM); + dma_enable_transfer_complete_interrupt (DMA1, DMA_CHANNEL6); + dma_enable_transfer_error_interrupt (DMA1, DMA_CHANNEL6); + dma_enable_channel (DMA1, DMA_CHANNEL6); + + i2c_enable_dma (I2C1); + +} + +int +i2cp_dma_in_progress (void) +{ + return !(DMA1_ISR & (DMA_ISR_TCIF6 | DMA_ISR_TEIF6)); +} + +void +i2cp_stop_dma (void) +{ + DMA1_IFCR |= DMA_IFCR_CTCIF7 | DMA_IFCR_CTEIF6 | DMA_IFCR_CGIF6; + + dma_disable_transfer_complete_interrupt (DMA1, DMA_CHANNEL6); + dma_disable_transfer_error_interrupt (DMA1, DMA_CHANNEL6); + + i2c_disable_dma (I2C1); + dma_disable_channel (DMA1, DMA_CHANNEL7); +} + +void +i2cp_reset (void) +{ + while (i2cp_lock ()); + i2cp_start (); + i2cp_abort_start (); + i2cp_stop (); + i2cp_abort_stop (); + + i2cp_start (); + i2cp_abort_start (); + i2cp_stop (); + i2cp_abort_stop (); + i2cp_unlock (); +} + + + +void +i2cp_scan (void) +{ + int i, r; + + return; + i2cp_reset (); + + printf ("Probing bus\r\n"); + for (i = 0; i < 128; ++i) + { + while (i2cp_lock ()); + i2cp_start (); + i2cp_abort_start (); + i2cp_stop (); + i2cp_abort_stop (); + r = i2cp_start_transaction (i, I2C_WRITE); + i2cp_stop (); + i2cp_unlock (); + if (!r) + printf ("Found device at address 0x%x\r\n", i); + usart1_drain (); + } + printf ("Done\r\n"); + i2cp_reset (); + +} + +void +i2cp_init (void) +{ + rcc_periph_clock_enable (RCC_I2C1); + rcc_periph_clock_enable (RCC_DMA1); + + while (i2cp_lock ()); + + + i2c_peripheral_enable (I2C); + i2c_clear_start (I2C); + i2c_clear_stop (I2C); + i2c_reset (I2C); + i2c_peripheral_enable (I2C); + + I2C_CR1 (I2C) |= I2C_CR1_SWRST; + delay_us (1000); + I2C_CR1 (I2C) &= ~I2C_CR1_SWRST; + + + i2cp_reset_sm (); + + gpio_set_mode (GPIOB, GPIO_MODE_OUTPUT_50_MHZ, + GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, + GPIO_I2C1_SCL | GPIO_I2C1_SDA); + + i2c_set_clock_frequency (I2C, I2C_CR2_FREQ_36MHZ); + i2c_set_standard_mode (I2C); + i2c_set_ccr (I2C, 0x200); /* t_high=t_high=CCR * Tpclk1 */ + i2c_set_trise (I2C, 0x0b); + + i2c_set_own_7bit_slave_address (I2C, 0x00); + + i2c_peripheral_enable (I2C); + i2cp_unlock (); +} diff --git a/app/i2c.h b/app/i2c.h new file mode 100644 index 0000000..26570d5 --- /dev/null +++ b/app/i2c.h @@ -0,0 +1,2 @@ +#define I2C_WRITE 0 +#define I2C_READ 1 diff --git a/app/lcd.c b/app/lcd.c new file mode 100644 index 0000000..e4a91ab --- /dev/null +++ b/app/lcd.c @@ -0,0 +1,478 @@ +#include "project.h" + +#define FOO do { printf("lcd:%x\r\n",__LINE__); usart1_drain(); } while (0) + +#define PCF8574_I2C_ADDRESS 0x27 + +#define LINE_RS 0x1 +#define LINE_RnW 0x2 +#define LINE_EN 0x4 +#define LINE_BACKLIGHT 0x8 + +#define LCD_CLEAR 0x1 +#define LCD_HOME 0x2 + +#define LCD_DISP 0x8 +#define LCD_DISP_ON 0x4 +#define LCD_DISP_CURSOR 0x2 +#define LCD_DISP_CURSOR_BLINK 0x1 + +#define LCD_FUNC 0x20 +#define LCD_FUNC_8BIT 0x10 +#define LCD_FUNC_4BIT 0x00 +#define LCD_FUNC_2ROWS 0x08 +#define LCD_FUNC_1ROW 0x00 +#define LCD_FUNC_5x10 0x04 +#define LCD_FUNC_5X7 0x00 + +#define LCD_SET_DDRAM_ADDR 0x80 + +#define LCD_H_SHIFT 5 +#define LCD_RS (1 << LCD_H_SHIFT) +#define LCD_W 20 +#define LCD_W_MASK (LCD_RS -1 ) +#define LCD_H 4 +#define LCD_SZ (LCD_H << LCD_H_SHIFT) +#define LCD_POS(c,r) (((r) << LCD_H_SHIFT ) +(c)) + +#define BYTES_PER_BYTE 6 + +#define DMA_BUF_SZ (BYTES_PER_BYTE * ( (1 + LCD_W) *LCD_H + 1)) + +static uint8_t dma_buf[DMA_BUF_SZ]; +static uint8_t update_buf[DMA_BUF_SZ]; +static int dma_in_progress = 0; +static int refresh_enabled = 0; + +static int backlight; +static int pos; + +static void +clock_nibble (uint8_t n) +{ + if (backlight) + n |= LINE_BACKLIGHT; + i2cp_send_data (n); + i2cp_send_data (LINE_EN | n); + i2cp_send_data (n); +} + + +static void +write_reg (uint8_t c, int r) +{ + uint8_t b; + + b = c & 0xf0; + if (r) + b |= LINE_RS; + + clock_nibble (b); + + b = (c & 0xf) << 4; + if (r) + b |= LINE_RS; + + clock_nibble (b); +} + +static void +send_command (uint8_t c) +{ + write_reg (c, 0); +} + +static void +send_one_command (uint8_t cmd, int delay) +{ + while (i2cp_lock ()); + i2cp_start_transaction (PCF8574_I2C_ADDRESS, I2C_WRITE); + send_command (cmd); + i2cp_stop (); + if (delay) + delay_ms (delay); + i2cp_unlock (); +} + + + +static void +cls (void) +{ + send_one_command (LCD_CLEAR, 2); +} + +#if 0 +static void +home (void) +{ + send_one_command (LCD_HOME, 2); +} +#endif + +static void +on (void) +{ + send_one_command (LCD_DISP | LCD_DISP_ON /* | LCD_DISP_CURSOR */ , 4); +} + +static void +off (void) +{ + send_one_command (LCD_DISP, 4); +} + +static int +lcd_addr (int x, int y) +{ + return x + ((y & 1) << 6) + ((y & 2) ? 20 : 0); +} + + +#if 0 +static void +move (uint8_t c, uint8_t r) +{ + send_one_command (LCD_SET_DDRAM_ADDR | lcd_addr (c, r), 2); +} +#endif + + +uint32_t refresh_wdt = 0; + +static void +start_dma (void) +{ + if (dma_in_progress) + return; + + refresh_wdt = 0; + + dma_in_progress = 1; + + memcpy (dma_buf, update_buf, DMA_BUF_SZ); + i2cp_start_transaction (PCF8574_I2C_ADDRESS, I2C_WRITE); + i2cp_start_dma (dma_buf, DMA_BUF_SZ); + +} + +void +dma1_channel6_isr (void) +{ + if (dma_in_progress) + { + i2cp_stop_dma (); + + i2cp_stop (); + dma_in_progress = 0; + } + + if (refresh_enabled) + start_dma (); +} + +void +lcd_refresh_wdt (void) +{ + refresh_wdt++; + + if (refresh_wdt < 1000) + return; + + refresh_wdt = 0; + +/*No refresh for 1s, restart everything */ + + i2cp_stop_dma (); + i2cp_stop (); + dma_in_progress = 0; + + start_dma (); + +} + +static inline void +dma_clock_nibble (uint8_t * ptr, uint8_t n) +{ + if (backlight) + n |= LINE_BACKLIGHT; + *(ptr++) = n; + *(ptr++) = n | LINE_EN; + *(ptr++) = n; +} + + +static inline int +dma_write_reg (uint8_t * ptr, uint8_t c, int r) +{ + uint8_t b; + + b = c & 0xf0; + if (r) + b |= LINE_RS; + + dma_clock_nibble (ptr, b); + ptr += 3; + + b = (c & 0xf) << 4; + if (r) + b |= LINE_RS; + + dma_clock_nibble (ptr, b); + + return 6; +} + +static inline int +dma_command (uint8_t * ptr, uint8_t c) +{ + return dma_write_reg (ptr, c, 0); +} + +static inline int +dma_data (uint8_t * ptr, uint8_t c) +{ + return dma_write_reg (ptr, c, 1); +} + + +static void +dma_generate_stream (void) +{ + uint8_t *dma_ptr; + int x, y, i; + + dma_ptr = update_buf; +/* 6 bytes per character, 6 bytes to move position, 5 moves + 20*4 chars => 510*/ + + for (y = 0; y < LCD_H; ++y) + { + + dma_ptr += dma_command (dma_ptr, LCD_SET_DDRAM_ADDR | lcd_addr (0, y)); + + i = y << LCD_H_SHIFT; + + for (x = 0; x < LCD_W; ++x, i++) + { + dma_ptr += dma_data (dma_ptr, ' '); + } + } + + dma_ptr += dma_command (dma_ptr, LCD_SET_DDRAM_ADDR | + lcd_addr (pos & LCD_W_MASK, pos >> LCD_H_SHIFT)); + +} + + +static void +dma_change_backlight (void) +{ + int len = DMA_BUF_SZ; + uint8_t *p = update_buf; + + cm_disable_interrupts (); + + if (backlight) + while (p++, len--) + *p |= LINE_BACKLIGHT; + else + while (p++, len--) + *p &= ~LINE_BACKLIGHT; + + cm_enable_interrupts (); +} + + +static int +dma_offset (int x, int y) +{ + return BYTES_PER_BYTE * (1 + x + y * (LCD_W + 1)); +} + + + +static void +_lcd_write_char (uint8_t c, int x, int y) +{ + cm_disable_interrupts (); + dma_data (update_buf + dma_offset (x, y), c); + cm_enable_interrupts (); +} + + +void +lcd_write_char (uint8_t c, int x, int y) +{ + cm_disable_interrupts (); + _lcd_write_char (c, x, y); + cm_enable_interrupts (); +} + + +void +lcd_erase (int x, int y, int w) +{ + uint8_t *dma_ptr = update_buf + dma_offset (x, y); + cm_disable_interrupts (); + while (w--) + dma_ptr += dma_data (dma_ptr, ' '); + cm_enable_interrupts (); +} + +void +lcd_erase_line (int w, int y) +{ + lcd_erase (0, y, w); +} + +void +lcd_erase_all (void) +{ + int y; + for (y = 0; y < LCD_H; ++y) + { + lcd_erase (0, 0, LCD_W); + } +} + +void +lcd_write (char *c, int x, int y) +{ + cm_disable_interrupts (); + while (*c) + { + _lcd_write_char (*(c++), x++, y); + if (x == LCD_W) + break; + } + cm_enable_interrupts (); +} + +#if 0 +static void +lcd_scroll (uint8_t * p) +{ + int i; + for (i = 0; i < 3; ++i) + { + memcpy (p, p + LCD_RS, LCD_W); + p += LCD_RS; + } + memset (p, ' ', LCD_W); +} + +void +lcd_putc (uint8_t c) +{ + + switch (c) + { + case '\r': + pos &= ~LCD_W_MASK; + break; + case '\n': + pos &= ~LCD_W_MASK; + pos += LCD_RS; + break; + default: + buf[pos] = c; + pos++; + } + + + if ((pos & LCD_W_MASK) == LCD_W) + { + pos &= ~LCD_W_MASK; + pos += LCD_RS; + } + + if (pos == LCD_SZ) + { + lcd_scroll (buf); + pos -= LCD_RS; + } + + +} +#endif + + +void +lcd_backlight (int i) +{ + backlight = i; + + dma_change_backlight (); + + if (refresh_enabled) + return; + + while (i2cp_lock ()); + i2cp_start_transaction (PCF8574_I2C_ADDRESS, I2C_WRITE); + i2cp_send_data (backlight ? LINE_BACKLIGHT : 0); + i2cp_stop (); + i2cp_unlock (); +} + + + + + +void +lcd_enable_refresh (void) +{ + refresh_enabled = 1; + start_dma (); +} + + +void +lcd_disable_refresh (void) +{ + refresh_enabled = 0; + while (dma_in_progress); +} + + + +void +lcd_reset (void) +{ + while (i2cp_lock ()); + i2cp_start_transaction (PCF8574_I2C_ADDRESS, I2C_WRITE); + clock_nibble (0x30); + delay_ms (5); + clock_nibble (0x30); + delay_us (64); + clock_nibble (0x30); + delay_us (64); + clock_nibble (0x20); + + send_command (LCD_FUNC | LCD_FUNC_4BIT | LCD_FUNC_2ROWS | LCD_FUNC_5X7); + i2cp_stop (); + i2cp_unlock (); + + on (); + cls (); +} + +void +lcd_init (void) +{ + lcd_backlight (0); + lcd_reset (); + lcd_backlight (1); + + dma_generate_stream (); + + nvic_enable_irq (NVIC_DMA1_CHANNEL6_IRQ); + lcd_enable_refresh (); +} + +void +lcd_shutdown (void) +{ + lcd_disable_refresh (); + lcd_backlight (0); + off (); +} diff --git a/app/led.c b/app/led.c new file mode 100644 index 0000000..64c4660 --- /dev/null +++ b/app/led.c @@ -0,0 +1,48 @@ +#include "project.h" + + +static int led = 0; + +void +led_init (void) +{ + gpio_set_mode (GPIOB, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, GPIO8); + gpio_set_mode (GPIOB, GPIO_MODE_OUTPUT_2_MHZ, + GPIO_CNF_OUTPUT_PUSHPULL, GPIO9); +} + + +void +led_clear (void) +{ + gpio_set (GPIOB, GPIO8); + gpio_set (GPIOB, GPIO9); +} + +void +led_set (uint32_t v) +{ + gpio_clear (GPIOB, v); + led = 200; +} + +void +led_tick (void) +{ + static int c; + + if (led) + { + led--; + if (!led) + led_clear (); + } + else + { + led_set (c ? GPIO8 : GPIO9); + c ^= 1; + } + + +} diff --git a/app/main.c b/app/main.c new file mode 100644 index 0000000..84edc6f --- /dev/null +++ b/app/main.c @@ -0,0 +1,58 @@ +#include "project.h" + + +static void +kbd_dispatch (void) +{ + uint8_t c; + + if (ring_read_byte (&rx1_ring, &c)) + return; + + printf("KEY> %c\r\n",c); + +} + +int +main (void) +{ +// rcc_clock_setup_in_hsi_out_48mhz (); + //nvic_set_priority_grouping(NVIC_PriorityGroup_4); + + /*set up pll */ + rcc_clock_setup_in_hse_8mhz_out_72mhz (); + + /*turn on clocks which aren't done elsewhere */ + rcc_periph_clock_enable (RCC_GPIOA); + rcc_periph_clock_enable (RCC_GPIOB); + rcc_periph_clock_enable (RCC_GPIOC); + rcc_periph_clock_enable (RCC_AFIO); + + + /*Adjust interrupt priorities so that uarts trump timer */ + nvic_set_priority (NVIC_USART1_IRQ, 0x40); + nvic_set_priority (NVIC_USART2_IRQ, 0x40); + nvic_set_priority (NVIC_USART3_IRQ, 0x40); + nvic_set_priority (NVIC_SYSTICK_IRQ, 0xff); + + + ticker_init (); + + led_init (); + usart_init (); + i2cp_init (); + + lcd_init (); + + + lcd_write ("Hello world", 0, 0); + + for (;;) + { + if (!ring_empty (&rx1_ring)) + kbd_dispatch (); + + } + + return 0; +} diff --git a/app/project.h b/app/project.h new file mode 100644 index 0000000..89184aa --- /dev/null +++ b/app/project.h @@ -0,0 +1,21 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +#include +#include + +#include "i2c.h" + +#include "ring.h" + +#include "prototypes.h" diff --git a/app/prototypes.h b/app/prototypes.h new file mode 100644 index 0000000..2e0163c --- /dev/null +++ b/app/prototypes.h @@ -0,0 +1,63 @@ +/* i2c.c */ +extern void i2c_clear_start(uint32_t i2c); +extern void i2cp_start(void); +extern void i2cp_abort_start(void); +extern void i2cp_stop(void); +extern void i2cp_abort_stop(void); +extern int i2cp_send_data(uint8_t v); +extern int i2cp_start_transaction(uint8_t a, int wnr); +extern int i2cp_lock(void); +extern void i2cp_unlock(void); +extern void i2cp_start_dma(uint8_t *buf, int len); +extern int i2cp_dma_in_progress(void); +extern void i2cp_stop_dma(void); +extern void i2cp_reset(void); +extern void i2cp_scan(void); +extern void i2cp_init(void); +/* lcd.c */ +extern uint32_t refresh_wdt; +extern void dma1_channel6_isr(void); +extern void lcd_refresh_wdt(void); +extern void lcd_write_char(uint8_t c, int x, int y); +extern void lcd_erase(int x, int y, int w); +extern void lcd_erase_line(int w, int y); +extern void lcd_erase_all(void); +extern void lcd_write(char *c, int x, int y); +extern void lcd_backlight(int i); +extern void lcd_enable_refresh(void); +extern void lcd_disable_refresh(void); +extern void lcd_reset(void); +extern void lcd_init(void); +extern void lcd_shutdown(void); +/* led.c */ +extern void led_init(void); +extern void led_clear(void); +extern void led_set(uint32_t v); +extern void led_tick(void); +/* main.c */ +extern int main(void); +/* ring.c */ +extern void ring_init(ring_t *r, uint8_t *buf, size_t len); +extern int ring_write_byte(ring_t *r, uint8_t c); +extern int ring_read_byte(ring_t *r, uint8_t *c); +extern int ring_write(ring_t *r, uint8_t *buf, size_t len); +extern int ring_empty(ring_t *r); +/* ticker.c */ +extern uint32_t ticks; +extern void delay_us(uint32_t d); +extern void sys_tick_handler(void); +extern void delay_ms(uint32_t d); +extern void ticker_init(void); +/* usart.c */ +extern ring_t rx1_ring; +extern ring_t tx1_ring; +extern ring_t rx2_ring; +extern ring_t tx2_ring; +extern void usart1_isr(void); +extern void usart2_isr(void); +extern int _write(int file, char *ptr, int len); +extern void usart1_queue(uint8_t d); +extern void usart2_queue(uint8_t d); +extern void usart2_drain(void); +extern void usart1_drain(void); +extern void usart_init(void); diff --git a/app/ring.c b/app/ring.c new file mode 100644 index 0000000..c4f3458 --- /dev/null +++ b/app/ring.c @@ -0,0 +1,68 @@ +#include "project.h" + + +static inline size_t +ring_next (ring_t * r, size_t p) +{ + p++; + if (p >= r->size) + p -= r->size; + return p; +} + +void +ring_init (ring_t * r, uint8_t * buf, size_t len) +{ + r->data = buf; + r->size = len; + r->write = 0; + r->read = 0; +} + +int +ring_write_byte (ring_t * r, uint8_t c) +{ + size_t n = ring_next (r, r->write); + + if (n == r->read) + return -1; + + r->data[r->write] = c; + + r->write = n; + + return 0; +} + + +int +ring_read_byte (ring_t * r, uint8_t * c) +{ + size_t n = ring_next (r, r->read); + + if (r->read == r->write) + return -1; + + *c = r->data[r->read]; + r->read = n; + + return 0; +} + +int +ring_write (ring_t * r, uint8_t * buf, size_t len) +{ + while (len--) + { + if (ring_write_byte (r, *(buf++))) + return -1; + } + + return 0; +} + +int +ring_empty (ring_t * r) +{ + return (r->read == r->write) ? 1 : 0; +} diff --git a/app/ring.h b/app/ring.h new file mode 100644 index 0000000..ba8887b --- /dev/null +++ b/app/ring.h @@ -0,0 +1,7 @@ +typedef struct ring +{ + uint8_t *data; + size_t size; + size_t write; + size_t read; +} ring_t; diff --git a/app/ticker.c b/app/ticker.c new file mode 100644 index 0000000..6ffff31 --- /dev/null +++ b/app/ticker.c @@ -0,0 +1,51 @@ +#include "project.h" + +static volatile uint32_t delay_ms_count; +uint32_t ticks; + +void +delay_us (uint32_t d) +{ + d *= 36; + while (d--) + { + __asm__ ("nop"); + } +} + +void +sys_tick_handler (void) +{ + if (delay_ms_count) + delay_ms_count--; + + ticks++; + + led_tick (); + lcd_refresh_wdt (); +} + + + +void +delay_ms (uint32_t d) +{ + delay_ms_count = d; + while (delay_ms_count); +} + + +void +ticker_init (void) +{ + + /*Start periodic timer */ + systick_set_clocksource (STK_CSR_CLKSOURCE_AHB_DIV8); + /* 48MHz / 8 = > 6Mhz */ + systick_set_reload (6000); + /* 6MHz / 6000 => 1kHz */ + systick_interrupt_enable (); + systick_counter_enable (); + + +} diff --git a/app/usart.c b/app/usart.c new file mode 100644 index 0000000..e0a80b1 --- /dev/null +++ b/app/usart.c @@ -0,0 +1,191 @@ +#include "project.h" + +#define BUFFER_SIZE 256 +#define BIG_BUFFER_SIZE 600 + +ring_t rx1_ring; +static uint8_t rx1_ring_buf[BUFFER_SIZE]; + +ring_t tx1_ring; +static uint8_t tx1_ring_buf[BUFFER_SIZE]; + +ring_t rx2_ring; +static uint8_t rx2_ring_buf[BUFFER_SIZE]; + +ring_t tx2_ring; +static uint8_t tx2_ring_buf[BIG_BUFFER_SIZE]; + +void +usart1_isr (void) +{ + uint8_t data; + + /* Check if we were called because of RXNE. */ + if (((USART_CR1 (USART1) & USART_CR1_RXNEIE) != 0) && + ((USART_SR (USART1) & USART_SR_RXNE) != 0)) + { + + /* Retrieve the data from the peripheral. */ + data = usart_recv (USART1); + + + ring_write_byte (&rx1_ring, data); + } + + /* Check if we were called because of TXE. */ + if (((USART_CR1 (USART1) & USART_CR1_TXEIE) != 0) && + ((USART_SR (USART1) & USART_SR_TXE) != 0)) + { + + if (ring_read_byte (&tx1_ring, &data)) + { + /*No more data, Disable the TXE interrupt, it's no longer needed. */ + USART_CR1 (USART1) &= ~USART_CR1_TXEIE; + } + else + { + usart_send (USART1, data); + } + } + +} + +void +usart2_isr (void) +{ + uint8_t data; + + /* Check if we were called because of RXNE. */ + if (((USART_CR1 (USART2) & USART_CR1_RXNEIE) != 0) && + ((USART_SR (USART2) & USART_SR_RXNE) != 0)) + { + + /* Retrieve the data from the peripheral. */ + data = usart_recv (USART2); + + ring_write_byte (&rx2_ring, data); + } + + /* Check if we were called because of TXE. */ + if (((USART_CR1 (USART2) & USART_CR1_TXEIE) != 0) && + ((USART_SR (USART2) & USART_SR_TXE) != 0)) + { + + if (ring_read_byte (&tx2_ring, &data)) + { + /*No more data, Disable the TXE interrupt, it's no longer needed. */ + USART_CR1 (USART2) &= ~USART_CR1_TXEIE; + } + else + { + usart_send_blocking (USART2, data); + } + } + +} + +int +_write (int file, char *ptr, int len) +{ + int ret; + + if (file == 1) + { + ret = ring_write (&tx1_ring, (uint8_t *) ptr, len); + + if (ret < 0) + ret = -ret; + + USART_CR1 (USART1) |= USART_CR1_TXEIE; + return ret; + } + + errno = EIO; + return -1; +} + +void +usart1_queue (uint8_t d) +{ + ring_write_byte (&tx1_ring, d); + USART_CR1 (USART1) |= USART_CR1_TXEIE; +} + + +void +usart2_queue (uint8_t d) +{ + ring_write_byte (&tx2_ring, d); + USART_CR1 (USART2) |= USART_CR1_TXEIE; +} + +void +usart2_drain (void) +{ + while (!ring_empty (&tx2_ring)); +} + +void +usart1_drain (void) +{ + while (!ring_empty (&tx1_ring)); +} + + + +void +usart_init (void) +{ + rcc_periph_clock_enable (RCC_USART1); + rcc_periph_clock_enable (RCC_USART2); + rcc_periph_clock_enable (RCC_USART3); + + ring_init (&rx1_ring, rx1_ring_buf, sizeof (rx1_ring_buf)); + ring_init (&tx1_ring, tx1_ring_buf, sizeof (tx1_ring_buf)); + + ring_init (&rx2_ring, rx2_ring_buf, sizeof (rx2_ring_buf)); + ring_init (&tx2_ring, tx2_ring_buf, sizeof (tx2_ring_buf)); + + + /* Enable the USART1,2 interrupt. */ + nvic_enable_irq (NVIC_USART1_IRQ); + nvic_enable_irq (NVIC_USART2_IRQ); + + /* Map pins, and set usart2 to have pull ups */ + gpio_set_mode (GPIOA, GPIO_MODE_OUTPUT_50_MHZ, + GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_TX); + gpio_set_mode (GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, + GPIO_USART1_RX); + + gpio_set_mode (GPIOA, GPIO_MODE_OUTPUT_50_MHZ, + GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX); + gpio_set_mode (GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, + GPIO_USART2_RX); + gpio_set (GPIOA, GPIO_USART2_RX); + + + /* Setup UART1 parameters. */ + usart_set_baudrate (USART1, 38400); + usart_set_databits (USART1, 8); + usart_set_stopbits (USART1, USART_STOPBITS_1); + usart_set_parity (USART1, USART_PARITY_NONE); + usart_set_flow_control (USART1, USART_FLOWCONTROL_NONE); + usart_set_mode (USART1, USART_MODE_TX_RX); + + /* Setup UART2 parameters. */ + usart_set_baudrate (USART2, 9600); + usart_set_databits (USART2, 8); + usart_set_stopbits (USART2, USART_STOPBITS_1); + usart_set_parity (USART2, USART_PARITY_NONE); + usart_set_flow_control (USART2, USART_FLOWCONTROL_NONE); + usart_set_mode (USART2, USART_MODE_TX_RX); + + + /* Enable USART1,2 Receive interrupt. */ + USART_CR1 (USART1) |= USART_CR1_RXNEIE; + USART_CR1 (USART2) |= USART_CR1_RXNEIE; + + /* Finally enable the USARTs. */ + usart_enable (USART1); + usart_enable (USART2); +} diff --git a/board/STM32F103R_BOARD.cfg b/board/STM32F103R_BOARD.cfg new file mode 100644 index 0000000..6d1d72b --- /dev/null +++ b/board/STM32F103R_BOARD.cfg @@ -0,0 +1,3 @@ +# + +source [find target/stm32f1x.cfg] diff --git a/interface/j-link.cfg b/interface/j-link.cfg new file mode 100644 index 0000000..3e95768 --- /dev/null +++ b/interface/j-link.cfg @@ -0,0 +1,5 @@ +# +telnet_port 4444 +gdb_port 3333 + +source [find interface/jlink.cfg] diff --git a/libopencm3 b/libopencm3 new file mode 160000 index 0000000..43e6692 --- /dev/null +++ b/libopencm3 @@ -0,0 +1 @@ +Subproject commit 43e66927fc48ffb9ad90fec275290ea7c0f88781 diff --git a/stm32-f103.cfg b/stm32-f103.cfg new file mode 100644 index 0000000..0809223 --- /dev/null +++ b/stm32-f103.cfg @@ -0,0 +1,6 @@ +# +telnet_port 4444 +gdb_port 3333 + +source [find interface/jlink.cfg] +source [find target/stm32f1x.cfg] -- cgit v1.2.3