aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
authorroot <root@no.no.james.local>2017-06-13 21:10:37 +0100
committerroot <root@no.no.james.local>2017-06-13 21:10:37 +0100
commiteaf5d4799cc52e9dd1ebcaeafbf8f670658fea98 (patch)
treebbeb1993818c5fc8cbcf5a001080f246facc8de6
downloadserial_over_dp-eaf5d4799cc52e9dd1ebcaeafbf8f670658fea98.tar.gz
serial_over_dp-eaf5d4799cc52e9dd1ebcaeafbf8f670658fea98.tar.bz2
serial_over_dp-eaf5d4799cc52e9dd1ebcaeafbf8f670658fea98.zip
inital commit
-rw-r--r--.gitignore8
-rw-r--r--.gitmodules3
-rw-r--r--Makefile.include45
-rw-r--r--Makefile.rules251
-rw-r--r--README36
-rw-r--r--app/Makefile56
-rw-r--r--app/cdcacm.c288
-rw-r--r--app/ddc.c17
-rw-r--r--app/dfu.c78
-rw-r--r--app/i2c_bb.c311
-rw-r--r--app/i2c_hw.c103
-rw-r--r--app/main.c54
-rw-r--r--app/project.h35
-rw-r--r--app/prototypes.h44
-rw-r--r--app/ring.c68
-rw-r--r--app/ring.h7
-rw-r--r--app/serial_over_dp.ld43
-rw-r--r--app/ticker.c76
-rw-r--r--app/usart.c90
-rw-r--r--app/vuart.c217
-rw-r--r--boot/Makefile32
-rw-r--r--boot/project.h23
-rw-r--r--boot/prototypes.h18
-rw-r--r--boot/usbdfu.c290
-rw-r--r--boot/usbdfu.ld40
-rw-r--r--docs/SC16IS740_750_760.pdfbin0 -> 560776 bytes
-rw-r--r--docs/rm0008.pdfbin0 -> 13016697 bytes
-rw-r--r--id.h3
-rw-r--r--oocd/board/STM32F103R_BOARD.cfg6
-rw-r--r--oocd/interface/j-link.cfg5
-rw-r--r--oocd/interface/stlink-v2.cfg11
-rw-r--r--oocd/stm32-f103.cfg6
32 files changed, 2264 insertions, 0 deletions
diff --git a/.gitignore b/.gitignore
new file mode 100644
index 0000000..e46adcb
--- /dev/null
+++ b/.gitignore
@@ -0,0 +1,8 @@
+*.o
+*.a
+*.d
+*.elf
+*.map
+*.hex
+*~
+*.dfu
diff --git a/.gitmodules b/.gitmodules
new file mode 100644
index 0000000..36a9790
--- /dev/null
+++ b/.gitmodules
@@ -0,0 +1,3 @@
+[submodule "libopencm3"]
+ path = libopencm3
+ url = git://git.panaceas.org/stm32/libopencm3.git
diff --git a/Makefile.include b/Makefile.include
new file mode 100644
index 0000000..5d6f84f
--- /dev/null
+++ b/Makefile.include
@@ -0,0 +1,45 @@
+##
+## This file is part of the libopencm3 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+##
+## 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 <http://www.gnu.org/licenses/>.
+##
+
+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 ?= ../oocd/interface/stlink-v2.cfg
+OOCD_INTERFACE ?= ../oocd/interface/j-link.cfg
+OOCD_BOARD ?= ../oocd/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..28422d9
--- /dev/null
+++ b/Makefile.rules
@@ -0,0 +1,251 @@
+#
+## This file is part of the libopencm3 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+## Copyright (C) 2013 Frantisek Burian <BuFran@seznam.cz>
+##
+## 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 <http://www.gnu.org/licenses/>.
+##
+
+# 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 += -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 -lgcc -lnosys -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 *.orig
+
+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/README b/README
new file mode 100644
index 0000000..ba383e9
--- /dev/null
+++ b/README
@@ -0,0 +1,36 @@
+To get this steaming pile of excellence working you need
+
+1) an STM32F103 board rated to 72MHz with an 8MHz clock and the PB6 and PB7 pins available
+
+eg
+http://www.ebay.co.uk/itm/132170295715
+http://www.ebay.co.uk/itm/132138287991
+
+2) optional (passive adaptors to get to you HDMI or DVI-D from whatever you have, the apple ones work well)
+
+3) Some way of connecting your HDMI/DVI-D to the board:
+
+HDMI DVI-D Cortex-M3
+
+15 DDC SCL 6 DDC SCL PB6 (with 10k pull-up to 3V3)
+16 DDC SDA 7 DDC SDA PB7 (with 10k pull-up to 3V3)
+17 GND 15 GND GND
+18 +5V 14 +5V (tie to HPD)
+19 HPD 16 HPD (tie to +5V)
+
+The code connects a virtual NS16X50 uart to the I2C bus at address 0x90 (like an SC16IS7XX does),
+and a 24C02 EEPROM containg DDC data for a 1280x1024 monitor at address 0xA0.
+
+The virtual UART is connected to the M3's real uart 1 which is enabled, and to a CDC ACM device
+on USB.
+
+The fake monitor is necessary because recent intel GPUs do hot plug detection and powering up the ports
+in firmware rather than in the driver it also tricks said firmware into configuring the port as HDMI/DVI
+rather than as Displayport - that way the GPIOs that AX can see get connected to SDA and SCL.
+
+The USB interface also offers a DFU device for flashing the firmware without a JTAG/ST-LINK cable,
+which although very slow is good because it synchronises the board reset with the USB host's rescaning
+of the device, so you don't need to replug.
+
+
+J.
diff --git a/app/Makefile b/app/Makefile
new file mode 100644
index 0000000..dc5503b
--- /dev/null
+++ b/app/Makefile
@@ -0,0 +1,56 @@
+##
+## This file is part of the libopencm3 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## 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 <http://www.gnu.org/licenses/>.
+##
+
+CPROTO=cproto
+PROG=serial_over_dp
+
+
+V=1
+default: ${PROG}.elf
+
+CSRCS= main.c cdcacm.c dfu.c i2c_bb.c vuart.c ring.c usart.c i2c_hw.c ticker.c ddc.c
+HSRCS = project.h
+
+
+BINARY = ${PROG}
+OBJS = ${CSRCS:%.c=%.o}
+
+include ../Makefile.include
+
+DID=$(shell printf '\#include "id.h"\nID_PRODUCT' | ${CC} -I.. -E - | grep -v ^\# )
+VID=$(shell printf '\#include "id.h"\nID_VENDOR' | ${CC} -I.. -E - | grep -v ^\# )
+
+INCLUDES += -I..
+
+dfu:${PROG}.dfu
+ dfu-util -R -a 0 -d ${VID}:${DID} -s 0x08002000:leave -D $<
+
+program: ${PROG}.elf
+ echo halt | nc -t localhost 4444
+ echo flash write_image erase ${PWD}/$< 0x2000 | nc -t localhost 4444
+ echo reset run | nc -t localhost 4444
+
+protos:
+ echo -n > prototypes.h
+ ${CPROTO} $(INCLUDES) $(DEFINES) -e -v ${CSRCS} > prototypes.h.tmp
+ mv -f prototypes.h.tmp prototypes.h
+
+
+tidy:
+ astyle -A3 -s2 --attach-extern-c -L -c -w -Y -m0 -f -p -H -U -k3 -xj -xd ${CSRCS} ${HSRCS} || astyle -A3 -s2 -L -c -w -Y -m0 -f -p -H -U -k3 -xj -xd ${CSRCS} ${HSRCS}
diff --git a/app/cdcacm.c b/app/cdcacm.c
new file mode 100644
index 0000000..b300241
--- /dev/null
+++ b/app/cdcacm.c
@@ -0,0 +1,288 @@
+#include "project.h"
+
+
+#define BUFFER_SIZE 512
+
+ring_t cdcacm_rx_ring;
+static uint8_t cdcacm_rx_ring_buf[BUFFER_SIZE];
+
+ring_t cdcacm_tx_ring;
+static uint8_t cdcacm_tx_ring_buf[BUFFER_SIZE];
+
+
+static const struct usb_device_descriptor dev = {
+ .bLength = USB_DT_DEVICE_SIZE,
+ .bDescriptorType = USB_DT_DEVICE,
+ .bcdUSB = 0x0200,
+ .bDeviceClass = USB_CLASS_CDC,
+ .bDeviceSubClass = 0,
+ .bDeviceProtocol = 0,
+ .bMaxPacketSize0 = 64,
+ .idVendor = ID_VENDOR,
+ .idProduct = ID_PRODUCT,
+ .bcdDevice = 0x0200,
+ .iManufacturer = 1,
+ .iProduct = 2,
+ .iSerialNumber = 3,
+ .bNumConfigurations = 1,
+};
+
+
+static const struct usb_endpoint_descriptor comm_endp[] = {
+ {
+ .bLength = USB_DT_ENDPOINT_SIZE,
+ .bDescriptorType = USB_DT_ENDPOINT,
+ .bEndpointAddress = 0x83,
+ .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
+ .wMaxPacketSize = 16,
+ .bInterval = 255,
+ }
+};
+
+static const struct usb_endpoint_descriptor data_endp[] = {
+ {
+ .bLength = USB_DT_ENDPOINT_SIZE,
+ .bDescriptorType = USB_DT_ENDPOINT,
+ .bEndpointAddress = 0x01,
+ .bmAttributes = USB_ENDPOINT_ATTR_BULK,
+ .wMaxPacketSize = 64,
+ .bInterval = 1,
+ },
+ {
+ .bLength = USB_DT_ENDPOINT_SIZE,
+ .bDescriptorType = USB_DT_ENDPOINT,
+ .bEndpointAddress = 0x82,
+ .bmAttributes = USB_ENDPOINT_ATTR_BULK,
+ .wMaxPacketSize = 64,
+ .bInterval = 1,
+ }
+};
+
+static const struct {
+ struct usb_cdc_header_descriptor header;
+ struct usb_cdc_call_management_descriptor call_mgmt;
+ struct usb_cdc_acm_descriptor acm;
+ struct usb_cdc_union_descriptor cdc_union;
+} __attribute__ ( (packed)) cdcacm_functional_descriptors = {
+ .header = {
+ .bFunctionLength = sizeof (struct usb_cdc_header_descriptor),
+ .bDescriptorType = CS_INTERFACE,
+ .bDescriptorSubtype = USB_CDC_TYPE_HEADER,
+ .bcdCDC = 0x0110,
+ },
+ .call_mgmt = {
+ .bFunctionLength =
+ sizeof (struct usb_cdc_call_management_descriptor),
+ .bDescriptorType = CS_INTERFACE,
+ .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT,
+ .bmCapabilities = 0,
+ .bDataInterface = 1,
+ },
+ .acm = {
+ .bFunctionLength = sizeof (struct usb_cdc_acm_descriptor),
+ .bDescriptorType = CS_INTERFACE,
+ .bDescriptorSubtype = USB_CDC_TYPE_ACM,
+ .bmCapabilities = 0,
+ },
+ .cdc_union = {
+ .bFunctionLength = sizeof (struct usb_cdc_union_descriptor),
+ .bDescriptorType = CS_INTERFACE,
+ .bDescriptorSubtype = USB_CDC_TYPE_UNION,
+ .bControlInterface = 0,
+ .bSubordinateInterface0 = 1,
+ }
+};
+
+static const struct usb_interface_descriptor comm_iface = {
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 0,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 1,
+ .bInterfaceClass = USB_CLASS_CDC,
+ .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
+ .bInterfaceProtocol = USB_CDC_PROTOCOL_AT,
+ .iInterface = 0,
+ .endpoint = comm_endp,
+ .extra = &cdcacm_functional_descriptors,
+ .extralen = sizeof (cdcacm_functional_descriptors)
+};
+
+static const struct usb_interface_descriptor data_iface = {
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 1,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 2,
+ .bInterfaceClass = USB_CLASS_DATA,
+ .bInterfaceSubClass = 0,
+ .bInterfaceProtocol = 0,
+ .iInterface = 0,
+ .endpoint = data_endp,
+};
+
+static const struct usb_interface ifaces[] = {
+ {
+ .num_altsetting = 1,
+ .altsetting = &comm_iface,
+ },
+ {
+ .num_altsetting = 1,
+ .altsetting = &data_iface,
+ },
+#ifdef INCLUDE_DFU_INTERFACE
+ {
+ .num_altsetting = 1,
+ .altsetting = &dfu_iface,
+ },
+#endif
+};
+
+static const struct usb_config_descriptor config = {
+ .bLength = USB_DT_CONFIGURATION_SIZE,
+ .bDescriptorType = USB_DT_CONFIGURATION,
+ .wTotalLength = 0,
+#ifdef INCLUDE_DFU_INTERFACE
+ .bNumInterfaces = 3,
+#else
+ .bNumInterfaces = 2,
+#endif
+ .bConfigurationValue = 1,
+ .iConfiguration = 0,
+ .bmAttributes = 0x80,
+ .bMaxPower = 0x32,
+ .interface = ifaces,
+};
+
+static const char *usb_strings[] = {
+ "Meh",
+ "Fish",
+ "Soup",
+#ifdef INCLUDE_DFU_INTERFACE
+ "DFU",
+#endif
+};
+
+/* Buffer to be used for control requests. */
+uint8_t usbd_control_buffer[128];
+
+usbd_device *usbd_dev;
+
+
+
+static int cdcacm_control_request (usbd_device *usbd_dev,
+ struct usb_setup_data *req,
+ uint8_t **buf,
+ uint16_t *len,
+ usbd_control_complete_callback *complete)
+{
+ (void) complete;
+ (void) buf;
+ (void) usbd_dev;
+#ifdef INCLUDE_DFU_INTERFACE
+
+ if (dfu_control_request (usbd_dev, req, buf, len, complete)) {
+ return 1;
+ }
+
+#endif
+
+ switch (req->bRequest) {
+ case USB_CDC_REQ_SET_CONTROL_LINE_STATE: {
+ /*
+ * This Linux cdc_acm driver requires this to be implemented
+ * even though it's optional in the CDC spec, and we don't
+ * advertise it in the ACM functional descriptor.
+ */
+ char local_buf[10];
+ struct usb_cdc_notification *notif = (void *) local_buf;
+ /* We echo signals back to host as notification. */
+ notif->bmRequestType = 0xA1;
+ notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE;
+ notif->wValue = 0;
+ notif->wIndex = 0;
+ notif->wLength = 2;
+ local_buf[8] = req->wValue & 3;
+ local_buf[9] = 0;
+ // usbd_ep_write_packet(0x83, buf, 10);
+ return 1;
+ }
+ case USB_CDC_REQ_SET_LINE_CODING:
+
+ if (*len < sizeof (struct usb_cdc_line_coding)) {
+ return 0;
+ }
+
+ return 1;
+ }
+
+ return 0;
+}
+
+
+void cdcacm_tick (void)
+{
+ unsigned ep = 0x82;
+ uint8_t buf[16];
+ uint8_t *ptr = buf;
+ size_t n = 0;
+
+ if (ring_empty (&cdcacm_tx_ring)) {
+ return;
+ }
+
+ if ( (*USB_EP_REG (ep & 0x7f) & USB_EP_TX_STAT) == USB_EP_TX_STAT_VALID) {
+ return;
+ }
+
+ while (!ring_read_byte (&cdcacm_tx_ring, ptr++)) {
+ n++;
+ }
+
+ usbd_ep_write_packet (usbd_dev, ep, buf, n);
+}
+
+
+static void cdcacm_data_rx_cb (usbd_device *usbd_dev, uint8_t ep)
+{
+ (void) ep;
+ uint8_t buf[64];
+ int len = usbd_ep_read_packet (usbd_dev, 0x01, buf, 64);
+
+ if (len) {
+ ring_write (&cdcacm_rx_ring, buf, len);
+ }
+}
+
+static void cdcacm_set_config (usbd_device *usbd_dev, uint16_t wValue)
+{
+ (void) wValue;
+ usbd_ep_setup (usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, 64, cdcacm_data_rx_cb);
+ usbd_ep_setup (usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, 64, NULL);
+ usbd_ep_setup (usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
+ usbd_register_control_callback (usbd_dev,
+ USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ cdcacm_control_request);
+}
+
+void usb_init (void)
+{
+ ring_init (&cdcacm_rx_ring, cdcacm_rx_ring_buf, sizeof (cdcacm_rx_ring_buf));
+ ring_init (&cdcacm_tx_ring, cdcacm_tx_ring_buf, sizeof (cdcacm_tx_ring_buf));
+ usbd_dev = usbd_init (&stm32f103_usb_driver,
+ &dev,
+ &config,
+ usb_strings,
+#ifdef INCLUDE_DFU_INTERFACE
+ 4,
+#else
+ 3,
+#endif
+ usbd_control_buffer,
+ sizeof (usbd_control_buffer));
+ usbd_register_set_config_callback (usbd_dev, cdcacm_set_config);
+}
+
+
+
diff --git a/app/ddc.c b/app/ddc.c
new file mode 100644
index 0000000..5245cf9
--- /dev/null
+++ b/app/ddc.c
@@ -0,0 +1,17 @@
+#include "project.h"
+
+static const uint8_t ddc[128] = {
+ 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x10, 0xAC, 0x24, 0x40, 0x36, 0x34, 0x34, 0x47,
+ 0x1A, 0x11, 0x01, 0x03, 0x80, 0x22, 0x1B, 0x78, 0xEE, 0xA6, 0xC5, 0xA2, 0x57, 0x4C, 0x9C, 0x25,
+ 0x12, 0x50, 0x54, 0xA5, 0x4B, 0x00, 0x71, 0x4F, 0x81, 0x80, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01,
+ 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x30, 0x2A, 0x00, 0x98, 0x51, 0x00, 0x2A, 0x40, 0x30, 0x70,
+ 0x13, 0x00, 0x52, 0x0E, 0x11, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0xFF, 0x00, 0x46, 0x50, 0x31,
+ 0x38, 0x31, 0x37, 0x36, 0x53, 0x47, 0x34, 0x34, 0x36, 0x0A, 0x00, 0x00, 0x00, 0xFC, 0x00, 0x44,
+ 0x45, 0x4C, 0x4C, 0x20, 0x31, 0x37, 0x30, 0x38, 0x46, 0x50, 0x0A, 0x20, 0x00, 0x00, 0x00, 0xFD,
+ 0x00, 0x38, 0x4C, 0x1E, 0x51, 0x0E, 0x00, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x00, 0x69,
+};
+
+uint8_t ddc_read (uint8_t v)
+{
+ return ddc[v & 0x7f];
+}
diff --git a/app/dfu.c b/app/dfu.c
new file mode 100644
index 0000000..dcde674
--- /dev/null
+++ b/app/dfu.c
@@ -0,0 +1,78 @@
+#include "project.h"
+
+#ifdef INCLUDE_DFU_INTERFACE
+
+extern uint32_t dfu_flag;
+
+const struct usb_dfu_descriptor dfu_function = {
+ .bLength = sizeof (struct usb_dfu_descriptor),
+ .bDescriptorType = DFU_FUNCTIONAL,
+ .bmAttributes = USB_DFU_CAN_DOWNLOAD,
+ .wDetachTimeout = 255,
+ .wTransferSize = 1024,
+ .bcdDFUVersion = 0x011A,
+};
+
+const struct usb_interface_descriptor dfu_iface = {
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 2,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 0,
+ .bInterfaceClass = 0xFE,
+ .bInterfaceSubClass = 1,
+ .bInterfaceProtocol = 1,
+ .iInterface = 4,
+
+ .extra = &dfu_function,
+ .extralen = sizeof (dfu_function),
+};
+
+
+static int
+dfu_detach_complete (usbd_device *usbd_dev, struct usb_setup_data *req)
+{
+ (void) req;
+ (void) usbd_dev;
+ dfu_flag = 0xfee1dead;
+ scb_reset_core();
+ return 1;
+}
+
+int
+dfu_control_request (usbd_device *usbd_dev, struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len,
+ usbd_control_complete_callback *complete)
+{
+ (void) buf;
+ (void) len;
+ (void) usbd_dev;
+
+ if ( (req->bmRequestType & 0x7F) != 0x21) {
+ return 0; /* Only accept class request. */
+ }
+
+ switch (req->bRequest) {
+ case DFU_GETSTATUS: {
+ (*buf) [0] = DFU_STATUS_OK;
+ (*buf) [1] = 0;
+ (*buf) [2] = 0;
+ (*buf) [3] = 0;
+ (*buf) [4] = STATE_APP_IDLE;
+ (*buf) [5] = 0; /* iString not used here */
+ *len = 6;
+ return 1;
+ }
+ case DFU_GETSTATE:
+ /* Return state with no state transision. */
+ *buf[0] = STATE_APP_IDLE;
+ *len = 1;
+ return 1;
+ case DFU_DETACH:
+ *complete = dfu_detach_complete;
+ return 1;
+ }
+
+ return 0;
+}
+#endif
diff --git a/app/i2c_bb.c b/app/i2c_bb.c
new file mode 100644
index 0000000..f392b5e
--- /dev/null
+++ b/app/i2c_bb.c
@@ -0,0 +1,311 @@
+#include "project.h"
+#include <stdio.h>
+#include <string.h>
+
+#define SDA_BANK GPIOB
+#define SDA_GPIO GPIO7
+
+#define SCL_BANK GPIOB
+#define SCL_GPIO GPIO6
+
+
+#define I2C_READ 1
+#define I2C_WRITE 0
+
+#define OUR_ADDRESS 0x90
+
+
+typedef enum {
+ ST_LOST = 0,
+ ST_ADDRESS_7,
+ ST_ADDRESS_6,
+ ST_ADDRESS_5,
+ ST_ADDRESS_4,
+ ST_ADDRESS_3,
+ ST_ADDRESS_2,
+ ST_ADDRESS_1,
+ ST_ADDRESS_0,
+ ST_ADDRESS_ACK,
+ ST_OUT_7,
+ ST_OUT_6,
+ ST_OUT_5,
+ ST_OUT_4,
+ ST_OUT_3,
+ ST_OUT_2,
+ ST_OUT_1,
+ ST_OUT_0,
+ ST_PREP_OUT_ACK,
+ ST_OUT_ACK,
+ /*Doesn't fall through*/
+ ST_PREP_REG_7,
+ ST_REG_7,
+ ST_REG_6,
+ ST_REG_5,
+ ST_REG_4,
+ ST_REG_3,
+ ST_REG_2,
+ ST_REG_1,
+ ST_REG_0,
+ ST_REG_ACK,
+ ST_PREP_IN_7,
+ ST_IN_7,
+ ST_IN_6,
+ ST_IN_5,
+ ST_IN_4,
+ ST_IN_3,
+ ST_IN_2,
+ ST_IN_1,
+ ST_IN_0,
+ ST_IN_ACK,
+ ST_REG_WRITE,
+ /*Doesn't fall through*/
+
+
+} i2c_state_t;
+
+
+static int dsda;
+
+static void i2c_bb_sda (int sda)
+{
+ dsda = sda;
+
+ if (sda) {
+ gpio_set_mode (SDA_BANK, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, SDA_GPIO);
+ gpio_set (SDA_BANK, SDA_GPIO);
+ } else {
+ gpio_set_mode (SDA_BANK, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, SDA_GPIO);
+ gpio_clear (SDA_BANK, SDA_GPIO);
+ }
+}
+
+
+static void i2c_bb_scl (int scl)
+{
+ if (scl) {
+ gpio_set_mode (SCL_BANK, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, SCL_GPIO);
+ gpio_set (SCL_BANK, SCL_GPIO);
+ } else {
+ gpio_set_mode (SCL_BANK, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, SCL_GPIO);
+ gpio_clear (SCL_BANK, SCL_GPIO);
+ }
+}
+
+static i2c_state_t state = ST_LOST;
+
+static void i2c_bb_sm (int od, int d, int oc, int c)
+{
+ static int rnw ;
+ static uint8_t sr;
+ static uint8_t reg;
+
+ //Check for START
+ if (oc && c && od && !d) {
+ state = ST_ADDRESS_7;
+ sr = 0;
+ }
+
+ // Check for STOP
+ if (oc && c && !od && d) {
+ state = ST_LOST;
+ }
+
+ switch (state) {
+ case ST_LOST:
+ i2c_bb_sda (1);
+ i2c_bb_scl (1);
+ break;
+ case ST_ADDRESS_7...ST_ADDRESS_0:
+
+ if (! (!oc && c)) {
+ break;
+ }
+
+ //rising scl of a7...a0
+ sr = (sr << 1) | !!d;
+
+ if (state == ST_ADDRESS_0) {
+ if ( (sr & ~I2C_READ) == OUR_ADDRESS) {
+ state++;
+ rnw = d;
+ } else {
+ state = ST_LOST;
+ }
+ } else {
+ state++;
+ }
+
+ break;
+ case ST_ADDRESS_ACK:
+
+ if (! (oc && !c)) {
+ break;
+ }
+
+ //falling scl of a0
+ i2c_bb_sda (0);
+
+ if (rnw) {
+ state++;
+ } else {
+ state = ST_PREP_REG_7;
+ }
+
+ break;
+ case ST_OUT_7:
+
+ if (! (oc && !c)) {
+ break;
+ }
+
+ //falling scl of ack
+ i2c_bb_sda (1);
+ //stretch SCL
+ i2c_bb_scl (0);
+ sr = vuart_read (reg);
+ i2c_bb_sda (sr & 0x80);
+ sr <<= 1;
+ i2c_bb_scl (1);
+ state++;
+ break;
+ case ST_OUT_6...ST_OUT_0:
+
+ if (! (oc && !c)) {
+ break;
+ }
+
+ //falling scl of d6...d0
+ i2c_bb_sda (sr & 0x80);
+ sr <<= 1;
+ state++;
+ break;
+ case ST_PREP_OUT_ACK:
+
+ if (! (oc && !c)) {
+ break;
+ }
+
+ //falling scl of d0
+ i2c_bb_sda (1);
+ state++;
+ break;
+ case ST_OUT_ACK:
+
+ if (! (!oc && c)) {
+ break;
+ }
+
+ //rising scl of ack
+
+ if (d) {
+ /*They're done with us */
+ state = ST_LOST;
+ } else {
+ /*They want more */
+ state = ST_OUT_7;
+ reg++;
+ }
+
+ break;
+ case ST_PREP_REG_7:
+
+ if (! (oc && !c)) {
+ break;
+ }
+
+ //falling scl of ack
+ i2c_bb_sda (1);
+ sr = 0;
+ state++;
+ break;
+ case ST_REG_7...ST_REG_0:
+
+ if (! (!oc && c)) {
+ break;
+ }
+
+ //rising scl of r7..r0
+ sr = (sr << 1) | !!d;
+ state++;
+ break;
+ case ST_REG_ACK:
+
+ if (! (oc && !c)) {
+ break;
+ }
+
+ //falling scl of r0
+ reg = sr;
+ i2c_bb_sda (0);
+ state = ST_PREP_IN_7;
+ break;
+ case ST_PREP_IN_7:
+
+ if (! (oc && !c)) {
+ break;
+ }
+
+ //falling scl of ack
+ i2c_bb_sda (1);
+ sr = 0;
+ state++;
+ break;
+ case ST_IN_7...ST_IN_0:
+
+ if (! (!oc && c)) {
+ break;
+ }
+
+ //rising scl of i7..i0
+ sr = (sr << 1) | !!d;
+ state++;
+ break;
+ case ST_IN_ACK:
+
+ if (! (oc && !c)) {
+ break;
+ }
+
+ //falling scl of i0
+ i2c_bb_sda (0);
+ state++;
+ break;
+ case ST_REG_WRITE:
+
+ if (! (oc && !c)) {
+ break;
+ }
+
+ //falling scl of ack
+ i2c_bb_sda (1);
+ //stretch SCL
+ i2c_bb_scl (0);
+ vuart_write (reg, sr);
+ i2c_bb_scl (1);
+ reg++;
+ sr = 0;
+ state = ST_IN_7;
+ break;
+ default:
+ state = ST_LOST;
+ }
+}
+
+
+
+void i2c_bb_init (void)
+{
+ i2c_bb_scl (1);
+ i2c_bb_sda (1);
+}
+
+
+void i2c_bb_poll (void)
+{
+ int sda = gpio_get (SDA_BANK, SDA_GPIO);
+ int scl = gpio_get (SCL_BANK, SCL_GPIO);
+ static int old_sda = 1, old_scl = 1;
+ i2c_bb_sm (old_sda, sda, old_scl, scl);
+ old_scl = scl;
+ old_sda = sda;
+}
diff --git a/app/i2c_hw.c b/app/i2c_hw.c
new file mode 100644
index 0000000..11e796e
--- /dev/null
+++ b/app/i2c_hw.c
@@ -0,0 +1,103 @@
+#include "project.h"
+
+#define SCL_GPIO GPIO_I2C1_SCL
+#define SCL_BANK GPIOB
+
+#define SDA_GPIO GPIO_I2C1_SDA
+#define SDA_BANK GPIOB
+
+#define I2C I2C1
+
+
+/*
+void i2c1_isr(void)
+{
+}
+*/
+
+void i2c1_er_isr (void)
+{
+}
+
+void i2c1_ev_isr (void)
+{
+ static uint8_t reg;
+ static int device;
+ static int next_is_reg;
+ uint32_t sr1 = I2C_SR1 (I2C);
+ uint32_t v;
+
+ if (sr1 & I2C_SR1_ADDR) {
+ v = I2C_SR2 (I2C);
+ device = !! (v & I2C_SR2_DUALF);
+ next_is_reg = 1;
+ }
+
+ if (sr1 & I2C_SR1_TxE) {
+ if (device) {
+ v = ddc_read (reg++);
+ } else {
+ v = vuart_read (reg++);
+ }
+
+ I2C_DR (I2C) = v;
+ }
+
+ if (sr1 & I2C_SR1_RxNE) {
+ v = I2C_DR (I2C);
+
+ if (next_is_reg) {
+ reg = v;
+ next_is_reg = 0;
+ } else {
+ if (reg == 0x10) {
+ vuart_write (0, v);
+ } else {
+ vuart_write (reg++, v);
+ }
+ }
+ }
+
+ if (sr1 & I2C_SR1_STOPF) {
+ v = I2C_CR1 (I2C);
+ I2C_CR1 (I2C) = v;
+ }
+}
+
+static void
+i2c_clear_start (uint32_t i2c)
+{
+ I2C_CR1 (i2c) &= ~ (uint32_t) I2C_CR1_START;
+}
+
+
+
+void
+i2c_hw_init (void)
+{
+ 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;
+ gpio_set_mode (SCL_BANK, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN,
+ SCL_GPIO);
+ gpio_set_mode (SDA_BANK, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN,
+ SDA_GPIO);
+ 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, 0x90 >> 1);
+ i2c_set_own_7bit_slave_address_two (I2C, 0xa0 >> 1);
+ i2c_enable_dual_addressing_mode (I2C);
+ i2c_peripheral_enable (I2C);
+ I2C_CR2 (I2C) |= I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN;
+ I2C_CR1 (I2C) |= I2C_CR1_ACK;
+ nvic_enable_irq (NVIC_I2C1_EV_IRQ);
+}
diff --git a/app/main.c b/app/main.c
new file mode 100644
index 0000000..b98bd82
--- /dev/null
+++ b/app/main.c
@@ -0,0 +1,54 @@
+#include "project.h"
+
+
+
+
+
+int main (void)
+{
+ /*set up pll */
+ rcc_clock_setup_in_hse_8mhz_out_72mhz();
+ /*turn on clocks to periferals */
+ rcc_periph_clock_enable (RCC_GPIOA);
+ rcc_periph_clock_enable (RCC_GPIOB);
+ rcc_periph_clock_enable (RCC_GPIOC);
+ rcc_periph_clock_enable (RCC_USART1);
+ rcc_periph_clock_enable (RCC_AFIO);
+ rcc_periph_clock_enable (RCC_I2C1);
+#if 0
+ nvic_set_priority (NVIC_I2C1_EV_IRQ, 0x38);
+ nvic_set_priority (NVIC_I2C1_ER_IRQ, 0x39);
+ nvic_set_priority (NVIC_USART1_IRQ, 0x44);
+ nvic_set_priority (NVIC_SYSTICK_IRQ, 0xff);
+#else
+ nvic_set_priority (NVIC_I2C1_EV_IRQ, 0xff);
+ nvic_set_priority (NVIC_I2C1_ER_IRQ, 0xff);
+ nvic_set_priority (NVIC_SYSTICK_IRQ, 0x80);
+ nvic_set_priority (NVIC_USART1_IRQ, 0x40);
+#endif
+ gpio_set_mode (LED1_BANK, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, LED1_GPIO);
+ gpio_set_mode (LED2_BANK, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, LED2_GPIO);
+ usart_init();
+ ticker_init();
+ printf ("Morning chaps!\r\n");
+#ifdef USB
+ usb_init();
+#endif
+#ifdef I2C_BIT_BANG
+ i2c_bb_init();
+#else
+ i2c_hw_init();
+#endif
+
+ for (;;) {
+#ifdef USB
+ usbd_poll (usbd_dev);
+#endif
+#ifdef I2C_BIT_BANG
+ i2c_bb_poll();
+#endif
+ }
+
+ return 0;
+}
+
diff --git a/app/project.h b/app/project.h
new file mode 100644
index 0000000..3df1a38
--- /dev/null
+++ b/app/project.h
@@ -0,0 +1,35 @@
+#include <stdlib.h>
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/usart.h>
+#include <libopencm3/stm32/usb.h>
+#include <libopencm3/stm32/i2c.h>
+#include <libopencm3/cm3/systick.h>
+#include <libopencm3/cm3/nvic.h>
+#include <libopencm3/usb/usbd.h>
+#include <libopencm3/usb/hid.h>
+#include <libopencm3/cm3/cortex.h>
+#include <libopencm3/usb/cdc.h>
+#include <id.h>
+
+#define INCLUDE_DFU_INTERFACE
+#undef I2C_BIT_BANG
+#define USB
+
+#ifdef INCLUDE_DFU_INTERFACE
+#include <libopencm3/cm3/scb.h>
+#include <libopencm3/usb/dfu.h>
+#endif
+
+#include <stdio.h>
+#include <errno.h>
+
+#define LED1_GPIO GPIO8
+#define LED1_BANK GPIOB
+
+#define LED2_GPIO GPIO9
+#define LED2_BANK GPIOB
+
+#include "ring.h"
+
+#include "prototypes.h"
diff --git a/app/prototypes.h b/app/prototypes.h
new file mode 100644
index 0000000..a877992
--- /dev/null
+++ b/app/prototypes.h
@@ -0,0 +1,44 @@
+/* main.c */
+extern int main(void);
+/* cdcacm.c */
+extern ring_t cdcacm_rx_ring;
+extern ring_t cdcacm_tx_ring;
+extern uint8_t usbd_control_buffer[128];
+extern usbd_device *usbd_dev;
+extern void cdcacm_tick(void);
+extern void usb_init(void);
+/* dfu.c */
+extern const struct usb_dfu_descriptor dfu_function;
+extern const struct usb_interface_descriptor dfu_iface;
+extern int dfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, usbd_control_complete_callback *complete);
+/* i2c_bb.c */
+extern void i2c_bb_init(void);
+extern void i2c_bb_poll(void);
+/* vuart.c */
+extern uint8_t vuart_read(unsigned reg);
+extern void vuart_write(unsigned reg, uint8_t val);
+/* 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_empty(ring_t *r);
+extern int ring_read_byte(ring_t *r, uint8_t *c);
+extern int ring_write(ring_t *r, uint8_t *buf, size_t len);
+/* usart.c */
+extern ring_t usart_rx_ring;
+extern ring_t usart_tx_ring;
+extern void usart1_isr(void);
+extern void usart_kick(void);
+extern int _write(int file, char *ptr, int len);
+extern void usart_init(void);
+/* i2c_hw.c */
+extern void i2c1_er_isr(void);
+extern void i2c1_ev_isr(void);
+extern void i2c_hw_init(void);
+/* ticker.c */
+extern unsigned led1;
+extern unsigned led2;
+extern void delay_us(uint32_t d);
+extern void sys_tick_handler(void);
+extern void ticker_init(void);
+/* ddc.c */
+extern uint8_t ddc_read(uint8_t v);
diff --git a/app/ring.c b/app/ring.c
new file mode 100644
index 0000000..e3a6209
--- /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_empty (ring_t *r)
+{
+ return (r->read == r->write);
+}
+
+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;
+}
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/serial_over_dp.ld b/app/serial_over_dp.ld
new file mode 100644
index 0000000..a2d5a9c
--- /dev/null
+++ b/app/serial_over_dp.ld
@@ -0,0 +1,43 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ */
+
+/* Linker script for Olimex STM32-H103 (STM32F103RBT6, 128K flash, 20K RAM). */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08002000, LENGTH = 120K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+}
+
+/* Include the common ld script. */
+INCLUDE libopencm3_stm32f1.ld
+
+dfu_shared_location = ORIGIN(ram) + LENGTH(ram) - 1024;
+
+/* PROVIDE(_stack = dfu_shared_location ); */
+
+SECTIONS
+{
+ .dfu_shared dfu_shared_location :{
+ dfu_flag = .;
+ }
+}
+
+
diff --git a/app/ticker.c b/app/ticker.c
new file mode 100644
index 0000000..05990d2
--- /dev/null
+++ b/app/ticker.c
@@ -0,0 +1,76 @@
+#include "project.h"
+
+
+static volatile uint32_t ticks;
+static uint32_t scale = 7;
+
+unsigned led1 = 1000, led2 = 1000;
+
+
+
+void
+delay_us (uint32_t d)
+{
+ d *= scale;
+
+ while (d--) {
+ __asm__ ("nop");
+ }
+}
+
+void
+sys_tick_handler (void)
+{
+ ticks++;
+ cdcacm_tick();
+
+ if (led1) {
+ led1--;
+ }
+
+ if (led2) {
+ led2--;
+ }
+
+ if (led1) {
+ gpio_clear (LED1_BANK, LED1_GPIO);
+ } else {
+ gpio_set (LED1_BANK, LED1_GPIO);
+ }
+
+ if (led2) {
+ gpio_clear (LED2_BANK, LED2_GPIO);
+ } else {
+ gpio_set (LED2_BANK, LED2_GPIO);
+ }
+}
+
+
+void
+ticker_init (void)
+{
+ uint32_t v, w;
+ /*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();
+
+ /*Calibrate the delay loop */
+ do {
+ scale--;
+ v = ticks;
+
+ while (v == ticks) {
+ ;
+ }
+
+ delay_us (1000);
+ w = ticks;
+ v++;
+ w -= v;
+ } while (w);
+}
+
diff --git a/app/usart.c b/app/usart.c
new file mode 100644
index 0000000..ecd8e56
--- /dev/null
+++ b/app/usart.c
@@ -0,0 +1,90 @@
+#include "project.h"
+
+#define BUFFER_SIZE 512
+
+ring_t usart_rx_ring;
+static uint8_t usart_rx_ring_buf[BUFFER_SIZE];
+
+ring_t usart_tx_ring;
+static uint8_t usart_tx_ring_buf[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 (&usart_rx_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 (&usart_tx_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 usart_kick (void)
+{
+ if (!ring_empty (&usart_tx_ring)) {
+ USART_CR1 (USART1) |= USART_CR1_TXEIE;
+ }
+}
+
+
+int
+_write (int file, char *ptr, int len)
+{
+ int ret;
+
+ if (file == 1) {
+ ret = ring_write (&usart_tx_ring, (uint8_t *) ptr, len);
+ usart_kick();
+
+ if (ret < 0) {
+ ret = -ret;
+ }
+
+ return ret;
+ }
+
+ errno = EIO;
+ return -1;
+}
+
+
+
+
+void
+usart_init (void)
+{
+ ring_init (&usart_rx_ring, usart_rx_ring_buf, sizeof (usart_rx_ring_buf));
+ ring_init (&usart_tx_ring, usart_tx_ring_buf, sizeof (usart_tx_ring_buf));
+ /* Enable the USART1 interrupt. */
+ nvic_enable_irq (NVIC_USART1_IRQ);
+ /* Map pins */
+ 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);
+ /* Setup UART1 parameters. */
+ usart_set_baudrate (USART1, 115200);
+ 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);
+ /* Enable USART1 Receive interrupt. */
+ USART_CR1 (USART1) |= USART_CR1_RXNEIE;
+ /* Finally enable USART1. */
+ usart_enable (USART1);
+}
diff --git a/app/vuart.c b/app/vuart.c
new file mode 100644
index 0000000..5aaf2d3
--- /dev/null
+++ b/app/vuart.c
@@ -0,0 +1,217 @@
+#include "project.h"
+
+#define RXR ((0))
+#define TXR ((0))
+#define DLLR ((0))
+
+#define IER ((1))
+#define DLHR ((1))
+
+#define IIR ((2))
+#define FCR ((2))
+
+#define LCR ((3))
+#define LCR_WS0 (1<<0)
+#define LCR_WS1 (1<<1)
+#define LCR_NSTOP (1<<2)
+#define LCR_PARITY_ENABLE (1<<3)
+#define LCR_EVEN_PARITY (1<<4)
+#define LCR_STUCK_PARITY (1<<5)
+#define LCR_BREAK (1<<6)
+#define LCR_DLAB (1<<7)
+
+#define MCR ((4))
+#define MCR_DTR (1<<0)
+#define MCR_RTS (1<<1)
+#define MCR_AUX1 (1<<2)
+#define MCR_AUX2 (1<<3)
+#define MCR_LOOP (1<<4)
+#define MCR_AUTOFLOW (1<<5)
+
+#define LSR ((5))
+#define LSR_DA (1<<0)
+#define LSR_OR (1<<1)
+#define LSR_PE (1<<2)
+#define LSR_FE (1<<3)
+#define LSR_BRK (1<<4)
+#define LSR_THRE (1<<5)
+#define LSR_THREI (1<<6)
+#define LSR_FIFOE (1<<7)
+
+#define MSR ((6))
+#define MSR_DCTS (1<<0)
+#define MSR_DDSR (1<<1)
+#define MSR_TERI (1<<2)
+#define MSR_DDCD (1<<3)
+#define MSR_CTS (1<<4)
+#define MSR_DSR (1<<5)
+#define MSR_RI (1<<6)
+#define MSR_DCD (1<<7)
+
+#define SR ((7))
+
+
+/* 0 */
+static uint8_t dllr = 1; /* 115200 baud */
+
+/* 1 */
+static uint8_t dlhr = 0;
+static uint8_t ier = 0;
+
+/* 2 */
+static uint8_t iir = 0;
+
+/* 3 */
+static uint8_t lcr = LCR_WS0 | LCR_WS1; /* 8 bits, 1 stop, no parity */
+
+/* 4 */
+static uint8_t mcr = MCR_RTS | MCR_DTR; /* RTS and DTR on */
+
+/* 5 */
+static uint8_t lsr = LSR_THRE | LSR_THREI;
+
+/* 6 */
+static uint8_t msr = MSR_CTS | MSR_DSR | MSR_DCD;
+
+/* 7 */
+static uint8_t sr = 0;
+
+
+static void vuart_xmit (uint8_t c)
+{
+ led1 = 100;
+ ring_write_byte (&usart_tx_ring, c);
+ usart_kick();
+#ifdef USB
+ ring_write_byte (&cdcacm_tx_ring, c);
+#endif
+}
+
+
+static int vuart_recv_empty (void)
+{
+ if (!ring_empty (&usart_rx_ring)) {
+ return 0;
+ }
+
+#ifdef USB
+
+ if (!ring_empty (&cdcacm_rx_ring)) {
+ return 0;
+ }
+
+#endif
+ return 1;
+}
+
+
+static int vuart_recv (uint8_t *c)
+{
+ *c = 0;
+
+ if (!ring_read_byte (&usart_rx_ring, c)) {
+ led2 = 100;
+ return 0;
+ }
+
+#ifdef USB
+
+ if (!ring_read_byte (&cdcacm_rx_ring, c)) {
+ led2 = 100;
+ return 0;
+ }
+
+#endif
+ return -1;
+}
+
+
+static void update_lsr (void)
+{
+ if (vuart_recv_empty()) {
+ lsr &= ~LSR_DA;
+ } else {
+ lsr |= LSR_DA;
+ }
+}
+
+uint8_t vuart_read (unsigned reg)
+{
+ uint8_t val;
+
+ switch (reg) {
+ case RXR:
+
+ //case DLLR:
+ if (! (lcr & LCR_DLAB)) {
+ vuart_recv (&val);
+ update_lsr();
+ return val;
+ } else {
+ return dllr;
+ }
+
+ case IER:
+ //case DLLH:
+ return (lcr & LCR_DLAB) ? dlhr : ier;
+ case IIR:
+ return iir;
+ case LCR:
+ return lcr;
+ case MCR:
+ return mcr;
+ case LSR:
+ update_lsr();
+ val = lsr;
+ lsr &= 0xe1;
+ return val;
+ case MSR:
+ val = msr;
+ msr &= 0xf0;
+ return val;
+ case SR:
+ return sr;
+ }
+
+ return 0;
+}
+
+
+void vuart_write (unsigned reg, uint8_t val)
+{
+ switch (reg) {
+ case RXR:
+
+ //case DLLR:
+ if (! (lcr & LCR_DLAB)) {
+ vuart_xmit (val);
+ } else {
+ dllr = val;
+ }
+
+ break;
+ case IER:
+
+ //case DLHR:
+ if (! (lcr & LCR_DLAB)) {
+ ier = val & 0xf;
+ } else {
+ dlhr = val;
+ }
+
+ break;
+ case LCR:
+ lcr = val;
+ break;
+ case MCR:
+ mcr = val & 0x1f;
+ break;
+ case SR:
+ sr = val;
+ break;
+ }
+}
+
+
+
+
diff --git a/boot/Makefile b/boot/Makefile
new file mode 100644
index 0000000..86d4d2c
--- /dev/null
+++ b/boot/Makefile
@@ -0,0 +1,32 @@
+##
+## This file is part of the libopencm3 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## 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 <http://www.gnu.org/licenses/>.
+##
+
+
+CSRCS=usbdfu.c
+PROG = usbdfu
+
+CPROTO=cproto
+V=1
+BINARY = ${PROG}
+OBJS = ${CSRCS:%.c=%.o}
+
+include ../Makefile.include
+
+CFLAGS += -I..
+
diff --git a/boot/project.h b/boot/project.h
new file mode 100644
index 0000000..0323569
--- /dev/null
+++ b/boot/project.h
@@ -0,0 +1,23 @@
+#include <stdlib.h>
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/usart.h>
+#include <libopencm3/cm3/systick.h>
+#include <libopencm3/cm3/nvic.h>
+#include <libopencm3/usb/usbd.h>
+#include <libopencm3/usb/hid.h>
+
+#define INCLUDE_DFU_INTERFACE
+
+
+#ifdef INCLUDE_DFU_INTERFACE
+#include <libopencm3/cm3/scb.h>
+#include <libopencm3/usb/dfu.h>
+#endif
+
+#include <stdio.h>
+#include <errno.h>
+
+#include "ring.h"
+
+#include "prototypes.h"
diff --git a/boot/prototypes.h b/boot/prototypes.h
new file mode 100644
index 0000000..45d399c
--- /dev/null
+++ b/boot/prototypes.h
@@ -0,0 +1,18 @@
+/* usbdfu.c */
+extern uint8_t usbd_control_buffer[1024];
+extern const struct usb_device_descriptor dev;
+extern const struct usb_dfu_descriptor dfu_function;
+extern const struct usb_interface_descriptor iface;
+extern const struct usb_interface ifaces[];
+extern const struct usb_config_descriptor config;
+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);
+/* usart.c */
+extern void usart1_isr(void);
+extern int _write(int file, char *ptr, int len);
+extern void usart_queue(uint8_t d);
+extern void usart_init(void);
diff --git a/boot/usbdfu.c b/boot/usbdfu.c
new file mode 100644
index 0000000..d538234
--- /dev/null
+++ b/boot/usbdfu.c
@@ -0,0 +1,290 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ */
+
+#include <string.h>
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/flash.h>
+#include <libopencm3/cm3/scb.h>
+#include <libopencm3/usb/usbd.h>
+#include <libopencm3/usb/dfu.h>
+
+#include <id.h>
+
+#define APP_ADDRESS 0x08002000
+
+/* Commands sent with wBlockNum == 0 as per ST implementation. */
+#define CMD_SETADDR 0x21
+#define CMD_ERASE 0x41
+
+void usb_set_config (usbd_device * usbd_dev, uint16_t wValue);
+
+/* We need a special large control buffer for this device: */
+uint8_t usbd_control_buffer[1024];
+
+static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
+
+extern uint32_t dfu_flag;
+
+static struct {
+ uint8_t buf[sizeof(usbd_control_buffer)];
+ uint16_t len;
+ uint32_t addr;
+ uint16_t blocknum;
+} prog;
+
+const struct usb_device_descriptor dev = {
+ .bLength = USB_DT_DEVICE_SIZE,
+ .bDescriptorType = USB_DT_DEVICE,
+ .bcdUSB = 0x0200,
+ .bDeviceClass = 0,
+ .bDeviceSubClass = 0,
+ .bDeviceProtocol = 0,
+ .bMaxPacketSize0 = 64,
+ .idVendor = ID_VENDOR,
+ .idProduct = ID_PRODUCT,
+ .bcdDevice = 0x0200,
+ .iManufacturer = 1,
+ .iProduct = 2,
+ .iSerialNumber = 3,
+ .bNumConfigurations = 1,
+};
+
+const struct usb_dfu_descriptor dfu_function = {
+ .bLength = sizeof(struct usb_dfu_descriptor),
+ .bDescriptorType = DFU_FUNCTIONAL,
+ .bmAttributes = USB_DFU_CAN_DOWNLOAD,
+ .wDetachTimeout = 255,
+ .wTransferSize = 1024,
+ .bcdDFUVersion = 0x011A,
+};
+
+const struct usb_interface_descriptor iface = {
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 0,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 0,
+ .bInterfaceClass = 0xFE, /* Device Firmware Upgrade */
+ .bInterfaceSubClass = 1,
+ .bInterfaceProtocol = 2,
+
+ /* The ST Microelectronics DfuSe application needs this string.
+ * The format isn't documented... */
+ .iInterface = 4,
+
+ .extra = &dfu_function,
+ .extralen = sizeof(dfu_function),
+};
+
+const struct usb_interface ifaces[] = {{
+ .num_altsetting = 1,
+ .altsetting = &iface,
+}};
+
+const struct usb_config_descriptor config = {
+ .bLength = USB_DT_CONFIGURATION_SIZE,
+ .bDescriptorType = USB_DT_CONFIGURATION,
+ .wTotalLength = 0,
+ .bNumInterfaces = 1,
+ .bConfigurationValue = 1,
+ .iConfiguration = 0,
+ .bmAttributes = 0xC0,
+ .bMaxPower = 0x32,
+
+ .interface = ifaces,
+};
+
+static const char *usb_strings[] = {
+ "Cabbages are good for you",
+ "fish",
+ "soup",
+ /* This string is used by ST Microelectronics' DfuSe utility. */
+ "@Internal Flash /0x08000000/8*001Ka,56*001Kg",
+};
+
+static uint8_t usbdfu_getstatus(usbd_device *usbd_dev, uint32_t *bwPollTimeout)
+{
+ (void)usbd_dev;
+
+ switch (usbdfu_state) {
+ case STATE_DFU_DNLOAD_SYNC:
+ usbdfu_state = STATE_DFU_DNBUSY;
+ *bwPollTimeout = 100;
+ return DFU_STATUS_OK;
+ case STATE_DFU_MANIFEST_SYNC:
+ /* Device will reset when read is complete. */
+ usbdfu_state = STATE_DFU_MANIFEST;
+ return DFU_STATUS_OK;
+ default:
+ return DFU_STATUS_OK;
+ }
+}
+
+static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_data *req)
+{
+ int i;
+ (void)req;
+ (void)usbd_dev;
+
+ switch (usbdfu_state) {
+ case STATE_DFU_DNBUSY:
+ flash_unlock();
+ if (prog.blocknum == 0) {
+ switch (prog.buf[0]) {
+ case CMD_ERASE:
+ {
+ uint32_t *dat = (uint32_t *)(prog.buf + 1);
+ flash_erase_page(*dat);
+ }
+ case CMD_SETADDR:
+ {
+ uint32_t *dat = (uint32_t *)(prog.buf + 1);
+ prog.addr = *dat;
+ }
+ }
+ } else {
+ uint32_t baseaddr = prog.addr + ((prog.blocknum - 2) *
+ dfu_function.wTransferSize);
+ for (i = 0; i < prog.len; i += 2) {
+ uint16_t *dat = (uint16_t *)(prog.buf + i);
+ flash_program_half_word(baseaddr + i,
+ *dat);
+ }
+ }
+ flash_lock();
+
+ /* Jump straight to dfuDNLOAD-IDLE, skipping dfuDNLOAD-SYNC. */
+ usbdfu_state = STATE_DFU_DNLOAD_IDLE;
+ return;
+ case STATE_DFU_MANIFEST:
+ /* USB device must detach, we just reset... */
+ scb_reset_system();
+ return; /* Will never return. */
+ default:
+ return;
+ }
+}
+
+static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
+ uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
+{
+
+ if ((req->bmRequestType & 0x7F) != 0x21)
+ return 0; /* Only accept class request. */
+
+ switch (req->bRequest) {
+ case DFU_DNLOAD:
+ if ((len == NULL) || (*len == 0)) {
+ usbdfu_state = STATE_DFU_MANIFEST_SYNC;
+ return 1;
+ } else {
+ /* Copy download data for use on GET_STATUS. */
+ prog.blocknum = req->wValue;
+ prog.len = *len;
+ memcpy(prog.buf, *buf, *len);
+ usbdfu_state = STATE_DFU_DNLOAD_SYNC;
+ return 1;
+ }
+ case DFU_CLRSTATUS:
+ /* Clear error and return to dfuIDLE. */
+ if (usbdfu_state == STATE_DFU_ERROR)
+ usbdfu_state = STATE_DFU_IDLE;
+ return 1;
+ case DFU_ABORT:
+ /* Abort returns to dfuIDLE state. */
+ usbdfu_state = STATE_DFU_IDLE;
+ return 1;
+ case DFU_UPLOAD:
+ /* Upload not supported for now. */
+ return 0;
+ case DFU_GETSTATUS: {
+ uint32_t bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
+ (*buf)[0] = usbdfu_getstatus(usbd_dev, &bwPollTimeout);
+ (*buf)[1] = bwPollTimeout & 0xFF;
+ (*buf)[2] = (bwPollTimeout >> 8) & 0xFF;
+ (*buf)[3] = (bwPollTimeout >> 16) & 0xFF;
+ (*buf)[4] = usbdfu_state;
+ (*buf)[5] = 0; /* iString not used here */
+ *len = 6;
+ *complete = usbdfu_getstatus_complete;
+ return 1;
+ }
+ case DFU_GETSTATE:
+ /* Return state with no state transision. */
+ *buf[0] = usbdfu_state;
+ *len = 1;
+ return 1;
+ }
+
+ return 0;
+}
+
+void
+usb_set_config (usbd_device * usbd_dev, uint16_t wValue)
+{
+ (void) wValue;
+ (void) usbd_dev;
+
+ usbd_register_control_callback(
+ usbd_dev,
+ USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ usbdfu_control_request);
+
+}
+
+int main(void)
+{
+ usbd_device *usbd_dev;
+
+ rcc_periph_clock_enable(RCC_GPIOA);
+
+ if (dfu_flag!=0xfee1dead) {
+ /* Boot the application if it's valid. */
+ if ((*(volatile uint32_t *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
+ /* Set vector table base address. */
+ SCB_VTOR = APP_ADDRESS & 0xFFFF;
+ /* Initialise master stack pointer. */
+ asm volatile("msr msp, %0"::"g"
+ (*(volatile uint32_t *)APP_ADDRESS));
+ /* Jump to application. */
+ (*(void (**)())(APP_ADDRESS + 4))();
+ }
+ }
+
+ dfu_flag=0;
+
+ rcc_clock_setup_in_hsi_out_48mhz();
+
+ rcc_periph_clock_enable(RCC_GPIOC);
+
+ gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO11);
+ gpio_set(GPIOC, GPIO11);
+
+ usbd_dev = usbd_init(&stm32f103_usb_driver, &dev, &config, usb_strings, 4, usbd_control_buffer, sizeof(usbd_control_buffer));
+
+ usbd_register_set_config_callback (usbd_dev, usb_set_config);
+
+ gpio_clear(GPIOC, GPIO11);
+
+ while (1)
+ usbd_poll(usbd_dev);
+}
diff --git a/boot/usbdfu.ld b/boot/usbdfu.ld
new file mode 100644
index 0000000..8680dc9
--- /dev/null
+++ b/boot/usbdfu.ld
@@ -0,0 +1,40 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ */
+
+/* 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
+
+dfu_shared_location = ORIGIN(ram) + LENGTH(ram) - 1024;
+
+SECTIONS
+{
+ .dfu_shared dfu_shared_location :{
+ dfu_flag = .;
+ }
+}
+
diff --git a/docs/SC16IS740_750_760.pdf b/docs/SC16IS740_750_760.pdf
new file mode 100644
index 0000000..fad2127
--- /dev/null
+++ b/docs/SC16IS740_750_760.pdf
Binary files differ
diff --git a/docs/rm0008.pdf b/docs/rm0008.pdf
new file mode 100644
index 0000000..8f3d0e1
--- /dev/null
+++ b/docs/rm0008.pdf
Binary files differ
diff --git a/id.h b/id.h
new file mode 100644
index 0000000..c65f067
--- /dev/null
+++ b/id.h
@@ -0,0 +1,3 @@
+#define ID_VENDOR 0x1234
+#define ID_PRODUCT 0x5678
+
diff --git a/oocd/board/STM32F103R_BOARD.cfg b/oocd/board/STM32F103R_BOARD.cfg
new file mode 100644
index 0000000..11217d2
--- /dev/null
+++ b/oocd/board/STM32F103R_BOARD.cfg
@@ -0,0 +1,6 @@
+#
+
+source [find target/stm32f1x.cfg]
+
+adapter_khz 500
+
diff --git a/oocd/interface/j-link.cfg b/oocd/interface/j-link.cfg
new file mode 100644
index 0000000..3e95768
--- /dev/null
+++ b/oocd/interface/j-link.cfg
@@ -0,0 +1,5 @@
+#
+telnet_port 4444
+gdb_port 3333
+
+source [find interface/jlink.cfg]
diff --git a/oocd/interface/stlink-v2.cfg b/oocd/interface/stlink-v2.cfg
new file mode 100644
index 0000000..0985230
--- /dev/null
+++ b/oocd/interface/stlink-v2.cfg
@@ -0,0 +1,11 @@
+#
+telnet_port 4444
+gdb_port 3333
+
+#interface hla
+#hla_layout stlink
+#hla_device_desc "ST-LINK/V2"
+#hla_vid_pid 0x0483 0x3748
+
+source [find interface/stlink-v2.cfg]
+
diff --git a/oocd/stm32-f103.cfg b/oocd/stm32-f103.cfg
new file mode 100644
index 0000000..0809223
--- /dev/null
+++ b/oocd/stm32-f103.cfg
@@ -0,0 +1,6 @@
+#
+telnet_port 4444
+gdb_port 3333
+
+source [find interface/jlink.cfg]
+source [find target/stm32f1x.cfg]