aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--examples/stm32-h103/Makefile10
-rw-r--r--examples/stm32-h103/usb_cdcacm/Makefile98
-rw-r--r--examples/stm32-h103/usb_cdcacm/README43
-rw-r--r--examples/stm32-h103/usb_cdcacm/cdc.h128
-rw-r--r--examples/stm32-h103/usb_cdcacm/cdcacm.c253
-rw-r--r--examples/stm32-h103/usb_cdcacm/cdcacm.ld32
-rw-r--r--include/usbstd.h8
-rw-r--r--lib/usb/usb_control.c16
-rw-r--r--lib/usb/usb_f103.c17
-rw-r--r--lib/usb/usb_private.h5
-rw-r--r--lib/usb/usb_standard.c195
11 files changed, 746 insertions, 59 deletions
diff --git a/examples/stm32-h103/Makefile b/examples/stm32-h103/Makefile
index 5aa063c..65fb97d 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
+all: miniblink fancyblink usart usb_cdcacm
miniblink:
@printf " BUILD examples/stm32-h103/miniblink\n"
@@ -42,6 +42,10 @@ spi:
@printf " BUILD examples/stm32-h103/spi\n"
$(Q)$(MAKE) -C spi
+usb_cdcacm:
+ @printf " BUILD examples/stm32-h103/usb_cdcacm\n"
+ $(Q)$(MAKE) -C spi
+
clean:
@printf " CLEAN examples/stm32-h103/miniblink\n"
$(Q)$(MAKE) -C miniblink clean
@@ -51,6 +55,8 @@ clean:
$(Q)$(MAKE) -C usart clean
@printf " CLEAN examples/stm32-h103/spi\n"
$(Q)$(MAKE) -C spi clean
+ @printf " CLEAN examples/stm32-h103/usb_cdcacm\n"
+ $(Q)$(MAKE) -C usb_cdcacm clean
-.PHONY: miniblink fancyblink usart spi clean
+.PHONY: miniblink fancyblink usart spi usb_cdcacm clean
diff --git a/examples/stm32-h103/usb_cdcacm/Makefile b/examples/stm32-h103/usb_cdcacm/Makefile
new file mode 100644
index 0000000..531bb96
--- /dev/null
+++ b/examples/stm32-h103/usb_cdcacm/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 = cdcacm
+
+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_cdcacm/README b/examples/stm32-h103/usb_cdcacm/README
new file mode 100644
index 0000000..fba104a
--- /dev/null
+++ b/examples/stm32-h103/usb_cdcacm/README
@@ -0,0 +1,43 @@
+------------------------------------------------------------------------------
+README
+------------------------------------------------------------------------------
+
+This example implements a USB CDC-ACM device (aka Virtual Serial Port)
+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_cdcacm/cdc.h b/examples/stm32-h103/usb_cdcacm/cdc.h
new file mode 100644
index 0000000..c67b5e9
--- /dev/null
+++ b/examples/stm32-h103/usb_cdcacm/cdc.h
@@ -0,0 +1,128 @@
+/*
+ * 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 __CDC_H
+#define __CDC_H
+
+/* Definitions of Communications Device Class from
+ * "Universal Serial Bus Class Definitions for Communications Devices
+ * Revision 1.2"
+ */
+
+/* Table 2: Communications Device Class Code */
+#define USB_CLASS_CDC 0x02
+
+/* Table 4: Class Subclass Code */
+#define USB_CDC_SUBCLASS_DLCM 0x01
+#define USB_CDC_SUBCLASS_ACM 0x02
+/* ... */
+
+/* Table 5 Communications Interface Class Control Protocol Codes */
+#define USB_CDC_PROTOCOL_NONE 0x00
+#define USB_CDC_PROTOCOL_AT 0x01
+/* ... */
+
+/* Table 6: Data Interface Class Code */
+#define USB_CLASS_DATA 0x0A
+
+/* Table 12: Type Values for the bDescriptorType Field */
+#define CS_INTERFACE 0x24
+#define CS_ENDPOINT 0x25
+
+/* Table 13: bDescriptor SubType in Communications Class Functional
+ * Descriptors */
+#define USB_CDC_TYPE_HEADER 0x00
+#define USB_CDC_TYPE_CALL_MANAGEMENT 0x01
+#define USB_CDC_TYPE_ACM 0x02
+/* ... */
+#define USB_CDC_TYPE_UNION 0x06
+/* ... */
+
+/* Table 15: Class-Specific Descriptor Header Format */
+struct usb_cdc_header_descriptor {
+ uint8_t bFunctionLength;
+ uint8_t bDescriptorType;
+ uint8_t bDescriptorSubtype;
+ uint16_t bcdCDC;
+} __attribute__((packed));
+
+/* Table 16: Union Interface Functional Descriptor */
+struct usb_cdc_union_descriptor {
+ uint8_t bFunctionLength;
+ uint8_t bDescriptorType;
+ uint8_t bDescriptorSubtype;
+ uint8_t bControlInterface;
+ uint8_t bSubordinateInterface0;
+ /* ... */
+} __attribute__((packed));
+
+
+/* Definitions for Abstract Control Model devices from:
+ * "Universal Serial Bus Communications Class Subclass Specification for
+ * PSTN Devices"
+ */
+
+/* Table 3: Call Management Functional Descriptor */
+struct usb_cdc_call_management_descriptor {
+ uint8_t bFunctionLength;
+ uint8_t bDescriptorType;
+ uint8_t bDescriptorSubtype;
+ uint8_t bmCapabilities;
+ uint8_t bDataInterface;
+} __attribute__((packed));
+
+/* Table 4: Abstract Control Management Functional Descriptor */
+struct usb_cdc_acm_descriptor {
+ uint8_t bFunctionLength;
+ uint8_t bDescriptorType;
+ uint8_t bDescriptorSubtype;
+ uint8_t bmCapabilities;
+} __attribute__((packed));
+
+/* Table 13: Class-Specific Request Codes for PSTN subclasses */
+/* ... */
+#define USB_CDC_REQ_SET_LINE_CODING 0x20
+/* ... */
+#define USB_CDC_REQ_SET_CONTROL_LINE_STATE 0x22
+/* ... */
+
+/* Table 17: Line Coding Structure */
+struct usb_cdc_line_coding {
+ uint32_t dwDTERate;
+ uint8_t bCharFormat;
+ uint8_t bParityType;
+ uint8_t bDataBits;
+} __attribute__((packed));
+
+/* Table 30: Class-Specific Notification Codes for PSTN subclasses */
+/* ... */
+#define USB_CDC_NOTIFY_SERIAL_STATE 0x28
+/* ... */
+
+
+/* Notification Structure */
+struct usb_cdc_notification {
+ uint8_t bmRequestType;
+ uint8_t bNotification;
+ uint16_t wValue;
+ uint16_t wIndex;
+ uint16_t wLength;
+} __attribute__((packed));
+
+#endif
+
diff --git a/examples/stm32-h103/usb_cdcacm/cdcacm.c b/examples/stm32-h103/usb_cdcacm/cdcacm.c
new file mode 100644
index 0000000..f757f63
--- /dev/null
+++ b/examples/stm32-h103/usb_cdcacm/cdcacm.c
@@ -0,0 +1,253 @@
+/*
+ * 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 <usbd.h>
+#include <stdlib.h>
+
+#include "cdc.h"
+
+static const struct usb_device_descriptor dev = {
+ .bLength = USB_DT_DEVICE_SIZE,
+ .bDescriptorType = USB_DT_DEVICE,
+ .bcdUSB = 0x0200,
+ .bDeviceClass = USB_CLASS_CDC,
+ .bDeviceSubClass = 0,
+ .bDeviceProtocol = 0,
+ .bMaxPacketSize0 = 64,
+ .idVendor = 0x0483,
+ .idProduct = 0x5740,
+ .bcdDevice = 0x0200,
+ .iManufacturer = 1,
+ .iProduct = 2,
+ .iSerialNumber = 3,
+ .bNumConfigurations = 1,
+};
+
+/* This notification endpoint isn't implemented. According to CDC spec its
+ * optional, but its absence causes a NULL pointer dereference in Linux cdc_acm
+ * driver. */
+static const struct usb_endpoint_descriptor comm_endp[] = {{
+ .bLength = USB_DT_ENDPOINT_SIZE,
+ .bDescriptorType = USB_DT_ENDPOINT,
+ .bEndpointAddress = 0x83,
+ .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
+ .wMaxPacketSize = 16,
+ .bInterval = 255,
+}};
+
+static const struct usb_endpoint_descriptor data_endp[] = {{
+ .bLength = USB_DT_ENDPOINT_SIZE,
+ .bDescriptorType = USB_DT_ENDPOINT,
+ .bEndpointAddress = 0x01,
+ .bmAttributes = USB_ENDPOINT_ATTR_BULK,
+ .wMaxPacketSize = 64,
+ .bInterval = 1,
+}, {
+ .bLength = USB_DT_ENDPOINT_SIZE,
+ .bDescriptorType = USB_DT_ENDPOINT,
+ .bEndpointAddress = 0x82,
+ .bmAttributes = USB_ENDPOINT_ATTR_BULK,
+ .wMaxPacketSize = 64,
+ .bInterval = 1,
+}};
+
+static const struct {
+ struct usb_cdc_header_descriptor header;
+ struct usb_cdc_call_management_descriptor call_mgmt;
+ struct usb_cdc_acm_descriptor acm;
+ struct usb_cdc_union_descriptor cdc_union;
+} __attribute__((packed)) cdcacm_functional_descriptors = {
+ .header = {
+ .bFunctionLength = sizeof(struct usb_cdc_header_descriptor),
+ .bDescriptorType = CS_INTERFACE,
+ .bDescriptorSubtype = USB_CDC_TYPE_HEADER,
+ .bcdCDC = 0x0110,
+ },
+ .call_mgmt = {
+ .bFunctionLength =
+ sizeof(struct usb_cdc_call_management_descriptor),
+ .bDescriptorType = CS_INTERFACE,
+ .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT,
+ .bmCapabilities = 0,
+ .bDataInterface = 1,
+ },
+ .acm = {
+ .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor),
+ .bDescriptorType = CS_INTERFACE,
+ .bDescriptorSubtype = USB_CDC_TYPE_ACM,
+ .bmCapabilities = 0,
+ },
+ .cdc_union = {
+ .bFunctionLength = sizeof(struct usb_cdc_union_descriptor),
+ .bDescriptorType = CS_INTERFACE,
+ .bDescriptorSubtype = USB_CDC_TYPE_UNION,
+ .bControlInterface = 0,
+ .bSubordinateInterface0 = 1,
+ }
+};
+
+static const struct usb_interface_descriptor comm_iface[] = {{
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 0,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 1,
+ .bInterfaceClass = USB_CLASS_CDC,
+ .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
+ .bInterfaceProtocol = USB_CDC_PROTOCOL_AT,
+ .iInterface = 0,
+
+ .endpoint = comm_endp,
+
+ .extra = &cdcacm_functional_descriptors,
+ .extralen = sizeof(cdcacm_functional_descriptors)
+}};
+
+static const struct usb_interface_descriptor data_iface[] = {{
+ .bLength = USB_DT_INTERFACE_SIZE,
+ .bDescriptorType = USB_DT_INTERFACE,
+ .bInterfaceNumber = 1,
+ .bAlternateSetting = 0,
+ .bNumEndpoints = 2,
+ .bInterfaceClass = USB_CLASS_DATA,
+ .bInterfaceSubClass = 0,
+ .bInterfaceProtocol = 0,
+ .iInterface = 0,
+
+ .endpoint = data_endp,
+}};
+
+static const struct usb_interface ifaces[] = {{
+ .num_altsetting = 1,
+ .altsetting = comm_iface,
+}, {
+ .num_altsetting = 1,
+ .altsetting = data_iface,
+}};
+
+static const struct usb_config_descriptor config = {
+ .bLength = USB_DT_CONFIGURATION_SIZE,
+ .bDescriptorType = USB_DT_CONFIGURATION,
+ .wTotalLength = 0,
+ .bNumInterfaces = 2,
+ .bConfigurationValue = 1,
+ .iConfiguration = 0,
+ .bmAttributes = 0x80,
+ .bMaxPower = 0x32,
+
+ .interface = ifaces,
+};
+
+static const char *usb_strings[] = {
+ "x",
+ "Black Sphere Technologies",
+ "CDC-ACM Demo",
+ "DEMO"
+};
+
+static int cdcacm_control_command(struct usb_setup_data *req,
+ void (**complete)(struct usb_setup_data *req))
+{
+ (void)complete;
+ char buf[10];
+ struct usb_cdc_notification *notif = (void*)buf;
+
+ switch(req->bRequest) {
+ case USB_CDC_REQ_SET_CONTROL_LINE_STATE:
+ /* This Linux cdc_acm driver requires this to be implemented
+ * even though it's optional in the CDC spec, and we don't
+ * advertise it in the ACM functional descriptor. */
+
+ /* We echo signals back to host as notification */
+ notif->bmRequestType = 0xA1;
+ notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE;
+ notif->wValue = 0;
+ notif->wIndex = 0;
+ notif->wLength = 2;
+ buf[8] = req->wValue & 3;
+ 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))
+ return 0;
+
+ return 1;
+ }
+ return 0;
+}
+
+static void cdcacm_data_rx_cb(u8 ep)
+{
+ (void)ep;
+
+ char buf[64];
+ int len = usbd_ep_read_packet(0x01, buf, 64);
+ if(len) {
+ usbd_ep_write_packet(0x82, buf, len);
+ buf[len] = 0;
+ }
+}
+
+static void cdcacm_set_config(u16 wValue)
+{
+ (void)wValue;
+
+ usbd_ep_setup(0x01, USB_ENDPOINT_ATTR_BULK, 64, cdcacm_data_rx_cb);
+ 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);
+}
+
+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(cdcacm_set_config);
+
+ {int i; for (i=0;i<0x80000;i++);}
+ gpio_clear(GPIOC, GPIO11);
+
+ while (1)
+ usbd_poll();
+}
+
diff --git a/examples/stm32-h103/usb_cdcacm/cdcacm.ld b/examples/stm32-h103/usb_cdcacm/cdcacm.ld
new file mode 100644
index 0000000..a393e0b
--- /dev/null
+++ b/examples/stm32-h103/usb_cdcacm/cdcacm.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/usbstd.h b/include/usbstd.h
index 81316b8..7c4cd37 100644
--- a/include/usbstd.h
+++ b/include/usbstd.h
@@ -45,6 +45,10 @@ struct usb_setup_data {
#define USB_REQ_TYPE_INTERFACE 0x01
#define USB_REQ_TYPE_ENDPOINT 0x02
+#define USB_REQ_TYPE_DIRECTION 0x80
+#define USB_REQ_TYPE_TYPE 0x60
+#define USB_REQ_TYPE_RECIPIENT 0x1F
+
/* USB Standard Request Codes - Table 9-4 */
#define USB_REQ_GET_STATUS 0
#define USB_REQ_CLEAR_FEATURE 1
@@ -71,9 +75,9 @@ struct usb_setup_data {
#define USB_DT_INTERFACE_POWER 8
/* USB Standard Feature Selectors - Table 9-6 */
-#define USB_FEAT_DEVICE_REMOTE_WAKEUP 1
#define USB_FEAT_ENDPOINT_HALT 0
-#define USB_FEAT_TEST_MOED 2
+#define USB_FEAT_DEVICE_REMOTE_WAKEUP 1
+#define USB_FEAT_TEST_MODE 2
/* Information Returned by a GetStatus() Request to a Device - Figure 9-4 */
#define USB_DEV_STATUS_SELF_POWERED 0x01
diff --git a/lib/usb/usb_control.c b/lib/usb/usb_control.c
index d656a0c..950e491 100644
--- a/lib/usb/usb_control.c
+++ b/lib/usb/usb_control.c
@@ -106,6 +106,10 @@ static void usb_control_setup_nodata(struct usb_setup_data *req)
{
int result = 0;
+ /* Buffer unused */
+ control_state.ctrl_buf = _usbd_device.ctrl_buf;
+ control_state.ctrl_len = 0;
+
/* Call user command hook function */
if(_usbd_device.user_callback_control_command)
result = _usbd_device.user_callback_control_command(req,
@@ -113,7 +117,9 @@ static void usb_control_setup_nodata(struct usb_setup_data *req)
/* Try standard command if not already handled */
if(!result)
- result = _usbd_standard_request_command(req);
+ result = _usbd_standard_request(req,
+ &control_state.ctrl_buf,
+ &control_state.ctrl_len);
if(result) {
/* Go to status stage if handled */
@@ -141,7 +147,7 @@ static void usb_control_setup_read(struct usb_setup_data *req)
/* Try standard request if not already handled */
if(!result)
- result = _usbd_standard_request_read(req,
+ result = _usbd_standard_request(req,
&control_state.ctrl_buf,
&control_state.ctrl_len);
@@ -218,10 +224,10 @@ void _usbd_control_out(uint8_t ea)
&control_state.complete);
if(!result)
- result = _usbd_standard_request_write(
+ result = _usbd_standard_request(
&control_state.req,
- control_state.ctrl_buf,
- control_state.ctrl_len);
+ &control_state.ctrl_buf,
+ &control_state.ctrl_len);
if(result) {
usbd_ep_write_packet(0, NULL, 0);
diff --git a/lib/usb/usb_f103.c b/lib/usb/usb_f103.c
index e4cf06e..1af4493 100644
--- a/lib/usb/usb_f103.c
+++ b/lib/usb/usb_f103.c
@@ -116,7 +116,22 @@ void usbd_ep_stall(u8 addr)
if(addr & 0x80)
USB_SET_EP_TX_STAT(addr, USB_EP_TX_STAT_STALL);
else
- USB_SET_EP_RX_STAT(addr & 0x7F, USB_EP_RX_STAT_STALL);
+ USB_SET_EP_RX_STAT(addr&0x7F, USB_EP_RX_STAT_STALL);
+}
+
+u8 usbd_get_ep_stall(u8 addr)
+{
+ if(addr == 0)
+ if ((*USB_EP_REG(addr) & USB_EP_TX_STAT) == USB_EP_TX_STAT_STALL)
+ return 1;
+ if(addr & 0x80) {
+ if ((*USB_EP_REG(addr) & USB_EP_TX_STAT) == USB_EP_TX_STAT_STALL)
+ return 1;
+ } else {
+ if ((*USB_EP_REG(addr&0x7F) & USB_EP_RX_STAT) == USB_EP_RX_STAT_STALL)
+ return 1;
+ }
+ return 0;
}
/** Copy a data buffer to Packet Memory.
diff --git a/lib/usb/usb_private.h b/lib/usb/usb_private.h
index f0c6a89..6cbc576 100644
--- a/lib/usb/usb_private.h
+++ b/lib/usb/usb_private.h
@@ -67,11 +67,8 @@ void _usbd_control_in(uint8_t ea);
void _usbd_control_out(uint8_t ea);
void _usbd_control_setup(uint8_t ea);
-int _usbd_standard_request_command(struct usb_setup_data *req);
-int _usbd_standard_request_read(struct usb_setup_data *req,
+int _usbd_standard_request(struct usb_setup_data *req,
uint8_t **buf, uint16_t *len);
-int _usbd_standard_request_write(struct usb_setup_data *req,
- uint8_t *buf, uint16_t len);
void _usbd_reset(void);
diff --git a/lib/usb/usb_standard.c b/lib/usb/usb_standard.c
index 0bfc7d8..ae6c2ee 100644
--- a/lib/usb/usb_standard.c
+++ b/lib/usb/usb_standard.c
@@ -115,8 +115,13 @@ static int usb_standard_get_descriptor(struct usb_setup_data *req,
return 0;
}
-static int usb_standard_set_address(struct usb_setup_data *req)
+static int usb_standard_set_address(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len)
{
+ (void)req;
+ (void)buf;
+ (void)len;
+
/* The actual address is only latched at the STATUS IN stage */
if((req->bmRequestType != 0) || (req->wValue >= 128)) return 0;
@@ -125,8 +130,13 @@ static int usb_standard_set_address(struct usb_setup_data *req)
return 1;
}
-static int usb_standard_set_configuration(struct usb_setup_data *req)
+static int usb_standard_set_configuration(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len)
{
+ (void)req;
+ (void)buf;
+ (void)len;
+
/* Is this correct, or should we reset alternate settings */
if(req->wValue == _usbd_device.current_config) return 1;
@@ -152,19 +162,38 @@ static int usb_standard_get_configuration(struct usb_setup_data *req,
return 1;
}
-static int usb_standard_set_interface(struct usb_setup_data *req)
+static int usb_standard_set_interface(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len)
{
(void)req;
- /* FIXME: Do something meaningful here: call app */
+ (void)buf;
+
+ /* FIXME: adapt if we have more than one interface */
+ if(req->wValue != 0) return 0;
+ *len = 0;
+
return 1;
}
-static int usb_standard_get_status(struct usb_setup_data *req, uint8_t **buf,
- uint16_t *len)
+static int usb_standard_get_interface(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len)
{
(void)req;
- /* FIXME: Return some meaningful status */
+ (void)buf;
+
+ /* FIXME: adapt if we have more than one interface */
+ *len = 1;
+ (*buf)[0] = 0;
+
+ return 1;
+}
+static int usb_standard_device_get_status(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len)
+{
+ (void)req;
+ /* bit 0: self powered */
+ /* bit 1: remote wakeup */
if(*len > 2) *len = 2;
(*buf)[0] = 0;
(*buf)[1] = 0;
@@ -172,18 +201,68 @@ static int usb_standard_get_status(struct usb_setup_data *req, uint8_t **buf,
return 1;
}
-int _usbd_standard_request_command(struct usb_setup_data *req)
+static int usb_standard_interface_get_status(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len)
{
- int (*command)(struct usb_setup_data *req) = NULL;
+ (void)req;
+ /* not defined */
- if((req->bmRequestType & 0x60) != USB_REQ_TYPE_STANDARD)
- return 0;
+ if(*len > 2) *len = 2;
+ (*buf)[0] = 0;
+ (*buf)[1] = 0;
+
+ return 1;
+}
+
+static int usb_standard_endpoint_get_status(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len)
+{
+ (void)req;
+
+ if(*len > 2) *len = 2;
+ (*buf)[0] = usbd_get_ep_stall(req->wIndex);
+ (*buf)[1] = 0;
+
+ return 1;
+}
+
+static int usb_standard_endpoint_stall(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len)
+{
+ (void)buf;
+ (void)len;
+
+ usbd_ep_stall(req->wIndex);
+
+ return 1;
+}
+
+static int usb_standard_endpoint_unstall(struct usb_setup_data *req,
+ uint8_t **buf, uint16_t *len)
+{
+ (void)buf;
+ (void)len;
+
+ usbd_ep_stall(req->wIndex);
+
+ return 1;
+}
+
+int _usbd_standard_request_device(struct usb_setup_data *req, uint8_t **buf,
+ uint16_t *len)
+{
+ int (*command)(struct usb_setup_data *req, uint8_t **buf,
+ uint16_t *len) = NULL;
switch(req->bRequest) {
case USB_REQ_CLEAR_FEATURE:
- /* FIXME: Implement CLEAR_FEATURE */
- /* TODO: Check what standard features are.
- * Maybe this is the application's responsibility. */
+ case USB_REQ_SET_FEATURE:
+ if (req->wValue == USB_FEAT_DEVICE_REMOTE_WAKEUP) {
+ /* device wakeup code goes here */
+ }
+ if (req->wValue == USB_FEAT_TEST_MODE) {
+ /* test mode code goes here */
+ }
break;
case USB_REQ_SET_ADDRESS:
/* SET ADDRESS is an exception.
@@ -193,45 +272,46 @@ int _usbd_standard_request_command(struct usb_setup_data *req)
case USB_REQ_SET_CONFIGURATION:
command = usb_standard_set_configuration;
break;
- case USB_REQ_SET_FEATURE:
- /* FIXME: Implement SET_FEATURE */
- /* TODO: Check what standard features are.
- * Maybe this is the application's responsibility. */
+ case USB_REQ_GET_CONFIGURATION:
+ command = usb_standard_get_configuration;
break;
- case USB_REQ_SET_INTERFACE:
- command = usb_standard_set_interface;
+ case USB_REQ_GET_DESCRIPTOR:
+ command = usb_standard_get_descriptor;
+ break;
+ case USB_REQ_GET_STATUS:
+ /* GET_STATUS always responds with zero reply.
+ * The application may override this behaviour. */
+ command = usb_standard_device_get_status;
+ break;
+ case USB_REQ_SET_DESCRIPTOR:
+ /* SET_DESCRIPTOR is optional and not implemented. */
break;
}
if(!command) return 0;
- return command(req);
+ return command(req, buf, len);
}
-int _usbd_standard_request_read(struct usb_setup_data *req, uint8_t **buf,
+int _usbd_standard_request_interface(struct usb_setup_data *req, uint8_t **buf,
uint16_t *len)
{
int (*command)(struct usb_setup_data *req, uint8_t **buf,
uint16_t *len) = NULL;
- /* Handle standard requests */
- if((req->bmRequestType & 0x60) != USB_REQ_TYPE_STANDARD)
- return 0;
-
switch(req->bRequest) {
- case USB_REQ_GET_CONFIGURATION:
- command = usb_standard_get_configuration;
- break;
- case USB_REQ_GET_DESCRIPTOR:
- command = usb_standard_get_descriptor;
+ case USB_REQ_CLEAR_FEATURE:
+ case USB_REQ_SET_FEATURE:
+ /* not defined */
break;
case USB_REQ_GET_INTERFACE:
- /* FIXME: Implement GET_INTERFACE */
+ command = usb_standard_get_interface;
+ break;
+ case USB_REQ_SET_INTERFACE:
+ command = usb_standard_set_interface;
break;
case USB_REQ_GET_STATUS:
- /* GET_STATUS always responds with zero reply.
- * The application may override this behaviour. */
- command = usb_standard_get_status;
+ command = usb_standard_interface_get_status;
break;
}
@@ -240,19 +320,25 @@ int _usbd_standard_request_read(struct usb_setup_data *req, uint8_t **buf,
return command(req, buf, len);
}
-int _usbd_standard_request_write(struct usb_setup_data *req, uint8_t *buf,
- uint16_t len)
+int _usbd_standard_request_endpoint(struct usb_setup_data *req, uint8_t **buf,
+ uint16_t *len)
{
- int (*command)(struct usb_setup_data *req, uint8_t *buf, uint16_t len)
- = NULL;
-
- /* Handle standard requests */
- if((req->bmRequestType & 0x60) != USB_REQ_TYPE_STANDARD)
- return 0;
+ int (*command)(struct usb_setup_data *req, uint8_t **buf,
+ uint16_t *len) = NULL;
switch(req->bRequest) {
- case USB_REQ_SET_DESCRIPTOR:
- /* SET_DESCRIPTOR is optional and not implemented. */
+ case USB_REQ_CLEAR_FEATURE:
+ if (req->wValue == USB_FEAT_ENDPOINT_HALT) {
+ command = usb_standard_endpoint_stall;
+ }
+ break;
+ case USB_REQ_SET_FEATURE:
+ if (req->wValue == USB_FEAT_ENDPOINT_HALT) {
+ command = usb_standard_endpoint_unstall;
+ }
+ break;
+ case USB_REQ_GET_STATUS:
+ command = usb_standard_endpoint_get_status;
break;
case USB_REQ_SET_SYNCH_FRAME:
/* FIXME: SYNCH_FRAME is not implemented. */
@@ -266,3 +352,22 @@ int _usbd_standard_request_write(struct usb_setup_data *req, uint8_t *buf,
return command(req, buf, len);
}
+int _usbd_standard_request(struct usb_setup_data *req, uint8_t **buf,
+ uint16_t *len)
+{
+ /* FIXME: have class/vendor requests as well */
+ if((req->bmRequestType & USB_REQ_TYPE_TYPE) != USB_REQ_TYPE_STANDARD)
+ return 0;
+
+ switch (req->bmRequestType & USB_REQ_TYPE_RECIPIENT) {
+ case USB_REQ_TYPE_DEVICE:
+ return _usbd_standard_request_device(req, buf, len);
+ case USB_REQ_TYPE_INTERFACE:
+ return _usbd_standard_request_interface(req, buf, len);
+ case USB_REQ_TYPE_ENDPOINT:
+ return _usbd_standard_request_endpoint(req, buf, len);
+ default:
+ return 0;
+ }
+}
+