aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorUwe Hermann2010-12-29 15:12:23 +0100
committerUwe Hermann2010-12-29 15:12:23 +0100
commit1c6d7cf06a099294df30ccfd8139bad573140dba (patch)
treef25bfa478e3b9afb938e6cd863c8b9ffcb8cb47e
parent66fd5373b4d1f99d2b34b7223c8964e3cb70de9f (diff)
parent586a4740d57ede9cd6cc4dd8f2d478c1244ee691 (diff)
Merge branch 'martinmm'.
-rwxr-xr-xdoo1
-rw-r--r--examples/Makefile10
-rw-r--r--examples/lisa-m/Makefile38
-rw-r--r--examples/lisa-m/usb_dfu/Makefile95
-rw-r--r--examples/lisa-m/usb_dfu/README43
-rw-r--r--examples/lisa-m/usb_dfu/dfu.h81
-rw-r--r--examples/lisa-m/usb_dfu/usbdfu.c298
-rw-r--r--examples/lisa-m/usb_dfu/usbdfu.ld29
-rw-r--r--examples/lisa-m/usb_hid/Makefile99
-rw-r--r--examples/lisa-m/usb_hid/README43
-rw-r--r--examples/lisa-m/usb_hid/hid.h38
-rw-r--r--examples/lisa-m/usb_hid/usbhid.c295
-rw-r--r--examples/lisa-m/usb_hid/usbhid.ld32
-rw-r--r--examples/other/usb_cdcacm/cdcacm.c31
-rw-r--r--examples/other/usb_dfu/usbdfu.c62
-rw-r--r--examples/other/usb_hid/usbhid.c17
-rw-r--r--examples/stm32-h103/Makefile10
-rw-r--r--examples/stm32-h103/usb_cdcacm/cdcacm.c31
-rw-r--r--examples/stm32-h103/usb_dfu/Makefile95
-rw-r--r--examples/stm32-h103/usb_dfu/README43
-rw-r--r--examples/stm32-h103/usb_dfu/dfu.h81
-rw-r--r--examples/stm32-h103/usb_dfu/usbdfu.c298
-rw-r--r--examples/stm32-h103/usb_dfu/usbdfu.ld29
-rw-r--r--examples/stm32-h103/usb_hid/Makefile98
-rw-r--r--examples/stm32-h103/usb_hid/README43
-rw-r--r--examples/stm32-h103/usb_hid/hid.h38
-rw-r--r--examples/stm32-h103/usb_hid/usbhid.c276
-rw-r--r--examples/stm32-h103/usb_hid/usbhid.ld32
-rw-r--r--examples/stm32-h103/usb_iap/Makefile98
-rw-r--r--examples/stm32-h103/usb_iap/README42
-rw-r--r--examples/stm32-h103/usb_iap/usbiap.c298
-rw-r--r--examples/stm32-h103/usb_iap/usbiap.ld32
-rw-r--r--include/usbd.h15
-rw-r--r--lib/usb/usb_control.c120
-rw-r--r--lib/usb/usb_private.h15
35 files changed, 2724 insertions, 182 deletions
diff --git a/doo b/doo
new file mode 100755
index 0000000..ba3e768
--- /dev/null
+++ b/doo
@@ -0,0 +1 @@
+PREFIX=/opt/paparazzi/stm32/bin/arm-none-eabi make
diff --git a/examples/Makefile b/examples/Makefile
index 8e3cd60..30e2505 100644
--- a/examples/Makefile
+++ b/examples/Makefile
@@ -24,7 +24,7 @@ Q := @
MAKEFLAGS += --no-print-directory
endif
-all: stm32-h103 mb525 obldc other
+all: stm32-h103 mb525 lisa-m obldc other
stm32-h103:
@printf " BUILD examples/stm32-h103\n"
@@ -34,6 +34,10 @@ mb525:
@printf " BUILD examples/mb525\n"
$(Q)$(MAKE) -C mb525
+lisa-m:
+ @printf " BUILD examples/lisa-m\n"
+ $(Q)$(MAKE) -C lisa-m
+
other:
@printf " BUILD examples/other\n"
$(Q)$(MAKE) -C other
@@ -47,10 +51,12 @@ clean:
$(Q)$(MAKE) -C stm32-h103 clean
@printf " CLEAN examples/mb525\n"
$(Q)$(MAKE) -C mb525 clean
+ @printf " CLEAN examples/lisa-m\n"
+ $(Q)$(MAKE) -C lisa-m clean
@printf " CLEAN examples/other\n"
$(Q)$(MAKE) -C other clean
@printf " CLEAN examples/obldc\n"
$(Q)$(MAKE) -C obldc clean
-.PHONY: stm32-h103 mb525 other obldc clean
+.PHONY: stm32-h103 mb525 lisa-m other obldc clean
diff --git a/examples/lisa-m/Makefile b/examples/lisa-m/Makefile
new file mode 100644
index 0000000..c92f799
--- /dev/null
+++ b/examples/lisa-m/Makefile
@@ -0,0 +1,38 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## This program is free software: you can redistribute it and/or modify
+## it under the terms of the GNU General Public License as published by
+## the Free Software Foundation, either version 3 of the License, or
+## (at your option) any later version.
+##
+## This program is distributed in the hope that it will be useful,
+## but WITHOUT ANY WARRANTY; without even the implied warranty of
+## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+## GNU General Public License for more details.
+##
+## You should have received a copy of the GNU General Public License
+## along with this program. If not, see <http://www.gnu.org/licenses/>.
+##
+
+# Be silent per default, but 'make V=1' will show all compiler calls.
+ifneq ($(V),1)
+Q := @
+# Do not print "Entering directory ...".
+MAKEFLAGS += --no-print-directory
+endif
+
+all: usb_hid
+
+usb_hid:
+ @printf " BUILD examples/stm32-h103/usb_hid\n"
+ $(Q)$(MAKE) -C usb_hid
+
+clean:
+ @printf " CLEAN examples/stm32-h103/usb_hid\n"
+ $(Q)$(MAKE) -C usb_hid clean
+
+.PHONY: usb_hid clean
+
diff --git a/examples/lisa-m/usb_dfu/Makefile b/examples/lisa-m/usb_dfu/Makefile
new file mode 100644
index 0000000..775a991
--- /dev/null
+++ b/examples/lisa-m/usb_dfu/Makefile
@@ -0,0 +1,95 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## This program is free software: you can redistribute it and/or modify
+## it under the terms of the GNU General Public License as published by
+## the Free Software Foundation, either version 3 of the License, or
+## (at your option) any later version.
+##
+## This program is distributed in the hope that it will be useful,
+## but WITHOUT ANY WARRANTY; without even the implied warranty of
+## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+## GNU General Public License for more details.
+##
+## You should have received a copy of the GNU General Public License
+## along with this program. If not, see <http://www.gnu.org/licenses/>.
+##
+
+BINARY = usbdfu
+
+# PREFIX ?= arm-none-eabi
+PREFIX ?= arm-elf
+CC = $(PREFIX)-gcc
+LD = $(PREFIX)-gcc
+OBJCOPY = $(PREFIX)-objcopy
+OBJDUMP = $(PREFIX)-objdump
+# Uncomment this line if you want to use the installed (not local) library.
+#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
+TOOLCHAIN_DIR = ../../..
+CFLAGS = -O0 -g3 -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
+ -mcpu=cortex-m3 -mthumb
+LDSCRIPT = $(BINARY).ld
+LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles -Wl,--defsym,_stack=0x20001000
+OBJS = $(BINARY).o
+
+OPENOCD_BASE = /usr
+OPENOCD = $(OPENOCD_BASE)/bin/openocd
+OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
+OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
+OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
+
+# Be silent per default, but 'make V=1' will show all compiler calls.
+ifneq ($(V),1)
+Q := @
+NULL := 2>/dev/null
+endif
+
+all: images
+
+images: $(BINARY)
+ @printf " OBJCOPY $(BINARY).bin\n"
+ $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
+ @printf " OBJCOPY $(BINARY).hex\n"
+ $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
+ @printf " OBJCOPY $(BINARY).srec\n"
+ $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
+ @printf " OBJDUMP $(BINARY).list\n"
+ $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
+
+$(BINARY): $(OBJS) $(LDSCRIPT)
+ @printf " LD $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
+
+%.o: %.c Makefile
+ @printf " CC $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(CC) $(CFLAGS) -o $@ -c $<
+
+clean:
+ @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
+ $(Q)rm -f *.o
+ @printf " CLEAN $(BINARY)\n"
+ $(Q)rm -f $(BINARY)
+ @printf " CLEAN $(BINARY).bin\n"
+ $(Q)rm -f $(BINARY).bin
+ @printf " CLEAN $(BINARY).hex\n"
+ $(Q)rm -f $(BINARY).hex
+ @printf " CLEAN $(BINARY).srec\n"
+ $(Q)rm -f $(BINARY).srec
+ @printf " CLEAN $(BINARY).list\n"
+ $(Q)rm -f $(BINARY).list
+
+flash: images
+ @printf " FLASH $(BINARY).bin\n"
+ @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
+ $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
+ -f $(OPENOCD_FLASHER) \
+ -f $(OPENOCD_BOARD) \
+ -c "init" -c "reset halt" \
+ -c "flash write_image erase $(BINARY).hex" \
+ -c "reset" \
+ -c "shutdown" $(NULL)
+
+.PHONY: images clean
+
diff --git a/examples/lisa-m/usb_dfu/README b/examples/lisa-m/usb_dfu/README
new file mode 100644
index 0000000..7146618
--- /dev/null
+++ b/examples/lisa-m/usb_dfu/README
@@ -0,0 +1,43 @@
+------------------------------------------------------------------------------
+README
+------------------------------------------------------------------------------
+
+This example implements a USB Device Firmware Upgrade (DFU) bootloader
+to demonstrate the use of the USB device stack.
+
+Building
+--------
+
+ $ make
+
+Running 'make' on the top-level libopenstm32 directory will automatically
+also build this example. Or you can build the library "manually" and
+then run 'make' in this directory.
+
+You may want to override the toolchain (e.g., arm-elf or arm-none-eabi):
+
+ $ PREFIX=arm-none-eabi make
+
+For a more verbose build you can use
+
+ $ make V=1
+
+
+Flashing
+--------
+
+You can flash the generated code using OpenOCD:
+
+ $ make flash
+
+Or you can do the same manually via:
+
+ $ openocd -f interface/jtagkey-tiny.cfg -f target/stm32.cfg
+ $ telnet localhost 4444
+ > reset halt
+ > flash write_image erase systick.hex
+ > reset
+
+Replace the "jtagkey-tiny.cfg" with whatever JTAG device you are using, and/or
+replace "stm.cfg" with your respective config file.
+
diff --git a/examples/lisa-m/usb_dfu/dfu.h b/examples/lisa-m/usb_dfu/dfu.h
new file mode 100644
index 0000000..e4e4b23
--- /dev/null
+++ b/examples/lisa-m/usb_dfu/dfu.h
@@ -0,0 +1,81 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#ifndef __DFU_H
+#define __DFU_H
+
+enum dfu_req {
+ DFU_DETACH,
+ DFU_DNLOAD,
+ DFU_UPLOAD,
+ DFU_GETSTATUS,
+ DFU_CLRSTATUS,
+ DFU_GETSTATE,
+ DFU_ABORT
+};
+
+enum dfu_status {
+ DFU_STATUS_OK,
+ DFU_STATUS_ERR_TARGET,
+ DFU_STATUS_ERR_FILE,
+ DFU_STATUS_ERR_WRITE,
+ DFU_STATUS_ERR_ERASE,
+ DFU_STATUS_ERR_CHECK_ERASED,
+ DFU_STATUS_ERR_PROG,
+ DFU_STATUS_ERR_VERIFY,
+ DFU_STATUS_ERR_ADDRESS,
+ DFU_STATUS_ERR_NOTDONE,
+ DFU_STATUS_ERR_FIRMWARE,
+ DFU_STATUS_ERR_VENDOR,
+ DFU_STATUS_ERR_USBR,
+ DFU_STATUS_ERR_POR,
+ DFU_STATUS_ERR_UNKNOWN,
+ DFU_STATUS_ERR_STALLEDPKT,
+};
+
+enum dfu_state {
+ STATE_APP_IDLE,
+ STATE_APP_DETACH,
+ STATE_DFU_IDLE,
+ STATE_DFU_DNLOAD_SYNC,
+ STATE_DFU_DNBUSY,
+ STATE_DFU_DNLOAD_IDLE,
+ STATE_DFU_MANIFEST_SYNC,
+ STATE_DFU_MANIFEST,
+ STATE_DFU_MANIFEST_WAIT_RESET,
+ STATE_DFU_UPLOAD_IDLE,
+ STATE_DFU_ERROR,
+};
+
+#define DFU_FUNCTIONAL 0x21
+struct usb_dfu_descriptor {
+ uint8_t bLength;
+ uint8_t bDescriptorType;
+ uint8_t bmAttributes;
+#define USB_DFU_CAN_DOWNLOAD 0x01
+#define USB_DFU_CAN_UPLOAD 0x02
+#define USB_DFU_MANIFEST_TOLERANT 0x04
+#define USB_DFU_WILL_DETACH 0x08
+
+ uint16_t wDetachTimeout;
+ uint16_t wTransferSize;
+ uint16_t bcdDFUVersion;
+} __attribute__((packed));
+
+#endif
diff --git a/examples/lisa-m/usb_dfu/usbdfu.c b/examples/lisa-m/usb_dfu/usbdfu.c
new file mode 100644
index 0000000..9e72318
--- /dev/null
+++ b/examples/lisa-m/usb_dfu/usbdfu.c
@@ -0,0 +1,298 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopenstm32/rcc.h>
+#include <libopenstm32/gpio.h>
+#include <libopenstm32/flash.h>
+#include <libopenstm32/scb.h>
+#include <usbd.h>
+
+#include <string.h>
+
+#include "dfu.h"
+
+#define APP_ADDRESS 0x08002000
+
+/* 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: */
+u8 usbd_control_buffer[1024];
+
+static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
+
+static struct {
+ u8 buf[sizeof(usbd_control_buffer)];
+ u16 len;
+ u32 addr;
+ u16 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 = 0x0483,
+ .idProduct = 0xDF11,
+ .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 | USB_DFU_WILL_DETACH,
+ .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[] = {
+ "x",
+ "Black Sphere Technologies",
+ "DFU Demo",
+ "DEMO",
+ /* This string is used by ST Microelectronics' DfuSe utility */
+ "@Internal Flash /0x08000000/8*001Ka,56*001Kg"
+};
+
+static u8 usbdfu_getstatus(u32 *bwPollTimeout)
+{
+ 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(struct usb_setup_data *req)
+{
+ int i;
+ (void)req;
+
+ switch(usbdfu_state) {
+ case STATE_DFU_DNBUSY:
+
+ flash_unlock();
+ if(prog.blocknum == 0) {
+ switch(prog.buf[0]) {
+ case CMD_ERASE:
+ flash_erase_page(*(u32*)(prog.buf+1));
+ case CMD_SETADDR:
+ prog.addr = *(u32*)(prog.buf+1);
+ }
+ } else {
+ u32 baseaddr = prog.addr +
+ ((prog.blocknum - 2) *
+ dfu_function.wTransferSize);
+ for(i = 0; i < prog.len; i += 2)
+ flash_program_half_word(baseaddr + i,
+ *(u16*)(prog.buf+i));
+ }
+ flash_lock();
+
+ /* We 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_command(struct usb_setup_data *req,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)complete;
+
+ if(req->bmRequestType != 0x21)
+ return 0; /* Only accept class request */
+
+ switch(req->bRequest) {
+ case DFU_DNLOAD:
+ usbdfu_state = STATE_DFU_MANIFEST_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;
+ }
+
+ return 0;
+}
+
+static int usbdfu_control_read(struct usb_setup_data *req, u8 **buf, u16 *len,
+ void (**complete)(struct usb_setup_data *req))
+{
+
+ if(req->bmRequestType != 0xA1)
+ return 0; /* Only accept class request */
+
+ switch(req->bRequest) {
+ case DFU_UPLOAD:
+ /* Upload not supported for now */
+ return 0;
+ case DFU_GETSTATUS: {
+ u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
+
+ (*buf)[0] = usbdfu_getstatus(&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;
+}
+
+static int usbdfu_control_write(struct usb_setup_data *req, u8 *buf, u16 len,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)complete;
+
+ if(req->bmRequestType != 0x21)
+ return 0; /* Only accept class request */
+
+ if(req->bRequest != DFU_DNLOAD)
+ return 0;
+
+ /* 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;
+}
+
+int main(void)
+{
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ if(!gpio_get(GPIOA, GPIO10)) {
+ /* Boot the application if it's valid */
+ if((*(volatile u32*)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 u32*)APP_ADDRESS));
+ /* Jump to application */
+ (*(void(**)())(APP_ADDRESS + 4))();
+ }
+ }
+
+ rcc_clock_setup_in_hsi_out_48mhz();
+
+ rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
+
+ AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_ON;
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO15);
+
+ usbd_init(&dev, &config, usb_strings);
+ usbd_set_control_buffer_size(sizeof(usbd_control_buffer));
+ usbd_register_control_command_callback(usbdfu_control_command);
+ usbd_register_control_write_callback(usbdfu_control_write);
+ usbd_register_control_read_callback(usbdfu_control_read);
+
+ gpio_set(GPIOA, GPIO15);
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
+
+ while (1)
+ usbd_poll();
+}
+
diff --git a/examples/lisa-m/usb_dfu/usbdfu.ld b/examples/lisa-m/usb_dfu/usbdfu.ld
new file mode 100644
index 0000000..d7cd0c5
--- /dev/null
+++ b/examples/lisa-m/usb_dfu/usbdfu.ld
@@ -0,0 +1,29 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH =8K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K
+}
+
+/* Include the common ld script from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/examples/lisa-m/usb_hid/Makefile b/examples/lisa-m/usb_hid/Makefile
new file mode 100644
index 0000000..10f3d65
--- /dev/null
+++ b/examples/lisa-m/usb_hid/Makefile
@@ -0,0 +1,99 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## This program is free software: you can redistribute it and/or modify
+## it under the terms of the GNU General Public License as published by
+## the Free Software Foundation, either version 3 of the License, or
+## (at your option) any later version.
+##
+## This program is distributed in the hope that it will be useful,
+## but WITHOUT ANY WARRANTY; without even the implied warranty of
+## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+## GNU General Public License for more details.
+##
+## You should have received a copy of the GNU General Public License
+## along with this program. If not, see <http://www.gnu.org/licenses/>.
+##
+
+BINARY = usbhid
+
+PREFIX=/opt/paparazzi/stm32/bin/arm-none-eabi
+# PREFIX ?= arm-none-eabi
+#PREFIX ?= arm-elf
+CC = $(PREFIX)-gcc
+LD = $(PREFIX)-gcc
+OBJCOPY = $(PREFIX)-objcopy
+OBJDUMP = $(PREFIX)-objdump
+# Uncomment this line if you want to use the installed (not local) library.
+#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
+TOOLCHAIN_DIR = ../../..
+CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
+ -mcpu=cortex-m3 -mthumb
+LDSCRIPT = $(BINARY).ld
+LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
+OBJS = $(BINARY).o
+
+#OPENOCD_BASE = /usr
+OPENOCD_BASE = /opt/paparazzi/stm32
+OPENOCD = $(OPENOCD_BASE)/bin/openocd
+OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
+#OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/openocd-usb.cfg
+OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey-tiny.cfg
+#OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/paparazzi_lisa_m.cfg
+OPENOCD_BOARD = /opt/paparazzi/stm32/share/openocd/scripts/board/lisa-l.cfg
+
+# Be silent per default, but 'make V=1' will show all compiler calls.
+ifneq ($(V),1)
+Q := @
+NULL := 2>/dev/null
+endif
+
+all: images
+
+images: $(BINARY)
+ @printf " OBJCOPY $(BINARY).bin\n"
+ $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
+ @printf " OBJCOPY $(BINARY).hex\n"
+ $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
+ @printf " OBJCOPY $(BINARY).srec\n"
+ $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
+ @printf " OBJDUMP $(BINARY).list\n"
+ $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
+
+$(BINARY): $(OBJS) $(LDSCRIPT)
+ @printf " LD $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
+
+%.o: %.c Makefile
+ @printf " CC $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(CC) $(CFLAGS) -o $@ -c $<
+
+clean:
+ @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
+ $(Q)rm -f *.o
+ @printf " CLEAN $(BINARY)\n"
+ $(Q)rm -f $(BINARY)
+ @printf " CLEAN $(BINARY).bin\n"
+ $(Q)rm -f $(BINARY).bin
+ @printf " CLEAN $(BINARY).hex\n"
+ $(Q)rm -f $(BINARY).hex
+ @printf " CLEAN $(BINARY).srec\n"
+ $(Q)rm -f $(BINARY).srec
+ @printf " CLEAN $(BINARY).list\n"
+ $(Q)rm -f $(BINARY).list
+
+flash: images
+ @printf " FLASH $(BINARY).bin\n"
+ @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
+ $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
+ -f $(OPENOCD_FLASHER) \
+ -f $(OPENOCD_BOARD) \
+ -c "init" -c "reset halt" \
+ -c "flash write_image erase $(BINARY).hex" \
+ -c "reset" \
+ -c "shutdown" $(NULL)
+
+.PHONY: images clean
+
diff --git a/examples/lisa-m/usb_hid/README b/examples/lisa-m/usb_hid/README
new file mode 100644
index 0000000..3ba2aa6
--- /dev/null
+++ b/examples/lisa-m/usb_hid/README
@@ -0,0 +1,43 @@
+------------------------------------------------------------------------------
+README
+------------------------------------------------------------------------------
+
+This example implements a USB Human Interface Device (HID)
+to demonstrate the use of the USB device stack.
+
+Building
+--------
+
+ $ make
+
+Running 'make' on the top-level libopenstm32 directory will automatically
+also build this example. Or you can build the library "manually" and
+then run 'make' in this directory.
+
+You may want to override the toolchain (e.g., arm-elf or arm-none-eabi):
+
+ $ PREFIX=arm-none-eabi make
+
+For a more verbose build you can use
+
+ $ make V=1
+
+
+Flashing
+--------
+
+You can flash the generated code using OpenOCD:
+
+ $ make flash
+
+Or you can do the same manually via:
+
+ $ openocd -f interface/jtagkey-tiny.cfg -f target/stm32.cfg
+ $ telnet localhost 4444
+ > reset halt
+ > flash write_image erase systick.hex
+ > reset
+
+Replace the "jtagkey-tiny.cfg" with whatever JTAG device you are using, and/or
+replace "stm.cfg" with your respective config file.
+
diff --git a/examples/lisa-m/usb_hid/hid.h b/examples/lisa-m/usb_hid/hid.h
new file mode 100644
index 0000000..4690103
--- /dev/null
+++ b/examples/lisa-m/usb_hid/hid.h
@@ -0,0 +1,38 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+#ifndef __HID_H
+#define __HID_H
+
+#include <stdint.h>
+
+#define USB_CLASS_HID 3
+
+#define USB_DT_HID 0x21
+#define USB_DT_REPORT 0x22
+
+struct usb_hid_descriptor {
+ uint8_t bLength;
+ uint8_t bDescriptorType;
+ uint16_t bcdHID;
+ uint8_t bCountryCode;
+ uint8_t bNumDescriptors;
+} __attribute__((packed));
+
+#endif
+
diff --git a/examples/lisa-m/usb_hid/usbhid.c b/examples/lisa-m/usb_hid/usbhid.c
new file mode 100644
index 0000000..f8981af
--- /dev/null
+++ b/examples/lisa-m/usb_hid/usbhid.c
@@ -0,0 +1,295 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopenstm32/rcc.h>
+#include <libopenstm32/gpio.h>
+#include <libopenstm32/systick.h>
+#include <usbd.h>
+
+#include <stdlib.h>
+
+#include "hid.h"
+
+/* Define this to include the DFU APP interface. */
+#define INCLUDE_DFU_INTERFACE
+
+#ifdef INCLUDE_DFU_INTERFACE
+# include <libopenstm32/scb.h>
+# include "../usb_dfu/dfu.h"
+#endif
+
+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 = 0x0483,
+ .idProduct = 0x5710,
+ .bcdDevice = 0x0200,
+ .iManufacturer = 1,
+ .iProduct = 2,
+ .iSerialNumber = 3,
+ .bNumConfigurations = 1,
+};
+
+/* I have no idea what this means. I haven't read the HID spec. */
+static const u8 hid_report_descriptor[] = {
+ 0x05, 0x01, 0x09, 0x02, 0xA1, 0x01, 0x09, 0x01,
+ 0xA1, 0x00, 0x05, 0x09, 0x19, 0x01, 0x29, 0x03,
+ 0x15, 0x00, 0x25, 0x01, 0x95, 0x03, 0x75, 0x01,
+ 0x81, 0x02, 0x95, 0x01, 0x75, 0x05, 0x81, 0x01,
+ 0x05, 0x01, 0x09, 0x30, 0x09, 0x31, 0x09, 0x38,
+ 0x15, 0x81, 0x25, 0x7F, 0x75, 0x08, 0x95, 0x03,
+ 0x81, 0x06, 0xC0, 0x09, 0x3c, 0x05, 0xff, 0x09,
+ 0x01, 0x15, 0x00, 0x25, 0x01, 0x75, 0x01, 0x95,
+ 0x02, 0xb1, 0x22, 0x75, 0x06, 0x95, 0x01, 0xb1,
+ 0x01, 0xc0
+};
+
+static const struct {
+ struct usb_hid_descriptor hid_descriptor;
+ struct {
+ uint8_t bReportDescriptorType;
+ uint16_t wDescriptorLength;
+ } __attribute__((packed)) hid_report;
+} __attribute__((packed)) hid_function = {
+ .hid_descriptor = {
+ .bLength = sizeof(hid_function),
+ .bDescriptorType = USB_DT_HID,
+ .bcdHID = 0x0100,
+ .bCountryCode = 0,
+ .bNumDescriptors = 1,
+ },
+ .hid_report = {
+ .bReportDescriptorType = USB_DT_REPORT,
+ .wDescriptorLength = sizeof(hid_report_descriptor),
+ }
+};
+
+const struct usb_endpoint_descriptor hid_endpoint = {
+ .bLength = USB_DT_ENDPOINT_SIZE,
+ .bDescriptorType = USB_DT_ENDPOINT,
+ .bEndpointAddress = 0x81,
+ .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
+ .wMaxPacketSize = 4,
+ .bInterval = 0x20,
+};
+
+const struct usb_interface_descriptor hid_iface = {
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 0,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 1,
+ .bInterfaceClass = USB_CLASS_HID,
+ .bInterfaceSubClass = 1, /* boot */
+ .bInterfaceProtocol = 2, /* mouse */
+ .iInterface = 0,
+
+ .endpoint = &hid_endpoint,
+
+ .extra = &hid_function,
+ .extralen = sizeof(hid_function),
+};
+
+#ifdef INCLUDE_DFU_INTERFACE
+const struct usb_dfu_descriptor dfu_function = {
+ .bLength = sizeof(struct usb_dfu_descriptor),
+ .bDescriptorType = DFU_FUNCTIONAL,
+ .bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_WILL_DETACH,
+ .wDetachTimeout = 255,
+ .wTransferSize = 1024,
+ .bcdDFUVersion = 0x011A,
+};
+
+const struct usb_interface_descriptor dfu_iface = {
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 1,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 0,
+ .bInterfaceClass = 0xFE,
+ .bInterfaceSubClass = 1,
+ .bInterfaceProtocol = 1,
+ .iInterface = 0,
+
+ .extra = &dfu_function,
+ .extralen = sizeof(dfu_function),
+};
+#endif
+
+const struct usb_interface ifaces[] = {{
+ .num_altsetting = 1,
+ .altsetting = &hid_iface,
+#ifdef INCLUDE_DFU_INTERFACE
+}, {
+ .num_altsetting = 1,
+ .altsetting = &dfu_iface,
+#endif
+}};
+
+const struct usb_config_descriptor config = {
+ .bLength = USB_DT_CONFIGURATION_SIZE,
+ .bDescriptorType = USB_DT_CONFIGURATION,
+ .wTotalLength = 0,
+#ifdef INCLUDE_DFU_INTERFACE
+ .bNumInterfaces = 2,
+#else
+ .bNumInterfaces = 1,
+#endif
+ .bConfigurationValue = 1,
+ .iConfiguration = 0,
+ .bmAttributes = 0xC0,
+ .bMaxPower = 0x32,
+
+ .interface = ifaces,
+};
+
+static const char *usb_strings[] = {
+ "x",
+ "Black Sphere Technologies",
+ "HID Demo",
+ "DEMO",
+};
+
+static int hid_control_request(struct usb_setup_data *req, u8 **buf, u16 *len,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)complete;
+
+ if((req->bmRequestType != 0x81) ||
+ (req->bRequest != USB_REQ_GET_DESCRIPTOR) ||
+ (req->wValue != 0x2200))
+ return 0;
+
+ /* Handle the HID report descriptor */
+ *buf = (u8*)hid_report_descriptor;
+ *len = sizeof(hid_report_descriptor);
+
+ return 1;
+}
+
+#ifdef INCLUDE_DFU_INTERFACE
+static void dfu_detach_complete(struct usb_setup_data *req)
+{
+ (void)req;
+
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO15);
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO10);
+ gpio_set(GPIOA, GPIO10);
+ scb_reset_core();
+}
+
+static int dfu_control_request(struct usb_setup_data *req, u8 **buf, u16 *len,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)buf;
+ (void)len;
+
+ if((req->bmRequestType != 0x21) || (req->bRequest != DFU_DETACH))
+ return 0; /* Only accept class request */
+
+ *complete = dfu_detach_complete;
+
+ return 1;
+}
+#endif
+
+static void hid_set_config(u16 wValue)
+{
+ (void)wValue;
+
+ usbd_ep_setup(0x81, USB_ENDPOINT_ATTR_INTERRUPT, 4, NULL);
+
+ usbd_register_control_callback(
+ USB_REQ_TYPE_STANDARD | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ hid_control_request);
+#ifdef INCLUDE_DFU_INTERFACE
+ usbd_register_control_callback(
+ USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ dfu_control_request);
+#endif
+
+ systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
+ systick_set_reload(100000);
+ systick_interrupt_enable();
+ systick_counter_enable();
+}
+
+int main(void)
+{
+ rcc_clock_setup_in_hsi_out_48mhz();
+
+
+ rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
+
+ /* USB_DETECT as input */
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_FLOAT, GPIO8);
+
+ /* disconnect USB_DISC, as output */
+ gpio_set(GPIOC, GPIO15);
+ gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
+
+ /* green LED off, as output */
+ gpio_clear(GPIOC, GPIO13);
+ gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO13);
+
+
+ usbd_init(&dev, &config, usb_strings);
+ usbd_register_set_config_callback(hid_set_config);
+
+ /* delay some seconds to show that pull-up switch works */
+ {int i; for (i=0;i<0x800000;i++);}
+
+ /* wait for USB Vbus */
+ while(gpio_get(GPIOA, GPIO8) == 0);
+
+ /* green LED on, connect USB */
+ gpio_set(GPIOC, GPIO13);
+ gpio_clear(GPIOC, GPIO15);
+
+ while (1)
+ usbd_poll();
+}
+
+void sys_tick_handler(void)
+{
+ static int x = 0;
+ static int dir = 1;
+ uint8_t buf[4] = {0, 0, 0, 0};
+
+ buf[1] = dir;
+ x += dir;
+ if(x > 30) dir = -dir;
+ if(x < -30) dir = -dir;
+
+ usbd_ep_write_packet(0x81, buf, 4);
+}
+
diff --git a/examples/lisa-m/usb_hid/usbhid.ld b/examples/lisa-m/usb_hid/usbhid.ld
new file mode 100644
index 0000000..a393e0b
--- /dev/null
+++ b/examples/lisa-m/usb_hid/usbhid.ld
@@ -0,0 +1,32 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* 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 from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/examples/other/usb_cdcacm/cdcacm.c b/examples/other/usb_cdcacm/cdcacm.c
index ae4ad1c..3d37db2 100644
--- a/examples/other/usb_cdcacm/cdcacm.c
+++ b/examples/other/usb_cdcacm/cdcacm.c
@@ -163,18 +163,19 @@ static const char *usb_strings[] = {
"DEMO"
};
-static int cdcacm_control_command(struct usb_setup_data *req,
- void (**complete)(struct usb_setup_data *req))
+static int cdcacm_control_request(struct usb_setup_data *req, u8 **buf,
+ u16 *len, void (**complete)(struct usb_setup_data *req))
{
(void)complete;
- char buf[10];
- struct usb_cdc_notification *notif = (void*)buf;
+ (void)buf;
switch(req->bRequest) {
- case USB_CDC_REQ_SET_CONTROL_LINE_STATE:
+ 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 buf[10];
+ struct usb_cdc_notification *notif = (void*)buf;
/* We echo signals back to host as notification */
notif->bmRequestType = 0xA1;
@@ -186,19 +187,9 @@ static int cdcacm_control_command(struct usb_setup_data *req,
buf[9] = 0;
//usbd_ep_write_packet(0x83, buf, 10);
return 1;
- }
- return 0;
-}
-
-static int cdcacm_control_write(struct usb_setup_data *req, u8 *buf, u16 len,
- void (**complete)(struct usb_setup_data *req))
-{
- (void)complete;
- (void)buf;
-
- switch(req->bRequest) {
+ }
case USB_CDC_REQ_SET_LINE_CODING:
- if(len < sizeof(struct usb_cdc_line_coding))
+ if(*len < sizeof(struct usb_cdc_line_coding))
return 0;
return 1;
@@ -226,8 +217,10 @@ static void cdcacm_set_config(u16 wValue)
usbd_ep_setup(0x82, USB_ENDPOINT_ATTR_BULK, 64, NULL);
usbd_ep_setup(0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
- usbd_register_control_command_callback(cdcacm_control_command);
- usbd_register_control_write_callback(cdcacm_control_write);
+ usbd_register_control_callback(
+ USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ cdcacm_control_request);
}
int main(void)
diff --git a/examples/other/usb_dfu/usbdfu.c b/examples/other/usb_dfu/usbdfu.c
index 9e72318..a6d8ce7 100644
--- a/examples/other/usb_dfu/usbdfu.c
+++ b/examples/other/usb_dfu/usbdfu.c
@@ -175,18 +175,26 @@ static void usbdfu_getstatus_complete(struct usb_setup_data *req)
}
}
-static int usbdfu_control_command(struct usb_setup_data *req,
- void (**complete)(struct usb_setup_data *req))
+static int usbdfu_control_request(struct usb_setup_data *req, u8 **buf,
+ u16 *len, void (**complete)(struct usb_setup_data *req))
{
- (void)complete;
- if(req->bmRequestType != 0x21)
+ if((req->bmRequestType & 0x7F) != 0x21)
return 0; /* Only accept class request */
-
+
switch(req->bRequest) {
case DFU_DNLOAD:
- usbdfu_state = STATE_DFU_MANIFEST_SYNC;
- return 1;
+ 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)
@@ -196,19 +204,6 @@ static int usbdfu_control_command(struct usb_setup_data *req,
/* Abort returns to dfuIDLE state */
usbdfu_state = STATE_DFU_IDLE;
return 1;
- }
-
- return 0;
-}
-
-static int usbdfu_control_read(struct usb_setup_data *req, u8 **buf, u16 *len,
- void (**complete)(struct usb_setup_data *req))
-{
-
- if(req->bmRequestType != 0xA1)
- return 0; /* Only accept class request */
-
- switch(req->bRequest) {
case DFU_UPLOAD:
/* Upload not supported for now */
return 0;
@@ -237,26 +232,6 @@ static int usbdfu_control_read(struct usb_setup_data *req, u8 **buf, u16 *len,
return 0;
}
-static int usbdfu_control_write(struct usb_setup_data *req, u8 *buf, u16 len,
- void (**complete)(struct usb_setup_data *req))
-{
- (void)complete;
-
- if(req->bmRequestType != 0x21)
- return 0; /* Only accept class request */
-
- if(req->bRequest != DFU_DNLOAD)
- return 0;
-
- /* 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;
-}
-
int main(void)
{
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
@@ -284,9 +259,10 @@ int main(void)
usbd_init(&dev, &config, usb_strings);
usbd_set_control_buffer_size(sizeof(usbd_control_buffer));
- usbd_register_control_command_callback(usbdfu_control_command);
- usbd_register_control_write_callback(usbdfu_control_write);
- usbd_register_control_read_callback(usbdfu_control_read);
+ usbd_register_control_callback(
+ USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ usbdfu_control_request);
gpio_set(GPIOA, GPIO15);
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
diff --git a/examples/other/usb_hid/usbhid.c b/examples/other/usb_hid/usbhid.c
index 32048a0..6226f32 100644
--- a/examples/other/usb_hid/usbhid.c
+++ b/examples/other/usb_hid/usbhid.c
@@ -171,7 +171,7 @@ static const char *usb_strings[] = {
"DEMO",
};
-static int hid_control_read(struct usb_setup_data *req, u8 **buf, u16 *len,
+static int hid_control_request(struct usb_setup_data *req, u8 **buf, u16 *len,
void (**complete)(struct usb_setup_data *req))
{
(void)complete;
@@ -200,9 +200,12 @@ static void dfu_detach_complete(struct usb_setup_data *req)
scb_reset_core();
}
-static int dfu_control_command(struct usb_setup_data *req,
+static int dfu_control_request(struct usb_setup_data *req, u8 **buf, u16 *len,
void (**complete)(struct usb_setup_data *req))
{
+ (void)buf;
+ (void)len;
+
if((req->bmRequestType != 0x21) || (req->bRequest != DFU_DETACH))
return 0; /* Only accept class request */
@@ -218,9 +221,15 @@ static void hid_set_config(u16 wValue)
usbd_ep_setup(0x81, USB_ENDPOINT_ATTR_INTERRUPT, 4, NULL);
- usbd_register_control_read_callback(hid_control_read);
+ usbd_register_control_callback(
+ USB_REQ_TYPE_STANDARD | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ hid_control_request);
#ifdef INCLUDE_DFU_INTERFACE
- usbd_register_control_command_callback(dfu_control_command);
+ usbd_register_control_callback(
+ USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ dfu_control_request);
#endif
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
diff --git a/examples/stm32-h103/Makefile b/examples/stm32-h103/Makefile
index 3e4098e..bd3a2d8 100644
--- a/examples/stm32-h103/Makefile
+++ b/examples/stm32-h103/Makefile
@@ -24,7 +24,7 @@ Q := @
MAKEFLAGS += --no-print-directory
endif
-all: miniblink fancyblink usart usb_cdcacm
+all: miniblink fancyblink usart usb_cdcacm usb_hid
miniblink:
@printf " BUILD examples/stm32-h103/miniblink\n"
@@ -46,6 +46,10 @@ usb_cdcacm:
@printf " BUILD examples/stm32-h103/usb_cdcacm\n"
$(Q)$(MAKE) -C usb_cdcacm
+usb_hid:
+ @printf " BUILD examples/stm32-h103/usb_hid\n"
+ $(Q)$(MAKE) -C usb_hid
+
clean:
@printf " CLEAN examples/stm32-h103/miniblink\n"
$(Q)$(MAKE) -C miniblink clean
@@ -57,6 +61,8 @@ clean:
$(Q)$(MAKE) -C spi clean
@printf " CLEAN examples/stm32-h103/usb_cdcacm\n"
$(Q)$(MAKE) -C usb_cdcacm clean
+ @printf " CLEAN examples/stm32-h103/usb_hid\n"
+ $(Q)$(MAKE) -C usb_hid clean
-.PHONY: miniblink fancyblink usart spi usb_cdcacm clean
+.PHONY: miniblink fancyblink usart spi usb_cdcacm usb_hid clean
diff --git a/examples/stm32-h103/usb_cdcacm/cdcacm.c b/examples/stm32-h103/usb_cdcacm/cdcacm.c
index f757f63..6029ece 100644
--- a/examples/stm32-h103/usb_cdcacm/cdcacm.c
+++ b/examples/stm32-h103/usb_cdcacm/cdcacm.c
@@ -163,18 +163,19 @@ static const char *usb_strings[] = {
"DEMO"
};
-static int cdcacm_control_command(struct usb_setup_data *req,
- void (**complete)(struct usb_setup_data *req))
+static int cdcacm_control_request(struct usb_setup_data *req, u8 **buf,
+ u16 *len, void (**complete)(struct usb_setup_data *req))
{
(void)complete;
- char buf[10];
- struct usb_cdc_notification *notif = (void*)buf;
+ (void)buf;
switch(req->bRequest) {
- case USB_CDC_REQ_SET_CONTROL_LINE_STATE:
+ 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 buf[10];
+ struct usb_cdc_notification *notif = (void*)buf;
/* We echo signals back to host as notification */
notif->bmRequestType = 0xA1;
@@ -186,19 +187,9 @@ static int cdcacm_control_command(struct usb_setup_data *req,
buf[9] = 0;
//usbd_ep_write_packet(0x83, buf, 10);
return 1;
- }
- return 0;
-}
-
-static int cdcacm_control_write(struct usb_setup_data *req, u8 *buf, u16 len,
- void (**complete)(struct usb_setup_data *req))
-{
- (void)complete;
- (void)buf;
-
- switch(req->bRequest) {
+ }
case USB_CDC_REQ_SET_LINE_CODING:
- if(len < sizeof(struct usb_cdc_line_coding))
+ if(*len < sizeof(struct usb_cdc_line_coding))
return 0;
return 1;
@@ -226,8 +217,10 @@ static void cdcacm_set_config(u16 wValue)
usbd_ep_setup(0x82, USB_ENDPOINT_ATTR_BULK, 64, NULL);
usbd_ep_setup(0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
- usbd_register_control_command_callback(cdcacm_control_command);
- usbd_register_control_write_callback(cdcacm_control_write);
+ usbd_register_control_callback(
+ USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ cdcacm_control_request);
}
int main(void)
diff --git a/examples/stm32-h103/usb_dfu/Makefile b/examples/stm32-h103/usb_dfu/Makefile
new file mode 100644
index 0000000..775a991
--- /dev/null
+++ b/examples/stm32-h103/usb_dfu/Makefile
@@ -0,0 +1,95 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## This program is free software: you can redistribute it and/or modify
+## it under the terms of the GNU General Public License as published by
+## the Free Software Foundation, either version 3 of the License, or
+## (at your option) any later version.
+##
+## This program is distributed in the hope that it will be useful,
+## but WITHOUT ANY WARRANTY; without even the implied warranty of
+## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+## GNU General Public License for more details.
+##
+## You should have received a copy of the GNU General Public License
+## along with this program. If not, see <http://www.gnu.org/licenses/>.
+##
+
+BINARY = usbdfu
+
+# PREFIX ?= arm-none-eabi
+PREFIX ?= arm-elf
+CC = $(PREFIX)-gcc
+LD = $(PREFIX)-gcc
+OBJCOPY = $(PREFIX)-objcopy
+OBJDUMP = $(PREFIX)-objdump
+# Uncomment this line if you want to use the installed (not local) library.
+#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
+TOOLCHAIN_DIR = ../../..
+CFLAGS = -O0 -g3 -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
+ -mcpu=cortex-m3 -mthumb
+LDSCRIPT = $(BINARY).ld
+LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles -Wl,--defsym,_stack=0x20001000
+OBJS = $(BINARY).o
+
+OPENOCD_BASE = /usr
+OPENOCD = $(OPENOCD_BASE)/bin/openocd
+OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
+OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
+OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
+
+# Be silent per default, but 'make V=1' will show all compiler calls.
+ifneq ($(V),1)
+Q := @
+NULL := 2>/dev/null
+endif
+
+all: images
+
+images: $(BINARY)
+ @printf " OBJCOPY $(BINARY).bin\n"
+ $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
+ @printf " OBJCOPY $(BINARY).hex\n"
+ $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
+ @printf " OBJCOPY $(BINARY).srec\n"
+ $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
+ @printf " OBJDUMP $(BINARY).list\n"
+ $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
+
+$(BINARY): $(OBJS) $(LDSCRIPT)
+ @printf " LD $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
+
+%.o: %.c Makefile
+ @printf " CC $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(CC) $(CFLAGS) -o $@ -c $<
+
+clean:
+ @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
+ $(Q)rm -f *.o
+ @printf " CLEAN $(BINARY)\n"
+ $(Q)rm -f $(BINARY)
+ @printf " CLEAN $(BINARY).bin\n"
+ $(Q)rm -f $(BINARY).bin
+ @printf " CLEAN $(BINARY).hex\n"
+ $(Q)rm -f $(BINARY).hex
+ @printf " CLEAN $(BINARY).srec\n"
+ $(Q)rm -f $(BINARY).srec
+ @printf " CLEAN $(BINARY).list\n"
+ $(Q)rm -f $(BINARY).list
+
+flash: images
+ @printf " FLASH $(BINARY).bin\n"
+ @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
+ $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
+ -f $(OPENOCD_FLASHER) \
+ -f $(OPENOCD_BOARD) \
+ -c "init" -c "reset halt" \
+ -c "flash write_image erase $(BINARY).hex" \
+ -c "reset" \
+ -c "shutdown" $(NULL)
+
+.PHONY: images clean
+
diff --git a/examples/stm32-h103/usb_dfu/README b/examples/stm32-h103/usb_dfu/README
new file mode 100644
index 0000000..7146618
--- /dev/null
+++ b/examples/stm32-h103/usb_dfu/README
@@ -0,0 +1,43 @@
+------------------------------------------------------------------------------
+README
+------------------------------------------------------------------------------
+
+This example implements a USB Device Firmware Upgrade (DFU) bootloader
+to demonstrate the use of the USB device stack.
+
+Building
+--------
+
+ $ make
+
+Running 'make' on the top-level libopenstm32 directory will automatically
+also build this example. Or you can build the library "manually" and
+then run 'make' in this directory.
+
+You may want to override the toolchain (e.g., arm-elf or arm-none-eabi):
+
+ $ PREFIX=arm-none-eabi make
+
+For a more verbose build you can use
+
+ $ make V=1
+
+
+Flashing
+--------
+
+You can flash the generated code using OpenOCD:
+
+ $ make flash
+
+Or you can do the same manually via:
+
+ $ openocd -f interface/jtagkey-tiny.cfg -f target/stm32.cfg
+ $ telnet localhost 4444
+ > reset halt
+ > flash write_image erase systick.hex
+ > reset
+
+Replace the "jtagkey-tiny.cfg" with whatever JTAG device you are using, and/or
+replace "stm.cfg" with your respective config file.
+
diff --git a/examples/stm32-h103/usb_dfu/dfu.h b/examples/stm32-h103/usb_dfu/dfu.h
new file mode 100644
index 0000000..e4e4b23
--- /dev/null
+++ b/examples/stm32-h103/usb_dfu/dfu.h
@@ -0,0 +1,81 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#ifndef __DFU_H
+#define __DFU_H
+
+enum dfu_req {
+ DFU_DETACH,
+ DFU_DNLOAD,
+ DFU_UPLOAD,
+ DFU_GETSTATUS,
+ DFU_CLRSTATUS,
+ DFU_GETSTATE,
+ DFU_ABORT
+};
+
+enum dfu_status {
+ DFU_STATUS_OK,
+ DFU_STATUS_ERR_TARGET,
+ DFU_STATUS_ERR_FILE,
+ DFU_STATUS_ERR_WRITE,
+ DFU_STATUS_ERR_ERASE,
+ DFU_STATUS_ERR_CHECK_ERASED,
+ DFU_STATUS_ERR_PROG,
+ DFU_STATUS_ERR_VERIFY,
+ DFU_STATUS_ERR_ADDRESS,
+ DFU_STATUS_ERR_NOTDONE,
+ DFU_STATUS_ERR_FIRMWARE,
+ DFU_STATUS_ERR_VENDOR,
+ DFU_STATUS_ERR_USBR,
+ DFU_STATUS_ERR_POR,
+ DFU_STATUS_ERR_UNKNOWN,
+ DFU_STATUS_ERR_STALLEDPKT,
+};
+
+enum dfu_state {
+ STATE_APP_IDLE,
+ STATE_APP_DETACH,
+ STATE_DFU_IDLE,
+ STATE_DFU_DNLOAD_SYNC,
+ STATE_DFU_DNBUSY,
+ STATE_DFU_DNLOAD_IDLE,
+ STATE_DFU_MANIFEST_SYNC,
+ STATE_DFU_MANIFEST,
+ STATE_DFU_MANIFEST_WAIT_RESET,
+ STATE_DFU_UPLOAD_IDLE,
+ STATE_DFU_ERROR,
+};
+
+#define DFU_FUNCTIONAL 0x21
+struct usb_dfu_descriptor {
+ uint8_t bLength;
+ uint8_t bDescriptorType;
+ uint8_t bmAttributes;
+#define USB_DFU_CAN_DOWNLOAD 0x01
+#define USB_DFU_CAN_UPLOAD 0x02
+#define USB_DFU_MANIFEST_TOLERANT 0x04
+#define USB_DFU_WILL_DETACH 0x08
+
+ uint16_t wDetachTimeout;
+ uint16_t wTransferSize;
+ uint16_t bcdDFUVersion;
+} __attribute__((packed));
+
+#endif
diff --git a/examples/stm32-h103/usb_dfu/usbdfu.c b/examples/stm32-h103/usb_dfu/usbdfu.c
new file mode 100644
index 0000000..9e72318
--- /dev/null
+++ b/examples/stm32-h103/usb_dfu/usbdfu.c
@@ -0,0 +1,298 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopenstm32/rcc.h>
+#include <libopenstm32/gpio.h>
+#include <libopenstm32/flash.h>
+#include <libopenstm32/scb.h>
+#include <usbd.h>
+
+#include <string.h>
+
+#include "dfu.h"
+
+#define APP_ADDRESS 0x08002000
+
+/* 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: */
+u8 usbd_control_buffer[1024];
+
+static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
+
+static struct {
+ u8 buf[sizeof(usbd_control_buffer)];
+ u16 len;
+ u32 addr;
+ u16 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 = 0x0483,
+ .idProduct = 0xDF11,
+ .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 | USB_DFU_WILL_DETACH,
+ .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[] = {
+ "x",
+ "Black Sphere Technologies",
+ "DFU Demo",
+ "DEMO",
+ /* This string is used by ST Microelectronics' DfuSe utility */
+ "@Internal Flash /0x08000000/8*001Ka,56*001Kg"
+};
+
+static u8 usbdfu_getstatus(u32 *bwPollTimeout)
+{
+ 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(struct usb_setup_data *req)
+{
+ int i;
+ (void)req;
+
+ switch(usbdfu_state) {
+ case STATE_DFU_DNBUSY:
+
+ flash_unlock();
+ if(prog.blocknum == 0) {
+ switch(prog.buf[0]) {
+ case CMD_ERASE:
+ flash_erase_page(*(u32*)(prog.buf+1));
+ case CMD_SETADDR:
+ prog.addr = *(u32*)(prog.buf+1);
+ }
+ } else {
+ u32 baseaddr = prog.addr +
+ ((prog.blocknum - 2) *
+ dfu_function.wTransferSize);
+ for(i = 0; i < prog.len; i += 2)
+ flash_program_half_word(baseaddr + i,
+ *(u16*)(prog.buf+i));
+ }
+ flash_lock();
+
+ /* We 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_command(struct usb_setup_data *req,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)complete;
+
+ if(req->bmRequestType != 0x21)
+ return 0; /* Only accept class request */
+
+ switch(req->bRequest) {
+ case DFU_DNLOAD:
+ usbdfu_state = STATE_DFU_MANIFEST_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;
+ }
+
+ return 0;
+}
+
+static int usbdfu_control_read(struct usb_setup_data *req, u8 **buf, u16 *len,
+ void (**complete)(struct usb_setup_data *req))
+{
+
+ if(req->bmRequestType != 0xA1)
+ return 0; /* Only accept class request */
+
+ switch(req->bRequest) {
+ case DFU_UPLOAD:
+ /* Upload not supported for now */
+ return 0;
+ case DFU_GETSTATUS: {
+ u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
+
+ (*buf)[0] = usbdfu_getstatus(&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;
+}
+
+static int usbdfu_control_write(struct usb_setup_data *req, u8 *buf, u16 len,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)complete;
+
+ if(req->bmRequestType != 0x21)
+ return 0; /* Only accept class request */
+
+ if(req->bRequest != DFU_DNLOAD)
+ return 0;
+
+ /* 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;
+}
+
+int main(void)
+{
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ if(!gpio_get(GPIOA, GPIO10)) {
+ /* Boot the application if it's valid */
+ if((*(volatile u32*)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 u32*)APP_ADDRESS));
+ /* Jump to application */
+ (*(void(**)())(APP_ADDRESS + 4))();
+ }
+ }
+
+ rcc_clock_setup_in_hsi_out_48mhz();
+
+ rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
+
+ AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_ON;
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO15);
+
+ usbd_init(&dev, &config, usb_strings);
+ usbd_set_control_buffer_size(sizeof(usbd_control_buffer));
+ usbd_register_control_command_callback(usbdfu_control_command);
+ usbd_register_control_write_callback(usbdfu_control_write);
+ usbd_register_control_read_callback(usbdfu_control_read);
+
+ gpio_set(GPIOA, GPIO15);
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
+
+ while (1)
+ usbd_poll();
+}
+
diff --git a/examples/stm32-h103/usb_dfu/usbdfu.ld b/examples/stm32-h103/usb_dfu/usbdfu.ld
new file mode 100644
index 0000000..d7cd0c5
--- /dev/null
+++ b/examples/stm32-h103/usb_dfu/usbdfu.ld
@@ -0,0 +1,29 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH =8K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K
+}
+
+/* Include the common ld script from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/examples/stm32-h103/usb_hid/Makefile b/examples/stm32-h103/usb_hid/Makefile
new file mode 100644
index 0000000..f280cfb
--- /dev/null
+++ b/examples/stm32-h103/usb_hid/Makefile
@@ -0,0 +1,98 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## This program is free software: you can redistribute it and/or modify
+## it under the terms of the GNU General Public License as published by
+## the Free Software Foundation, either version 3 of the License, or
+## (at your option) any later version.
+##
+## This program is distributed in the hope that it will be useful,
+## but WITHOUT ANY WARRANTY; without even the implied warranty of
+## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+## GNU General Public License for more details.
+##
+## You should have received a copy of the GNU General Public License
+## along with this program. If not, see <http://www.gnu.org/licenses/>.
+##
+
+BINARY = usbhid
+
+PREFIX=/opt/paparazzi/stm32/bin/arm-none-eabi
+# PREFIX ?= arm-none-eabi
+#PREFIX ?= arm-elf
+CC = $(PREFIX)-gcc
+LD = $(PREFIX)-gcc
+OBJCOPY = $(PREFIX)-objcopy
+OBJDUMP = $(PREFIX)-objdump
+# Uncomment this line if you want to use the installed (not local) library.
+#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
+TOOLCHAIN_DIR = ../../..
+CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
+ -mcpu=cortex-m3 -mthumb
+LDSCRIPT = $(BINARY).ld
+LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
+OBJS = $(BINARY).o
+
+#OPENOCD_BASE = /usr
+OPENOCD_BASE = /opt/paparazzi/stm32
+OPENOCD = $(OPENOCD_BASE)/bin/openocd
+OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
+#OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/openocd-usb.cfg
+OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey-tiny.cfg
+OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
+
+# Be silent per default, but 'make V=1' will show all compiler calls.
+ifneq ($(V),1)
+Q := @
+NULL := 2>/dev/null
+endif
+
+all: images
+
+images: $(BINARY)
+ @printf " OBJCOPY $(BINARY).bin\n"
+ $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
+ @printf " OBJCOPY $(BINARY).hex\n"
+ $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
+ @printf " OBJCOPY $(BINARY).srec\n"
+ $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
+ @printf " OBJDUMP $(BINARY).list\n"
+ $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
+
+$(BINARY): $(OBJS) $(LDSCRIPT)
+ @printf " LD $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
+
+%.o: %.c Makefile
+ @printf " CC $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(CC) $(CFLAGS) -o $@ -c $<
+
+clean:
+ @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
+ $(Q)rm -f *.o
+ @printf " CLEAN $(BINARY)\n"
+ $(Q)rm -f $(BINARY)
+ @printf " CLEAN $(BINARY).bin\n"
+ $(Q)rm -f $(BINARY).bin
+ @printf " CLEAN $(BINARY).hex\n"
+ $(Q)rm -f $(BINARY).hex
+ @printf " CLEAN $(BINARY).srec\n"
+ $(Q)rm -f $(BINARY).srec
+ @printf " CLEAN $(BINARY).list\n"
+ $(Q)rm -f $(BINARY).list
+
+flash: images
+ @printf " FLASH $(BINARY).bin\n"
+ @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
+ $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
+ -f $(OPENOCD_FLASHER) \
+ -f $(OPENOCD_BOARD) \
+ -c "init" -c "reset halt" \
+ -c "flash write_image erase $(BINARY).hex" \
+ -c "reset" \
+ -c "shutdown" $(NULL)
+
+.PHONY: images clean
+
diff --git a/examples/stm32-h103/usb_hid/README b/examples/stm32-h103/usb_hid/README
new file mode 100644
index 0000000..3ba2aa6
--- /dev/null
+++ b/examples/stm32-h103/usb_hid/README
@@ -0,0 +1,43 @@
+------------------------------------------------------------------------------
+README
+------------------------------------------------------------------------------
+
+This example implements a USB Human Interface Device (HID)
+to demonstrate the use of the USB device stack.
+
+Building
+--------
+
+ $ make
+
+Running 'make' on the top-level libopenstm32 directory will automatically
+also build this example. Or you can build the library "manually" and
+then run 'make' in this directory.
+
+You may want to override the toolchain (e.g., arm-elf or arm-none-eabi):
+
+ $ PREFIX=arm-none-eabi make
+
+For a more verbose build you can use
+
+ $ make V=1
+
+
+Flashing
+--------
+
+You can flash the generated code using OpenOCD:
+
+ $ make flash
+
+Or you can do the same manually via:
+
+ $ openocd -f interface/jtagkey-tiny.cfg -f target/stm32.cfg
+ $ telnet localhost 4444
+ > reset halt
+ > flash write_image erase systick.hex
+ > reset
+
+Replace the "jtagkey-tiny.cfg" with whatever JTAG device you are using, and/or
+replace "stm.cfg" with your respective config file.
+
diff --git a/examples/stm32-h103/usb_hid/hid.h b/examples/stm32-h103/usb_hid/hid.h
new file mode 100644
index 0000000..4690103
--- /dev/null
+++ b/examples/stm32-h103/usb_hid/hid.h
@@ -0,0 +1,38 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+#ifndef __HID_H
+#define __HID_H
+
+#include <stdint.h>
+
+#define USB_CLASS_HID 3
+
+#define USB_DT_HID 0x21
+#define USB_DT_REPORT 0x22
+
+struct usb_hid_descriptor {
+ uint8_t bLength;
+ uint8_t bDescriptorType;
+ uint16_t bcdHID;
+ uint8_t bCountryCode;
+ uint8_t bNumDescriptors;
+} __attribute__((packed));
+
+#endif
+
diff --git a/examples/stm32-h103/usb_hid/usbhid.c b/examples/stm32-h103/usb_hid/usbhid.c
new file mode 100644
index 0000000..e27dac7
--- /dev/null
+++ b/examples/stm32-h103/usb_hid/usbhid.c
@@ -0,0 +1,276 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopenstm32/rcc.h>
+#include <libopenstm32/gpio.h>
+#include <libopenstm32/systick.h>
+#include <usbd.h>
+
+#include <stdlib.h>
+
+#include "hid.h"
+
+/* Define this to include the DFU APP interface. */
+#define INCLUDE_DFU_INTERFACE
+
+#ifdef INCLUDE_DFU_INTERFACE
+# include <libopenstm32/scb.h>
+# include "../usb_dfu/dfu.h"
+#endif
+
+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 = 0x0483,
+ .idProduct = 0x5710,
+ .bcdDevice = 0x0200,
+ .iManufacturer = 1,
+ .iProduct = 2,
+ .iSerialNumber = 3,
+ .bNumConfigurations = 1,
+};
+
+/* I have no idea what this means. I haven't read the HID spec. */
+static const u8 hid_report_descriptor[] = {
+ 0x05, 0x01, 0x09, 0x02, 0xA1, 0x01, 0x09, 0x01,
+ 0xA1, 0x00, 0x05, 0x09, 0x19, 0x01, 0x29, 0x03,
+ 0x15, 0x00, 0x25, 0x01, 0x95, 0x03, 0x75, 0x01,
+ 0x81, 0x02, 0x95, 0x01, 0x75, 0x05, 0x81, 0x01,
+ 0x05, 0x01, 0x09, 0x30, 0x09, 0x31, 0x09, 0x38,
+ 0x15, 0x81, 0x25, 0x7F, 0x75, 0x08, 0x95, 0x03,
+ 0x81, 0x06, 0xC0, 0x09, 0x3c, 0x05, 0xff, 0x09,
+ 0x01, 0x15, 0x00, 0x25, 0x01, 0x75, 0x01, 0x95,
+ 0x02, 0xb1, 0x22, 0x75, 0x06, 0x95, 0x01, 0xb1,
+ 0x01, 0xc0
+};
+
+static const struct {
+ struct usb_hid_descriptor hid_descriptor;
+ struct {
+ uint8_t bReportDescriptorType;
+ uint16_t wDescriptorLength;
+ } __attribute__((packed)) hid_report;
+} __attribute__((packed)) hid_function = {
+ .hid_descriptor = {
+ .bLength = sizeof(hid_function),
+ .bDescriptorType = USB_DT_HID,
+ .bcdHID = 0x0100,
+ .bCountryCode = 0,
+ .bNumDescriptors = 1,
+ },
+ .hid_report = {
+ .bReportDescriptorType = USB_DT_REPORT,
+ .wDescriptorLength = sizeof(hid_report_descriptor),
+ }
+};
+
+const struct usb_endpoint_descriptor hid_endpoint = {
+ .bLength = USB_DT_ENDPOINT_SIZE,
+ .bDescriptorType = USB_DT_ENDPOINT,
+ .bEndpointAddress = 0x81,
+ .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
+ .wMaxPacketSize = 4,
+ .bInterval = 0x20,
+};
+
+const struct usb_interface_descriptor hid_iface = {
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 0,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 1,
+ .bInterfaceClass = USB_CLASS_HID,
+ .bInterfaceSubClass = 1, /* boot */
+ .bInterfaceProtocol = 2, /* mouse */
+ .iInterface = 0,
+
+ .endpoint = &hid_endpoint,
+
+ .extra = &hid_function,
+ .extralen = sizeof(hid_function),
+};
+
+#ifdef INCLUDE_DFU_INTERFACE
+const struct usb_dfu_descriptor dfu_function = {
+ .bLength = sizeof(struct usb_dfu_descriptor),
+ .bDescriptorType = DFU_FUNCTIONAL,
+ .bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_WILL_DETACH,
+ .wDetachTimeout = 255,
+ .wTransferSize = 1024,
+ .bcdDFUVersion = 0x011A,
+};
+
+const struct usb_interface_descriptor dfu_iface = {
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 1,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 0,
+ .bInterfaceClass = 0xFE,
+ .bInterfaceSubClass = 1,
+ .bInterfaceProtocol = 1,
+ .iInterface = 0,
+
+ .extra = &dfu_function,
+ .extralen = sizeof(dfu_function),
+};
+#endif
+
+const struct usb_interface ifaces[] = {{
+ .num_altsetting = 1,
+ .altsetting = &hid_iface,
+#ifdef INCLUDE_DFU_INTERFACE
+}, {
+ .num_altsetting = 1,
+ .altsetting = &dfu_iface,
+#endif
+}};
+
+const struct usb_config_descriptor config = {
+ .bLength = USB_DT_CONFIGURATION_SIZE,
+ .bDescriptorType = USB_DT_CONFIGURATION,
+ .wTotalLength = 0,
+#ifdef INCLUDE_DFU_INTERFACE
+ .bNumInterfaces = 2,
+#else
+ .bNumInterfaces = 1,
+#endif
+ .bConfigurationValue = 1,
+ .iConfiguration = 0,
+ .bmAttributes = 0xC0,
+ .bMaxPower = 0x32,
+
+ .interface = ifaces,
+};
+
+static const char *usb_strings[] = {
+ "x",
+ "Black Sphere Technologies",
+ "HID Demo",
+ "DEMO",
+};
+
+static int hid_control_request(struct usb_setup_data *req, u8 **buf, u16 *len,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)complete;
+
+ if((req->bmRequestType != 0x81) ||
+ (req->bRequest != USB_REQ_GET_DESCRIPTOR) ||
+ (req->wValue != 0x2200))
+ return 0;
+
+ /* Handle the HID report descriptor */
+ *buf = (u8*)hid_report_descriptor;
+ *len = sizeof(hid_report_descriptor);
+
+ return 1;
+}
+
+#ifdef INCLUDE_DFU_INTERFACE
+static void dfu_detach_complete(struct usb_setup_data *req)
+{
+ (void)req;
+
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO15);
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO10);
+ gpio_set(GPIOA, GPIO10);
+ scb_reset_core();
+}
+
+static int dfu_control_request(struct usb_setup_data *req, u8 **buf, u16 *len,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)buf;
+ (void)len;
+
+ if((req->bmRequestType != 0x21) || (req->bRequest != DFU_DETACH))
+ return 0; /* Only accept class request */
+
+ *complete = dfu_detach_complete;
+
+ return 1;
+}
+#endif
+
+static void hid_set_config(u16 wValue)
+{
+ (void)wValue;
+
+ usbd_ep_setup(0x81, USB_ENDPOINT_ATTR_INTERRUPT, 4, NULL);
+
+ usbd_register_control_callback(
+ USB_REQ_TYPE_STANDARD | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ hid_control_request);
+#ifdef INCLUDE_DFU_INTERFACE
+ usbd_register_control_callback(
+ USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
+ USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
+ dfu_control_request);
+#endif
+
+ systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
+ systick_set_reload(100000);
+ systick_interrupt_enable();
+ systick_counter_enable();
+}
+
+int main(void)
+{
+ rcc_clock_setup_in_hsi_out_48mhz();
+
+
+ rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
+
+ gpio_set(GPIOC, GPIO11);
+ gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO11);
+
+ usbd_init(&dev, &config, usb_strings);
+ usbd_register_set_config_callback(hid_set_config);
+
+ {int i; for (i=0;i<0x80000;i++);}
+ gpio_clear(GPIOC, GPIO11);
+
+ while (1)
+ usbd_poll();
+}
+
+void sys_tick_handler(void)
+{
+ static int x = 0;
+ static int dir = 1;
+ uint8_t buf[4] = {0, 0, 0, 0};
+
+ buf[1] = dir;
+ x += dir;
+ if(x > 30) dir = -dir;
+ if(x < -30) dir = -dir;
+
+ usbd_ep_write_packet(0x81, buf, 4);
+}
+
diff --git a/examples/stm32-h103/usb_hid/usbhid.ld b/examples/stm32-h103/usb_hid/usbhid.ld
new file mode 100644
index 0000000..a393e0b
--- /dev/null
+++ b/examples/stm32-h103/usb_hid/usbhid.ld
@@ -0,0 +1,32 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* 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 from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/examples/stm32-h103/usb_iap/Makefile b/examples/stm32-h103/usb_iap/Makefile
new file mode 100644
index 0000000..195e5da
--- /dev/null
+++ b/examples/stm32-h103/usb_iap/Makefile
@@ -0,0 +1,98 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## This program is free software: you can redistribute it and/or modify
+## it under the terms of the GNU General Public License as published by
+## the Free Software Foundation, either version 3 of the License, or
+## (at your option) any later version.
+##
+## This program is distributed in the hope that it will be useful,
+## but WITHOUT ANY WARRANTY; without even the implied warranty of
+## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+## GNU General Public License for more details.
+##
+## You should have received a copy of the GNU General Public License
+## along with this program. If not, see <http://www.gnu.org/licenses/>.
+##
+
+BINARY = usbiap
+
+PREFIX=/opt/paparazzi/stm32/bin/arm-none-eabi
+# PREFIX ?= arm-none-eabi
+#PREFIX ?= arm-elf
+CC = $(PREFIX)-gcc
+LD = $(PREFIX)-gcc
+OBJCOPY = $(PREFIX)-objcopy
+OBJDUMP = $(PREFIX)-objdump
+# Uncomment this line if you want to use the installed (not local) library.
+#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
+TOOLCHAIN_DIR = ../../..
+CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
+ -mcpu=cortex-m3 -mthumb
+LDSCRIPT = $(BINARY).ld
+LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
+OBJS = $(BINARY).o
+
+#OPENOCD_BASE = /usr
+OPENOCD_BASE = /opt/paparazzi/stm32
+OPENOCD = $(OPENOCD_BASE)/bin/openocd
+OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
+#OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/openocd-usb.cfg
+OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey-tiny.cfg
+OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
+
+# Be silent per default, but 'make V=1' will show all compiler calls.
+ifneq ($(V),1)
+Q := @
+NULL := 2>/dev/null
+endif
+
+all: images
+
+images: $(BINARY)
+ @printf " OBJCOPY $(BINARY).bin\n"
+ $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
+ @printf " OBJCOPY $(BINARY).hex\n"
+ $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
+ @printf " OBJCOPY $(BINARY).srec\n"
+ $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
+ @printf " OBJDUMP $(BINARY).list\n"
+ $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
+
+$(BINARY): $(OBJS) $(LDSCRIPT)
+ @printf " LD $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
+
+%.o: %.c Makefile
+ @printf " CC $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(CC) $(CFLAGS) -o $@ -c $<
+
+clean:
+ @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
+ $(Q)rm -f *.o
+ @printf " CLEAN $(BINARY)\n"
+ $(Q)rm -f $(BINARY)
+ @printf " CLEAN $(BINARY).bin\n"
+ $(Q)rm -f $(BINARY).bin
+ @printf " CLEAN $(BINARY).hex\n"
+ $(Q)rm -f $(BINARY).hex
+ @printf " CLEAN $(BINARY).srec\n"
+ $(Q)rm -f $(BINARY).srec
+ @printf " CLEAN $(BINARY).list\n"
+ $(Q)rm -f $(BINARY).list
+
+flash: images
+ @printf " FLASH $(BINARY).bin\n"
+ @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
+ $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
+ -f $(OPENOCD_FLASHER) \
+ -f $(OPENOCD_BOARD) \
+ -c "init" -c "reset halt" \
+ -c "flash write_image erase $(BINARY).hex" \
+ -c "reset" \
+ -c "shutdown" $(NULL)
+
+.PHONY: images clean
+
diff --git a/examples/stm32-h103/usb_iap/README b/examples/stm32-h103/usb_iap/README
new file mode 100644
index 0000000..c4b41ed
--- /dev/null
+++ b/examples/stm32-h103/usb_iap/README
@@ -0,0 +1,42 @@
+------------------------------------------------------------------------------
+README
+------------------------------------------------------------------------------
+
+This example implements a USB bootloader for the Paparazzi project.
+
+Building
+--------
+
+ $ make
+
+Running 'make' on the top-level libopenstm32 directory will automatically
+also build this example. Or you can build the library "manually" and
+then run 'make' in this directory.
+
+You may want to override the toolchain (e.g., arm-elf or arm-none-eabi):
+
+ $ PREFIX=arm-none-eabi make
+
+For a more verbose build you can use
+
+ $ make V=1
+
+
+Flashing
+--------
+
+You can flash the generated code using OpenOCD:
+
+ $ make flash
+
+Or you can do the same manually via:
+
+ $ openocd -f interface/jtagkey-tiny.cfg -f target/stm32.cfg
+ $ telnet localhost 4444
+ > reset halt
+ > flash write_image erase usbiap.hex
+ > reset
+
+Replace the "jtagkey-tiny.cfg" with whatever JTAG device you are using, and/or
+replace "stm.cfg" with your respective config file.
+
diff --git a/examples/stm32-h103/usb_iap/usbiap.c b/examples/stm32-h103/usb_iap/usbiap.c
new file mode 100644
index 0000000..9e72318
--- /dev/null
+++ b/examples/stm32-h103/usb_iap/usbiap.c
@@ -0,0 +1,298 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopenstm32/rcc.h>
+#include <libopenstm32/gpio.h>
+#include <libopenstm32/flash.h>
+#include <libopenstm32/scb.h>
+#include <usbd.h>
+
+#include <string.h>
+
+#include "dfu.h"
+
+#define APP_ADDRESS 0x08002000
+
+/* 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: */
+u8 usbd_control_buffer[1024];
+
+static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
+
+static struct {
+ u8 buf[sizeof(usbd_control_buffer)];
+ u16 len;
+ u32 addr;
+ u16 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 = 0x0483,
+ .idProduct = 0xDF11,
+ .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 | USB_DFU_WILL_DETACH,
+ .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[] = {
+ "x",
+ "Black Sphere Technologies",
+ "DFU Demo",
+ "DEMO",
+ /* This string is used by ST Microelectronics' DfuSe utility */
+ "@Internal Flash /0x08000000/8*001Ka,56*001Kg"
+};
+
+static u8 usbdfu_getstatus(u32 *bwPollTimeout)
+{
+ 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(struct usb_setup_data *req)
+{
+ int i;
+ (void)req;
+
+ switch(usbdfu_state) {
+ case STATE_DFU_DNBUSY:
+
+ flash_unlock();
+ if(prog.blocknum == 0) {
+ switch(prog.buf[0]) {
+ case CMD_ERASE:
+ flash_erase_page(*(u32*)(prog.buf+1));
+ case CMD_SETADDR:
+ prog.addr = *(u32*)(prog.buf+1);
+ }
+ } else {
+ u32 baseaddr = prog.addr +
+ ((prog.blocknum - 2) *
+ dfu_function.wTransferSize);
+ for(i = 0; i < prog.len; i += 2)
+ flash_program_half_word(baseaddr + i,
+ *(u16*)(prog.buf+i));
+ }
+ flash_lock();
+
+ /* We 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_command(struct usb_setup_data *req,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)complete;
+
+ if(req->bmRequestType != 0x21)
+ return 0; /* Only accept class request */
+
+ switch(req->bRequest) {
+ case DFU_DNLOAD:
+ usbdfu_state = STATE_DFU_MANIFEST_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;
+ }
+
+ return 0;
+}
+
+static int usbdfu_control_read(struct usb_setup_data *req, u8 **buf, u16 *len,
+ void (**complete)(struct usb_setup_data *req))
+{
+
+ if(req->bmRequestType != 0xA1)
+ return 0; /* Only accept class request */
+
+ switch(req->bRequest) {
+ case DFU_UPLOAD:
+ /* Upload not supported for now */
+ return 0;
+ case DFU_GETSTATUS: {
+ u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
+
+ (*buf)[0] = usbdfu_getstatus(&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;
+}
+
+static int usbdfu_control_write(struct usb_setup_data *req, u8 *buf, u16 len,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)complete;
+
+ if(req->bmRequestType != 0x21)
+ return 0; /* Only accept class request */
+
+ if(req->bRequest != DFU_DNLOAD)
+ return 0;
+
+ /* 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;
+}
+
+int main(void)
+{
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ if(!gpio_get(GPIOA, GPIO10)) {
+ /* Boot the application if it's valid */
+ if((*(volatile u32*)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 u32*)APP_ADDRESS));
+ /* Jump to application */
+ (*(void(**)())(APP_ADDRESS + 4))();
+ }
+ }
+
+ rcc_clock_setup_in_hsi_out_48mhz();
+
+ rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
+
+ AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_ON;
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO15);
+
+ usbd_init(&dev, &config, usb_strings);
+ usbd_set_control_buffer_size(sizeof(usbd_control_buffer));
+ usbd_register_control_command_callback(usbdfu_control_command);
+ usbd_register_control_write_callback(usbdfu_control_write);
+ usbd_register_control_read_callback(usbdfu_control_read);
+
+ gpio_set(GPIOA, GPIO15);
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
+
+ while (1)
+ usbd_poll();
+}
+
diff --git a/examples/stm32-h103/usb_iap/usbiap.ld b/examples/stm32-h103/usb_iap/usbiap.ld
new file mode 100644
index 0000000..a393e0b
--- /dev/null
+++ b/examples/stm32-h103/usb_iap/usbiap.ld
@@ -0,0 +1,32 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* 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 from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/include/usbd.h b/include/usbd.h
index d825d9e..310c44e 100644
--- a/include/usbd.h
+++ b/include/usbd.h
@@ -36,16 +36,13 @@ extern void usbd_register_reset_callback(void (*callback)(void));
extern void usbd_register_suspend_callback(void (*callback)(void));
extern void usbd_register_resume_callback(void (*callback)(void));
+typedef int (*usbd_control_callback)(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len,
+ void (**complete)(struct usb_setup_data *req));
+
/* <usb_control.c> */
-extern void usbd_register_control_command_callback(
- int (*callback)(struct usb_setup_data *req,
- void (**complete)(struct usb_setup_data *req)));
-extern void usbd_register_control_read_callback(
- int (*callback)(struct usb_setup_data *req, uint8_t **buf,
- uint16_t *len, void (**complete)(struct usb_setup_data *req)));
-extern void usbd_register_control_write_callback(
- int (*callback)(struct usb_setup_data *req, uint8_t *buf,
- uint16_t len, void (**complete)(struct usb_setup_data *req)));
+extern int usbd_register_control_callback(uint8_t type, uint8_t type_mask,
+ usbd_control_callback callback);
/* <usb_standard.c> */
extern void
diff --git a/lib/usb/usb_control.c b/lib/usb/usb_control.c
index f5e4d27..c10144d 100644
--- a/lib/usb/usb_control.c
+++ b/lib/usb/usb_control.c
@@ -36,30 +36,21 @@ static struct usb_control_state {
} control_state;
/** Register application callback function for handling of usb control
- * request with no data. */
-void usbd_register_control_command_callback(
- int (*callback)(struct usb_setup_data *req,
- void (**complete)(struct usb_setup_data *req)))
+ * request. */
+int usbd_register_control_callback(uint8_t type, uint8_t type_mask,
+ usbd_control_callback callback)
{
- _usbd_device.user_callback_control_command = callback;
-}
-
-/** Register application callback function for handling of usb control
- * request to read data. */
-void usbd_register_control_read_callback(
- int (*callback)(struct usb_setup_data *req, uint8_t **buf,
- uint16_t *len, void (**complete)(struct usb_setup_data *req)))
-{
- _usbd_device.user_callback_control_read = callback;
-}
-
-/** Register application callback function for handling of usb control
- * request with received data. */
-void usbd_register_control_write_callback(
- int (*callback)(struct usb_setup_data *req, uint8_t *buf, uint16_t len,
- void (**complete)(struct usb_setup_data *req)))
-{
- _usbd_device.user_callback_control_write = callback;
+ int i;
+ for(i = 0; i < MAX_USER_CONTROL_CALLBACK; i++) {
+ if(_usbd_device.user_control_callback[i].cb)
+ continue;
+
+ _usbd_device.user_control_callback[i].type = type;
+ _usbd_device.user_control_callback[i].type_mask = type_mask;
+ _usbd_device.user_control_callback[i].cb = callback;
+ return 0;
+ }
+ return -1;
}
static void usb_control_send_chunk(void)
@@ -102,58 +93,47 @@ static int usb_control_recv_chunk(void)
return packetsize;
}
-static void usb_control_setup_nodata(struct usb_setup_data *req)
+static int usb_control_request_dispatch(struct usb_setup_data *req)
{
int result = 0;
-
- /* Buffer unused */
- control_state.ctrl_buf = _usbd_device.ctrl_buf;
- control_state.ctrl_len = 0;
+ int i;
+ struct user_control_callback *cb = _usbd_device.user_control_callback;
/* Call user command hook function */
- if(_usbd_device.user_callback_control_command)
- result = _usbd_device.user_callback_control_command(req,
+ for(i = 0; i < MAX_USER_CONTROL_CALLBACK; i++) {
+ if(cb[i].cb == NULL)
+ break;
+
+ if((req->bmRequestType & cb[i].type_mask) == cb[i].type) {
+ result = cb[i].cb(req, &control_state.ctrl_buf,
+ &control_state.ctrl_len,
&control_state.complete);
+ if(result)
+ return result;
+ }
+ }
- /* Try standard command if not already handled */
- if(!result)
- result = _usbd_standard_request(req,
- &control_state.ctrl_buf,
+ /* Try standard request if not already handled */
+ return _usbd_standard_request(req, &control_state.ctrl_buf,
&control_state.ctrl_len);
-
- if(result) {
- /* Go to status stage if handled */
- usbd_ep_write_packet(0, NULL, 0);
- control_state.state = STATUS_IN;
- } else {
- /* Stall endpoint on failure */
- usbd_ep_stall_set(0, 1);
- }
}
+/* Handle commands and read requests. */
static void usb_control_setup_read(struct usb_setup_data *req)
{
- int result = 0;
control_state.ctrl_buf = _usbd_device.ctrl_buf;
- control_state.ctrl_len = req->wLength;
-
- /* Call user command hook function */
- if(_usbd_device.user_callback_control_read)
- result = _usbd_device.user_callback_control_read(req,
- &control_state.ctrl_buf,
- &control_state.ctrl_len,
- &control_state.complete);
+ control_state.ctrl_len = req->wLength;
- /* Try standard request if not already handled */
- if(!result)
- result = _usbd_standard_request(req,
- &control_state.ctrl_buf,
- &control_state.ctrl_len);
-
- if(result) {
- /* Go to status stage if handled */
- usb_control_send_chunk();
+ if(usb_control_request_dispatch(req)) {
+ if(control_state.ctrl_len) {
+ /* Go to data out stage if handled */
+ usb_control_send_chunk();
+ } else {
+ /* Go to status stage if handled */
+ usbd_ep_write_packet(0, NULL, 0);
+ control_state.state = STATUS_IN;
+ }
} else {
/* Stall endpoint on failure */
usbd_ep_stall_set(0, 1);
@@ -189,7 +169,7 @@ void _usbd_control_setup(uint8_t ea)
}
if(req->wLength == 0) {
- usb_control_setup_nodata(req);
+ usb_control_setup_read(req);
} else if(req->bmRequestType & 0x80) {
usb_control_setup_read(req);
} else {
@@ -216,20 +196,8 @@ void _usbd_control_out(uint8_t ea)
/* We have now received the full data payload.
* Invoke callback to process.
*/
- if(_usbd_device.user_callback_control_write)
- result = _usbd_device.user_callback_control_write(
- &control_state.req,
- control_state.ctrl_buf,
- control_state.ctrl_len,
- &control_state.complete);
-
- if(!result)
- result = _usbd_standard_request(
- &control_state.req,
- &control_state.ctrl_buf,
- &control_state.ctrl_len);
-
- if(result) {
+ if(usb_control_request_dispatch(&control_state.req)) {
+ /* Got to status stage on success */
usbd_ep_write_packet(0, NULL, 0);
control_state.state = STATUS_IN;
} else {
diff --git a/lib/usb/usb_private.h b/lib/usb/usb_private.h
index 6cbc576..6c7e073 100644
--- a/lib/usb/usb_private.h
+++ b/lib/usb/usb_private.h
@@ -21,6 +21,8 @@
#ifndef __USB_PRIVATE_H
#define __USB_PRIVATE_H
+#define MAX_USER_CONTROL_CALLBACK 4
+
#define MIN(a, b) ((a)<(b) ? (a) : (b))
/** Internal collection of device information. */
@@ -42,14 +44,11 @@ extern struct _usbd_device {
void (*user_callback_suspend)(void);
void (*user_callback_resume)(void);
- int (*user_callback_control_command)(struct usb_setup_data *req,
- void (**complete)(struct usb_setup_data *req));
- int (*user_callback_control_read)(struct usb_setup_data *req,
- uint8_t **buf, uint16_t *len,
- void (**complete)(struct usb_setup_data *req));
- int (*user_callback_control_write)(struct usb_setup_data *req,
- uint8_t *buf, uint16_t len,
- void (**complete)(struct usb_setup_data *req));
+ struct user_control_callback {
+ usbd_control_callback cb;
+ uint8_t type;
+ uint8_t type_mask;
+ } user_control_callback[MAX_USER_CONTROL_CALLBACK];
void (*user_callback_ctr[8][3])(uint8_t ea);