summaryrefslogtreecommitdiffstats
path: root/boot
diff options
context:
space:
mode:
authorroot <root@lab.ourano.james.local>2021-02-26 12:12:38 +0000
committerroot <root@lab.ourano.james.local>2021-02-26 12:12:38 +0000
commit3d48137c00511b3f2d35511482d1a76f8d06382d (patch)
treed75c88220cc847007869b0795a240c5077948262 /boot
parent6d3a824e1cdae6e28146b7de380724b49488f3c2 (diff)
downloadclock-3d48137c00511b3f2d35511482d1a76f8d06382d.tar.gz
clock-3d48137c00511b3f2d35511482d1a76f8d06382d.tar.bz2
clock-3d48137c00511b3f2d35511482d1a76f8d06382d.zip
works
Diffstat (limited to 'boot')
-rw-r--r--boot/Makefile49
-rw-r--r--boot/bootloader.c139
-rw-r--r--boot/bootloader.ld38
-rw-r--r--boot/delay.c42
-rw-r--r--boot/dfu.c197
-rw-r--r--boot/gdb.script2
-rw-r--r--boot/max7219.c124
-rw-r--r--boot/pins.h55
-rw-r--r--boot/project.h29
-rw-r--r--boot/prototypes.h27
-rw-r--r--boot/usart.c68
-rw-r--r--boot/usb.c94
12 files changed, 864 insertions, 0 deletions
diff --git a/boot/Makefile b/boot/Makefile
new file mode 100644
index 0000000..e744d9a
--- /dev/null
+++ b/boot/Makefile
@@ -0,0 +1,49 @@
+##
+## 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=bootloader.c usb.c dfu.c delay.c usart.c max7219.c
+PROG = bootloader
+
+CPROTO=cproto
+V=1
+BINARY = ${PROG}
+OBJS = ${CSRCS:%.c=%.o}
+
+include ../Makefile.include
+
+CPPFLAGS += -I..
+CFLAGS += ${CPPFLAGS}
+CFLAGS+=-Wno-redundant-decls -Wno-unused-parameter
+
+ds:
+ $(Q)$(OOCD) -f ../oocd/interface/$(OOCD_INTERFACE).cfg \
+ -f ../oocd/board/$(OOCD_BOARD).cfg
+
+debug: ${PROG}.elf
+ ${PREFIX}-gdb -x gdb.script ${PROG}.elf
+
+protos: ${CSRCS}
+ echo -n > prototypes.h
+ ${CPROTO} -E "${CPP} $(CPPFLAGS)" -e -v ${CSRCS} > prototypes.h.tmp
+ /bin/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}
diff --git a/boot/bootloader.c b/boot/bootloader.c
new file mode 100644
index 0000000..27b6b98
--- /dev/null
+++ b/boot/bootloader.c
@@ -0,0 +1,139 @@
+/*
+ * 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 "project.h"
+
+
+#define BOOTLOADER_BUTTON GPIO15
+#define BOOTLOADER_BUTTON_PORT GPIOE
+
+
+static const clock_scale_t hsi_16mhz_3v3_48 = {
+ /* 48MHz */
+ .pllm = 16,
+ .plln = 96,
+ .pllp = 2,
+ .pllq = 2,
+ .hpre = RCC_CFGR_HPRE_DIV_NONE,
+ .ppre1 = RCC_CFGR_PPRE_DIV_4,
+ .ppre2 = RCC_CFGR_PPRE_DIV_2,
+ .power_save = 1,
+ .flash_config = FLASH_ACR_ICE | FLASH_ACR_DCE |
+ FLASH_ACR_LATENCY_3WS,
+ .apb1_frequency = 12000000,
+ .apb2_frequency = 24000000,
+};
+
+static void rcc_clock_setup_hsi_3v3 (const clock_scale_t *clock)
+{
+
+ /* Enable internal high-speed oscillator. */
+ rcc_osc_on (HSI);
+ rcc_wait_for_osc_ready (HSI);
+
+ /* Select HSI as SYSCLK source. */
+ rcc_set_sysclk_source (RCC_CFGR_SW_HSI);
+ rcc_wait_for_sysclk_status (HSI);
+
+ rcc_osc_off (PLL);
+
+ while (RCC_CR & RCC_CR_PLLRDY);
+
+ pwr_set_vos_scale (SCALE1);
+
+ /*
+ * Set prescalers for AHB, ADC, ABP1, ABP2.
+ * Do this before touching the PLL (TODO: why?).
+ */
+ rcc_set_hpre (clock->hpre);
+ rcc_set_ppre1 (clock->ppre1);
+ rcc_set_ppre2 (clock->ppre2);
+
+ rcc_set_main_pll_hsi (clock->pllm, clock->plln,
+ clock->pllp, clock->pllq);
+
+ /* Enable PLL oscillator and wait for it to stabilize. */
+ rcc_osc_on (PLL);
+ rcc_wait_for_osc_ready (PLL);
+
+ /* Configure flash settings. */
+ flash_set_ws (clock->flash_config);
+
+ /* Select PLL as SYSCLK source. */
+ rcc_set_sysclk_source (RCC_CFGR_SW_PLL);
+
+ /* Wait for PLL clock to be selected. */
+ rcc_wait_for_sysclk_status (PLL);
+
+ /* Set the peripheral clock frequencies used. */
+ rcc_apb1_frequency = clock->apb1_frequency;
+ rcc_apb2_frequency = clock->apb2_frequency;
+
+}
+
+
+int main (void)
+{
+
+ rcc_periph_clock_enable (RCC_GPIOE);
+ MAP_INPUT_PU (BOOTLOADER_BUTTON);
+
+
+ if ((dfu_flag != 0xfee1dead) && (GET(BOOTLOADER_BUTTON))) {
+ /* Boot the application if it's valid. */
+ if ((* (volatile uint32_t *)APP_ADDRESS & 0x2FFE0000) == 0x20020000) {
+ /* Set vector table base address. */
+ SCB_VTOR = APP_ADDRESS & 0xFFFF;
+ /* Initialise master stack pointer. */
+ asm volatile ("msr msp, %0\n"
+ "blx %1\n" ::
+ "g" (* (volatile uint32_t *)APP_ADDRESS),
+ "r" (* (uint32_t *) (APP_ADDRESS + 4))
+ : "memory");
+ }
+ }
+
+
+
+
+ dfu_flag = 0;
+
+ rcc_periph_clock_enable (RCC_SYSCFG);
+ rcc_periph_clock_enable (RCC_GPIOB);
+ rcc_periph_clock_enable (RCC_GPIOG);
+
+ rcc_clock_setup_hsi_3v3 (&hsi_16mhz_3v3_48);
+
+ RCC_AHB1RSTR |= RCC_AHB1RSTR_ETHMACRST;
+ RCC_AHB2RSTR |= RCC_AHB2RSTR_OTGFSRST;
+ asm ("nop":::"memory");
+ RCC_AHB2RSTR &= ~RCC_AHB2RSTR_OTGFSRST;
+ RCC_AHB1RSTR &= ~RCC_AHB1RSTR_ETHMACRST;
+
+ max7219_init();
+
+ usart_init();
+ usart2_xmit_str("\r\nDFU Bootloader\r\n");
+ delay_ms (100);
+ usart_init();
+ usart2_xmit_str ("Ready\r\n");
+
+
+ usb();
+}
diff --git a/boot/bootloader.ld b/boot/bootloader.ld
new file mode 100644
index 0000000..cedb886
--- /dev/null
+++ b/boot/bootloader.ld
@@ -0,0 +1,38 @@
+/*
+ * 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). */
+
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K
+ ram (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
+}
+
+/* Include the common ld script. */
+INCLUDE libopencm3_stm32f4.ld
+
+dfu_shared_location = ORIGIN(ram) + LENGTH(ram) - 1024;
+
+SECTIONS
+{
+ .dfu_shared dfu_shared_location :{
+ dfu_flag = .;
+ }
+}
diff --git a/boot/delay.c b/boot/delay.c
new file mode 100644
index 0000000..132081a
--- /dev/null
+++ b/boot/delay.c
@@ -0,0 +1,42 @@
+#include "project.h"
+
+
+
+static volatile uint32_t delay_ms_count;
+
+void
+sys_tick_handler (void)
+{
+ if (delay_ms_count)
+ delay_ms_count--;
+}
+void
+ticker_on (void)
+{
+ /*168MHz 1ms */
+ systick_set_reload (48000);
+ systick_set_clocksource (STK_CSR_CLKSOURCE_AHB);
+ systick_counter_enable();
+ /* this done last */
+ systick_interrupt_enable();
+}
+
+void
+ticker_off (void)
+{
+ systick_interrupt_disable();
+ systick_counter_disable();
+}
+
+
+void
+delay_ms (uint32_t d)
+{
+ ticker_on();
+ delay_ms_count = d;
+
+ while (delay_ms_count);
+ ticker_off();
+}
+
+
diff --git a/boot/dfu.c b/boot/dfu.c
new file mode 100644
index 0000000..f931a6e
--- /dev/null
+++ b/boot/dfu.c
@@ -0,0 +1,197 @@
+#include "project.h"
+
+/* Commands sent with wBlockNum == 0 as per ST implementation. */
+#define CMD_SETADDR 0x21
+#define CMD_ERASE 0x41
+
+
+/* We need a special large control buffer for this device: */
+
+static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
+
+static uint32_t sector_bases[] = {
+ 0x08000000,
+ 0x08004000,
+ 0x08008000,
+ 0x0800C000,
+ 0x08010000,
+ 0x08020000,
+ 0x08040000,
+ 0x08060000,
+ 0x08080000,
+ 0x080A0000,
+ 0x080C0000,
+ 0x080E0000,
+};
+
+#define N_SECTORS (sizeof(sector_bases)/sizeof(sector_bases[0]))
+
+static struct {
+ uint8_t buf[sizeof (usbd_control_buffer)];
+ uint16_t len;
+ uint32_t addr;
+ uint16_t blocknum;
+} prog;
+
+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 = 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),
+};
+
+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 int usbdfu_getstatus_complete (usbd_device *usbd_dev, struct usb_setup_data *req)
+{
+ unsigned 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);
+
+ for (i = 0; i < N_SECTORS; ++i) {
+ if (*dat == sector_bases[i])
+ flash_erase_sector (i, FLASH_CR_PROGRAM_X32);
+ }
+ }
+
+ /*Fall through*/
+ 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 += 4) {
+ uint32_t *dat = (uint32_t *) (prog.buf + i);
+ flash_program_word (baseaddr + i, *dat);
+ }
+ }
+
+ flash_lock();
+
+ /* Jump straight to dfuDNLOAD-IDLE, skipping dfuDNLOAD-SYNC. */
+ usbdfu_state = STATE_DFU_DNLOAD_IDLE;
+ return 0;
+
+ case STATE_DFU_MANIFEST:
+ /* USB device must detach, we just reset... */
+ scb_reset_system();
+ return 0; /* Will never return. */
+
+ default:
+ return 0;
+ }
+}
+
+int usbdfu_control_request (usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
+ uint16_t *len, int (**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;
+}
+
+
diff --git a/boot/gdb.script b/boot/gdb.script
new file mode 100644
index 0000000..7cf9d09
--- /dev/null
+++ b/boot/gdb.script
@@ -0,0 +1,2 @@
+target remote localhost:3333
+cont
diff --git a/boot/max7219.c b/boot/max7219.c
new file mode 100644
index 0000000..3e06562
--- /dev/null
+++ b/boot/max7219.c
@@ -0,0 +1,124 @@
+#include "project.h"
+
+#define NCS (GPIO7)
+#define NCS_PORT GPIOG
+
+#define SCK (GPIO3)
+#define SCK_PORT GPIOB
+
+#define MOSI (GPIO5)
+#define MOSI_PORT GPIOB
+
+
+static void
+set (int sck, int ncs, int mosi)
+{
+ if (sck)
+ SET (SCK);
+ else
+ CLEAR (SCK);
+
+
+ if (ncs)
+ SET (NCS);
+ else
+ CLEAR (NCS);
+
+
+ if (mosi)
+ SET (MOSI);
+ else
+ CLEAR (MOSI);
+
+ // delay_us(1);
+ //delay_us(10);
+
+}
+
+static void
+spip_send_8 (uint8_t wot)
+{
+ int i;
+
+ for (i = 0; i < 8; ++i) {
+ set (0, 0, wot & 0x80);
+ set (1, 0, wot & 0x80);
+ set (0, 0, wot & 0x80);
+ wot <<= 1;
+ }
+}
+
+
+
+static void
+write_reg (uint8_t reg, uint8_t data)
+{
+
+ set (0, 1, 0);
+ set (0, 0, 0);
+
+ spip_send_8 (reg);
+ spip_send_8 (data);
+
+ spip_send_8 (reg);
+ spip_send_8 (data);
+
+ spip_send_8 (reg);
+ spip_send_8 (data);
+
+ set (0, 0, 0);
+ set (0, 1, 0);
+}
+
+
+static void
+write_regs (uint8_t reg, uint8_t data1, uint8_t data2, uint8_t data3)
+{
+
+ set (0, 1, 0);
+ set (0, 0, 0);
+
+ spip_send_8 (reg);
+ spip_send_8 (data3);
+
+ spip_send_8 (reg);
+ spip_send_8 (data2);
+
+ spip_send_8 (reg);
+ spip_send_8 (data1);
+
+ set (0, 0, 0);
+ set (0, 1, 0);
+}
+
+
+void
+max7219_init (void)
+{
+ MAP_OUTPUT_PP (SCK);
+ MAP_OUTPUT_PP (NCS);
+ MAP_OUTPUT_PP (MOSI);
+
+ set (0, 1, 0);
+
+
+ write_reg (0xc, 0x1); //Power up
+ write_reg (0xf, 0x0); //normal mode
+
+ write_reg (0x9, 0x0); //No decode
+ write_reg (0xb, 0x7); //8 digits
+ write_regs (0xa,15,15,15); //max brightness
+ write_reg (1,0);
+ write_reg (2,0);
+ write_reg (3,0);
+ write_reg (4,0);
+ write_reg (5,0);
+ write_regs (6,0xbe,0,0);
+ write_regs (7,0x47,0,0);
+ write_regs (8,0x3d,0,0);
+
+}
+
+
+
+
diff --git a/boot/pins.h b/boot/pins.h
new file mode 100644
index 0000000..723ca82
--- /dev/null
+++ b/boot/pins.h
@@ -0,0 +1,55 @@
+
+#define MAP_AF_100(a, af) do { \
+ gpio_mode_setup( a ## _PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, a ); \
+ gpio_set_output_options( a ## _PORT, GPIO_OTYPE_PP, GPIO_OSPEED_100MHZ, a); \
+ gpio_set_af( a ## _PORT, af, a); \
+ } while (0)
+
+#define MAP_AF(a, af) do { \
+ gpio_mode_setup( a ## _PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, a ); \
+ gpio_set_output_options( a ## _PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, a); \
+ gpio_set_af( a ## _PORT, af, a); \
+ } while (0)
+
+#define MAP_AF_PU(a, af) do { \
+ gpio_mode_setup( a ## _PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, a ); \
+ gpio_set_output_options( a ## _PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, a); \
+ gpio_set_af( a ## _PORT, af, a); \
+ } while (0)
+
+#define MAP_AF_OD(a, af) do { \
+ gpio_mode_setup( a ## _PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, a ); \
+ gpio_set_output_options( a ## _PORT, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, a); \
+ gpio_set_af( a ## _PORT, af, a); \
+ } while (0)
+
+
+#define MAP_OUTPUT_PP(a) do { \
+ gpio_mode_setup( a ## _PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, a ); \
+ gpio_set_output_options( a ## _PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, a); \
+ } while (0)
+
+#define MAP_OUTPUT_PP_PU(a) do { \
+ gpio_mode_setup( a ## _PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_PULLUP, a ); \
+ gpio_set_output_options( a ## _PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, a); \
+ } while (0)
+
+#define MAP_OUTPUT_OD(a) do { \
+ gpio_mode_setup( a ## _PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_PULLUP, a ); \
+ gpio_set_output_options( a ## _PORT, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, a); \
+ } while (0)
+
+
+#define MAP_INPUT_PU(a) do { \
+ gpio_mode_setup( a ## _PORT, GPIO_MODE_INPUT, GPIO_PUPD_PULLUP, a ); \
+ } while (0)
+
+
+#define MAP_INPUT(a) do { \
+ gpio_mode_setup( a ## _PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE, a ); \
+ } while (0)
+
+
+#define CLEAR(a) gpio_clear( a ## _PORT, a)
+#define SET(a) gpio_set( a ## _PORT, a)
+#define GET(a) gpio_get( a ## _PORT, a)
diff --git a/boot/project.h b/boot/project.h
new file mode 100644
index 0000000..5699389
--- /dev/null
+++ b/boot/project.h
@@ -0,0 +1,29 @@
+#include <string.h>
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/flash.h>
+#include <libopencm3/stm32/otg_common.h>
+#include <libopencm3/stm32/otg_fs.h>
+#include <libopencm3/stm32/pwr.h>
+#include <libopencm3/stm32/syscfg.h>
+#include <libopencm3/stm32/usart.h>
+
+
+#include <libopencm3/cm3/systick.h>
+#include <libopencm3/cm3/scb.h>
+#include <libopencm3/cm3/cortex.h>
+
+#include <libopencm3/usb/usbd.h>
+#include <libopencm3/usb/dfu.h>
+
+#include "pins.h"
+
+#include <id.h>
+
+
+
+#include "prototypes.h"
+extern uint32_t dfu_flag;
+
+
+#define APP_ADDRESS 0x08004000
diff --git a/boot/prototypes.h b/boot/prototypes.h
new file mode 100644
index 0000000..17cc0fa
--- /dev/null
+++ b/boot/prototypes.h
@@ -0,0 +1,27 @@
+/* bootloader.c */
+extern int main(void);
+/* usb.c */
+extern uint8_t usbd_control_buffer[1024];
+extern const struct usb_device_descriptor dev;
+extern const struct usb_interface ifaces[];
+extern const struct usb_config_descriptor config;
+extern void usb_set_config(usbd_device *usbd_dev, uint16_t wValue);
+extern void usb(void);
+/* dfu.c */
+extern const struct usb_dfu_descriptor dfu_function;
+extern const struct usb_interface_descriptor dfu_iface;
+extern int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, int (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req));
+/* delay.c */
+extern void sys_tick_handler(void);
+extern void ticker_on(void);
+extern void ticker_off(void);
+extern void delay_ms(uint32_t d);
+/* usart.c */
+extern void usart2_xmit_chr(char d);
+extern void usart2_xmit_str(const char *s);
+extern void usart2_xmit_nl(void);
+extern void usart2_xmit_xdigit(unsigned d);
+extern void usart2_xmit_uint32(uint32_t v);
+extern void usart_init(void);
+/* max7219.c */
+extern void max7219_init(void);
diff --git a/boot/usart.c b/boot/usart.c
new file mode 100644
index 0000000..c602710
--- /dev/null
+++ b/boot/usart.c
@@ -0,0 +1,68 @@
+#include "project.h"
+
+
+#define TX2 GPIO5
+#define TX2_PORT GPIOD
+
+#define RX2 GPIO6
+#define RX2_PORT GPIOD
+
+
+void
+usart2_xmit_chr (char d)
+{
+ usart_send_blocking (USART2, d);
+}
+
+
+void
+usart2_xmit_str (const char *s)
+{
+ while (*s)
+ usart_send_blocking (USART2, * (s++));
+}
+
+
+void usart2_xmit_nl (void)
+{
+ usart2_xmit_str ("\r\n");
+}
+
+void usart2_xmit_xdigit (unsigned d)
+{
+ if (d < 0xa) usart2_xmit_chr ('0' + d);
+ else usart2_xmit_chr ('a' + (d - 0xa));
+}
+
+void usart2_xmit_uint32 (uint32_t v)
+{
+ unsigned i;
+
+ for (i = 0; i < 8; ++i) {
+ usart2_xmit_xdigit (v >> 28);
+ v <<= 4;
+ }
+}
+
+
+void
+usart_init (void)
+{
+ rcc_periph_clock_enable (RCC_GPIOD);
+ rcc_periph_clock_enable (RCC_USART2);
+
+
+ MAP_INPUT (RX2);
+ MAP_AF (TX2, GPIO_AF7);
+ MAP_AF_PU (RX2, GPIO_AF7);
+
+
+ usart_set_baudrate (USART2, 38400);
+ 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);
+
+ usart_enable (USART2);
+}
diff --git a/boot/usb.c b/boot/usb.c
new file mode 100644
index 0000000..e8d2e20
--- /dev/null
+++ b/boot/usb.c
@@ -0,0 +1,94 @@
+#include "project.h"
+
+#define USB_DM GPIO11
+#define USB_DM_PORT GPIOA
+#define USB_DP GPIO12
+#define USB_DP_PORT GPIOA
+
+uint8_t usbd_control_buffer[1024];
+
+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_interface ifaces[] = {{
+ .num_altsetting = 1,
+ .altsetting = &dfu_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[] = {
+ VENDOR_NAME,
+ PRODUCT_NAME " (dfu mode)",
+ SERIAL_NUMBER,
+ /* This string is used by ST Microelectronics' DfuSe utility. */
+ "@Internal Flash /0x08000000/04*016Kg,01*064Kg,07*128Kg",
+};
+
+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);
+
+}
+
+
+void usb (void)
+{
+ usbd_device *usbd_dev;
+
+
+ rcc_periph_clock_enable (RCC_GPIOA);
+ rcc_periph_clock_enable (RCC_OTGFS);
+
+ MAP_AF_100 (USB_DP, GPIO_AF10);
+ MAP_AF_100 (USB_DM, GPIO_AF10);
+
+
+ usbd_dev = usbd_init (&otgfs_usb_driver, &dev, &config, usb_strings, 4, usbd_control_buffer, sizeof (usbd_control_buffer));
+
+ OTG_FS_GCCFG |= OTG_GCCFG_NOVBUSSENS;
+ OTG_FS_GCCFG &= ~OTG_GCCFG_VBUSASEN;
+ OTG_FS_GCCFG &= ~OTG_GCCFG_VBUSBSEN;
+
+ usbd_register_set_config_callback (usbd_dev, usb_set_config);
+
+
+ while (1)
+ usbd_poll (usbd_dev);
+
+}