diff --git a/include/libopencm3/stm32/usb.h b/include/libopencm3/stm32/common/st_usbfs_common.h
similarity index 82%
rename from include/libopencm3/stm32/usb.h
rename to include/libopencm3/stm32/common/st_usbfs_common.h
index 3e09b7e1..874aa503 100644
--- a/include/libopencm3/stm32/usb.h
+++ b/include/libopencm3/stm32/common/st_usbfs_common.h
@@ -1,8 +1,8 @@
-/** @defgroup adc_defines USB Defines
+/** @defgroup usb_defines USB Defines
-@brief Defined Constants and Types for the STM32F1xx USB Module
+@brief Defined Constants and Types for the STM32F* USB drivers
-@ingroup STM32F1xx_defines
+@ingroup STM32Fx_defines
@version 1.0.0
@@ -32,15 +32,28 @@ LGPL License Terms @ref lgpl_license
* along with this library. If not, see .
*/
+/* THIS FILE SHOULD NOT BE INCLUDED DIRECTLY !
+ * Use top-level
+ */
+
/**@{*/
-#ifndef LIBOPENCM3_USB_H
-#define LIBOPENCM3_USB_H
+/** @cond */
+#ifdef LIBOPENCM3_ST_USBFS_H
+/** @endcond */
+#ifndef LIBOPENCM3_ST_USBFS_COMMON_H
+#define LIBOPENCM3_ST_USBFS_COMMON_H
-#include
-#include
#include
+/*****************************************************************************/
+/* Module definitions */
+/*****************************************************************************/
+
+/*****************************************************************************/
+/* Register definitions */
+/*****************************************************************************/
+
/* --- USB general registers ----------------------------------------------- */
/* USB Control register */
@@ -54,14 +67,14 @@ LGPL License Terms @ref lgpl_license
/* USB Buffer table address register */
#define USB_BTABLE_REG (&MMIO32(USB_DEV_FS_BASE + 0x50))
-/* Link Power Management register */
-#define USB_LPMCSR_REG (&MMIO32(USB_DEV_FS_BASE + 0x54))
-/* Battery Charge Detection register */
-#define USB_BCDR_REG (&MMIO32(USB_DEV_FS_BASE + 0x58))
-
/* USB EP register */
#define USB_EP_REG(EP) (&MMIO32(USB_DEV_FS_BASE) + (EP))
+
+/*****************************************************************************/
+/* Register values */
+/*****************************************************************************/
+
/* --- USB control register masks / bits ----------------------------------- */
/* Interrupt mask bits, set to 1 to enable interrupt generation */
@@ -75,8 +88,6 @@ LGPL License Terms @ref lgpl_license
#define USB_CNTR_ESOFM 0x0100
/* Request/Force bits */
-#define USB_CNTR_L1REQM 0x0080 /* F0 port */
-#define USB_CNTR_L1RESUME 0x0020 /* F0 port */
#define USB_CNTR_RESUME 0x0010 /* Resume request */
#define USB_CNTR_FSUSP 0x0008 /* Force suspend */
#define USB_CNTR_LP_MODE 0x0004 /* Low-power mode */
@@ -93,7 +104,6 @@ LGPL License Terms @ref lgpl_license
#define USB_ISTR_RESET 0x0400 /* USB RESET request */
#define USB_ISTR_SOF 0x0200 /* Start Of Frame */
#define USB_ISTR_ESOF 0x0100 /* Expected Start Of Frame */
-#define USB_ISTR_L1REQ 0x0080
#define USB_ISTR_DIR 0x0010 /* Direction of transaction */
#define USB_ISTR_EP_ID 0x000F /* Endpoint Identifier */
@@ -108,7 +118,7 @@ LGPL License Terms @ref lgpl_license
#define USB_CLR_ISTR_SOF() CLR_REG_BIT(USB_ISTR_REG, USB_ISTR_SOF)
#define USB_CLR_ISTR_ESOF() CLR_REG_BIT(USB_ISTR_REG, USB_ISTR_ESOF)
-/* USB Frame Number Register bits ------------------------------------------ */
+/* --- USB Frame Number Register bits -------------------------------------- */
#define USB_FNR_RXDP (1 << 15)
#define USB_FNR_RXDM (1 << 14)
@@ -121,27 +131,12 @@ LGPL License Terms @ref lgpl_license
/* --- USB device address register masks / bits ---------------------------- */
-#define USB_DADDR_EF 0x0080
+#define USB_DADDR_EF (1 << 7)
#define USB_DADDR_ADDR 0x007F
-/* --- USB Link Power Management control/status register masks / bits ------ */
-#define USB_LPMCSR_BESL_SHIFT 4
-#define USB_LPMCSR_BESL (15 << USB_LPMCSR_BESL_SHIFT)
+/* USB_BTABLE Values ------------------------------------------------------- */
-#define USB_LPMCSR_REMWAKE (1 << 3)
-#define USB_LPMCSR_LPMACK (1 << 1)
-#define USB_LPMCSR_LPMEN (1 << 0)
-
-/* --- USB Battery Charge Detection register masks / bits ------ */
-#define USB_BCDR_DPPU (1 << 15)
-#define USB_BCDR_PS2DET (1 << 7)
-#define USB_BCDR_SDET (1 << 6)
-#define USB_BCDR_PDET (1 << 5)
-#define USB_BCDR_DCDET (1 << 4)
-#define USB_BCDR_SDEN (1 << 3)
-#define USB_BCDR_PDEN (1 << 2)
-#define USB_BCDR_DCDEN (1 << 1)
-#define USB_BCDR_BCDEN (1 << 0)
+#define USB_BTABLE_BTABLE 0xFFF8
/* --- USB device address register manipulators ---------------------------- */
@@ -240,6 +235,7 @@ LGPL License Terms @ref lgpl_license
#define USB_CLR_EP_TX_CTR(EP) \
USB_CLR_EP_NTOGGLE_BIT_AND_SET(EP, USB_EP_TX_CTR, USB_EP_RX_CTR)
+
#define USB_SET_EP_TYPE(EP, TYPE) \
SET_REG(USB_EP_REG(EP), \
(GET_REG(USB_EP_REG(EP)) & \
@@ -277,22 +273,11 @@ LGPL License Terms @ref lgpl_license
GET_REG(USB_EP_REG(EP)) & \
(USB_EP_NTOGGLE_MSK | USB_EP_RX_DTOG))
+
/* --- USB BTABLE registers ------------------------------------------------ */
#define USB_GET_BTABLE GET_REG(USB_BTABLE_REG)
-#define USB_EP_TX_ADDR(EP) \
- ((uint32_t *)(USB_PMA_BASE + (USB_GET_BTABLE + EP * 8 + 0) * 2))
-
-#define USB_EP_TX_COUNT(EP) \
- ((uint32_t *)(USB_PMA_BASE + (USB_GET_BTABLE + EP * 8 + 2) * 2))
-
-#define USB_EP_RX_ADDR(EP) \
- ((uint32_t *)(USB_PMA_BASE + (USB_GET_BTABLE + EP * 8 + 4) * 2))
-
-#define USB_EP_RX_COUNT(EP) \
- ((uint32_t *)(USB_PMA_BASE + (USB_GET_BTABLE + EP * 8 + 6) * 2))
-
/* --- USB BTABLE manipulators --------------------------------------------- */
#define USB_GET_EP_TX_ADDR(EP) GET_REG(USB_EP_TX_ADDR(EP))
@@ -304,13 +289,14 @@ LGPL License Terms @ref lgpl_license
#define USB_SET_EP_RX_ADDR(EP, ADDR) SET_REG(USB_EP_RX_ADDR(EP), ADDR)
#define USB_SET_EP_RX_COUNT(EP, COUNT) SET_REG(USB_EP_RX_COUNT(EP), COUNT)
-#define USB_GET_EP_TX_BUFF(EP) \
- (USB_PMA_BASE + (uint8_t *)(USB_GET_EP_TX_ADDR(EP) * 2))
-#define USB_GET_EP_RX_BUFF(EP) \
- (USB_PMA_BASE + (uint8_t *)(USB_GET_EP_RX_ADDR(EP) * 2))
-
-#endif
/**@}*/
+#endif
+/** @cond */
+#else
+#error "st_usbfs_common.h should not be included explicitly, only via st_usbfs.h"
+#endif
+/** @endcond */
+
diff --git a/include/libopencm3/stm32/common/st_usbfs_v1.h b/include/libopencm3/stm32/common/st_usbfs_v1.h
new file mode 100644
index 00000000..7a5a0459
--- /dev/null
+++ b/include/libopencm3/stm32/common/st_usbfs_v1.h
@@ -0,0 +1,67 @@
+/** @addtogroup usb_defines
+ */
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see .
+ */
+
+/* THIS FILE SHOULD NOT BE INCLUDED DIRECTLY !
+ * Use top-level
+ *
+ * Additional definitions for F1, F3, L1 devices:
+ * -F102, F103 (RM0008)
+ * -F302x{B,C}; *NOT* F302x{6,8,D,E} !! (USB_BTABLE access issues) (RM0365)
+ * -F303x{B,C}; *NOT* F303x{D,E} !! (USB_BTABLE access issues) (RM0316)
+ * -F37x (RM0313)
+ * -L1xx (RM0038)
+ */
+
+/** @cond */
+#ifdef LIBOPENCM3_ST_USBFS_H
+/** @endcond */
+#ifndef LIBOPENCM3_ST_USBFS_V1_H
+#define LIBOPENCM3_ST_USBFS_V1_H
+
+#include
+
+/* --- USB BTABLE Registers ------------------------------------------------ */
+
+#define USB_EP_TX_ADDR(EP) \
+ ((uint32_t *)(USB_PMA_BASE + (USB_GET_BTABLE + EP * 8 + 0) * 2))
+
+#define USB_EP_TX_COUNT(EP) \
+ ((uint32_t *)(USB_PMA_BASE + (USB_GET_BTABLE + EP * 8 + 2) * 2))
+
+#define USB_EP_RX_ADDR(EP) \
+ ((uint32_t *)(USB_PMA_BASE + (USB_GET_BTABLE + EP * 8 + 4) * 2))
+
+#define USB_EP_RX_COUNT(EP) \
+ ((uint32_t *)(USB_PMA_BASE + (USB_GET_BTABLE + EP * 8 + 6) * 2))
+
+/* --- USB BTABLE manipulators --------------------------------------------- */
+
+#define USB_GET_EP_TX_BUFF(EP) \
+ (USB_PMA_BASE + (uint8_t *)(USB_GET_EP_TX_ADDR(EP) * 2))
+
+#define USB_GET_EP_RX_BUFF(EP) \
+ (USB_PMA_BASE + (uint8_t *)(USB_GET_EP_RX_ADDR(EP) * 2))
+
+#endif
+/** @cond */
+#else
+#error "st_usbfs_v1.h should not be included directly, only via st_usbfs.h"
+#endif
+/** @endcond */
+
diff --git a/include/libopencm3/stm32/f1/st_usbfs.h b/include/libopencm3/stm32/f1/st_usbfs.h
new file mode 100644
index 00000000..7da73f2a
--- /dev/null
+++ b/include/libopencm3/stm32/f1/st_usbfs.h
@@ -0,0 +1,27 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see .
+ */
+/* THIS FILE SHOULD NOT BE INCLUDED DIRECTLY !
+ * Use top-level
+ */
+
+#ifndef LIBOPENCM3_ST_USBFS_H
+# error Do not include directly !
+#else
+
+#include
+
+#endif
diff --git a/include/libopencm3/stm32/f3/st_usbfs.h b/include/libopencm3/stm32/f3/st_usbfs.h
new file mode 100644
index 00000000..7da73f2a
--- /dev/null
+++ b/include/libopencm3/stm32/f3/st_usbfs.h
@@ -0,0 +1,27 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see .
+ */
+/* THIS FILE SHOULD NOT BE INCLUDED DIRECTLY !
+ * Use top-level
+ */
+
+#ifndef LIBOPENCM3_ST_USBFS_H
+# error Do not include directly !
+#else
+
+#include
+
+#endif
diff --git a/include/libopencm3/stm32/l1/st_usbfs.h b/include/libopencm3/stm32/l1/st_usbfs.h
new file mode 100644
index 00000000..7da73f2a
--- /dev/null
+++ b/include/libopencm3/stm32/l1/st_usbfs.h
@@ -0,0 +1,27 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see .
+ */
+/* THIS FILE SHOULD NOT BE INCLUDED DIRECTLY !
+ * Use top-level
+ */
+
+#ifndef LIBOPENCM3_ST_USBFS_H
+# error Do not include directly !
+#else
+
+#include
+
+#endif
diff --git a/include/libopencm3/stm32/st_usbfs.h b/include/libopencm3/stm32/st_usbfs.h
new file mode 100644
index 00000000..6befced9
--- /dev/null
+++ b/include/libopencm3/stm32/st_usbfs.h
@@ -0,0 +1,36 @@
+/* This provides unification of USB code for supported STM32F subfamilies */
+
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see .
+ */
+
+#ifndef LIBOPENCM3_ST_USBFS_H
+#define LIBOPENCM3_ST_USBFS_H
+
+#include
+#include
+
+#if defined(STM32F1)
+# include
+#elif defined(STM32F3)
+# include
+#elif defined(STM32L1)
+# include
+#else
+# error "STM32 family not defined or not supported."
+#endif
+
+#endif
diff --git a/include/libopencm3/usb/usbd.h b/include/libopencm3/usb/usbd.h
index 274710c2..e2447c38 100644
--- a/include/libopencm3/usb/usbd.h
+++ b/include/libopencm3/usb/usbd.h
@@ -52,7 +52,7 @@ enum usbd_request_return_codes {
typedef struct _usbd_driver usbd_driver;
typedef struct _usbd_device usbd_device;
-extern const usbd_driver stm32f103_usb_driver;
+extern const usbd_driver st_usbfs_v1_usb_driver;
extern const usbd_driver stm32f107_usb_driver;
extern const usbd_driver stm32f207_usb_driver;
#define otgfs_usb_driver stm32f107_usb_driver
diff --git a/lib/usb/usb_f103.c b/lib/stm32/common/st_usbfs_core.c
similarity index 55%
rename from lib/usb/usb_f103.c
rename to lib/stm32/common/st_usbfs_core.c
index de3032eb..081839d3 100644
--- a/lib/usb/usb_f103.c
+++ b/lib/stm32/common/st_usbfs_core.c
@@ -2,6 +2,7 @@
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Gareth McMullin
+ * Copyright (C) 2015 Robin Kreis
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
@@ -20,59 +21,16 @@
#include
#include
#include
-#include
+#include
#include
-#include "usb_private.h"
+#include "../../usb/usb_private.h"
+#include "st_usbfs_core.h"
-static usbd_device *stm32f103_usbd_init(void);
-static void stm32f103_set_address(usbd_device *usbd_dev, uint8_t addr);
-static void stm32f103_ep_setup(usbd_device *usbd_dev, uint8_t addr,
- uint8_t type, uint16_t max_size,
- void (*callback) (usbd_device *usbd_dev,
- uint8_t ep));
-static void stm32f103_endpoints_reset(usbd_device *usbd_dev);
-static void stm32f103_ep_stall_set(usbd_device *usbd_dev, uint8_t addr,
- uint8_t stall);
-static uint8_t stm32f103_ep_stall_get(usbd_device *usbd_dev, uint8_t addr);
-static void stm32f103_ep_nak_set(usbd_device *usbd_dev, uint8_t addr,
- uint8_t nak);
-static uint16_t stm32f103_ep_write_packet(usbd_device *usbd_dev, uint8_t addr,
- const void *buf, uint16_t len);
-static uint16_t stm32f103_ep_read_packet(usbd_device *usbd_dev, uint8_t addr,
- void *buf, uint16_t len);
-static void stm32f103_poll(usbd_device *usbd_dev);
+/* TODO - can't these be inside the impls, not globals from the core? */
+uint8_t st_usbfs_force_nak[8];
+struct _usbd_device st_usbfs_dev;
-static uint8_t force_nak[8];
-static struct _usbd_device usbd_dev;
-
-const struct _usbd_driver stm32f103_usb_driver = {
- .init = stm32f103_usbd_init,
- .set_address = stm32f103_set_address,
- .ep_setup = stm32f103_ep_setup,
- .ep_reset = stm32f103_endpoints_reset,
- .ep_stall_set = stm32f103_ep_stall_set,
- .ep_stall_get = stm32f103_ep_stall_get,
- .ep_nak_set = stm32f103_ep_nak_set,
- .ep_write_packet = stm32f103_ep_write_packet,
- .ep_read_packet = stm32f103_ep_read_packet,
- .poll = stm32f103_poll,
-};
-
-/** Initialize the USB device controller hardware of the STM32. */
-static usbd_device *stm32f103_usbd_init(void)
-{
- rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
- SET_REG(USB_CNTR_REG, 0);
- SET_REG(USB_BTABLE_REG, 0);
- SET_REG(USB_ISTR_REG, 0);
-
- /* Enable RESET, SUSPEND, RESUME and CTR interrupts. */
- SET_REG(USB_CNTR_REG, USB_CNTR_RESETM | USB_CNTR_CTRM |
- USB_CNTR_SUSPM | USB_CNTR_WKUPM);
- return &usbd_dev;
-}
-
-static void stm32f103_set_address(usbd_device *dev, uint8_t addr)
+void st_usbfs_set_address(usbd_device *dev, uint8_t addr)
{
(void)dev;
/* Set device address and enable. */
@@ -85,7 +43,7 @@ static void stm32f103_set_address(usbd_device *dev, uint8_t addr)
* @param ep Index of endpoint to configure.
* @param size Size in bytes of the RX buffer.
*/
-static void usb_set_ep_rx_bufsize(usbd_device *dev, uint8_t ep, uint32_t size)
+void st_usbfs_set_ep_rx_bufsize(usbd_device *dev, uint8_t ep, uint32_t size)
{
(void)dev;
if (size > 62) {
@@ -101,10 +59,10 @@ static void usb_set_ep_rx_bufsize(usbd_device *dev, uint8_t ep, uint32_t size)
}
}
-static void stm32f103_ep_setup(usbd_device *dev, uint8_t addr, uint8_t type,
- uint16_t max_size,
- void (*callback) (usbd_device *usbd_dev,
- uint8_t ep))
+void st_usbfs_ep_setup(usbd_device *dev, uint8_t addr, uint8_t type,
+ uint16_t max_size,
+ void (*callback) (usbd_device *usbd_dev,
+ uint8_t ep))
{
/* Translate USB standard type codes to STM32. */
const uint16_t typelookup[] = {
@@ -133,7 +91,7 @@ static void stm32f103_ep_setup(usbd_device *dev, uint8_t addr, uint8_t type,
if (!dir) {
USB_SET_EP_RX_ADDR(addr, dev->pm_top);
- usb_set_ep_rx_bufsize(dev, addr, max_size);
+ st_usbfs_set_ep_rx_bufsize(dev, addr, max_size);
if (callback) {
dev->user_callback_ctr[addr][USB_TRANSACTION_OUT] =
(void *)callback;
@@ -144,7 +102,7 @@ static void stm32f103_ep_setup(usbd_device *dev, uint8_t addr, uint8_t type,
}
}
-static void stm32f103_endpoints_reset(usbd_device *dev)
+void st_usbfs_endpoints_reset(usbd_device *dev)
{
int i;
@@ -153,10 +111,10 @@ static void stm32f103_endpoints_reset(usbd_device *dev)
USB_SET_EP_TX_STAT(i, USB_EP_TX_STAT_DISABLED);
USB_SET_EP_RX_STAT(i, USB_EP_RX_STAT_DISABLED);
}
- dev->pm_top = 0x40 + (2 * dev->desc->bMaxPacketSize0);
+ dev->pm_top = USBD_PM_TOP + (2 * dev->desc->bMaxPacketSize0);
}
-static void stm32f103_ep_stall_set(usbd_device *dev, uint8_t addr,
+void st_usbfs_ep_stall_set(usbd_device *dev, uint8_t addr,
uint8_t stall)
{
(void)dev;
@@ -186,7 +144,7 @@ static void stm32f103_ep_stall_set(usbd_device *dev, uint8_t addr,
}
}
-static uint8_t stm32f103_ep_stall_get(usbd_device *dev, uint8_t addr)
+uint8_t st_usbfs_ep_stall_get(usbd_device *dev, uint8_t addr)
{
(void)dev;
if (addr & 0x80) {
@@ -203,7 +161,7 @@ static uint8_t stm32f103_ep_stall_get(usbd_device *dev, uint8_t addr)
return 0;
}
-static void stm32f103_ep_nak_set(usbd_device *dev, uint8_t addr, uint8_t nak)
+void st_usbfs_ep_nak_set(usbd_device *dev, uint8_t addr, uint8_t nak)
{
(void)dev;
/* It does not make sence to force NAK on IN endpoints. */
@@ -211,7 +169,7 @@ static void stm32f103_ep_nak_set(usbd_device *dev, uint8_t addr, uint8_t nak)
return;
}
- force_nak[addr] = nak;
+ st_usbfs_force_nak[addr] = nak;
if (nak) {
USB_SET_EP_RX_STAT(addr, USB_EP_RX_STAT_NAK);
@@ -220,24 +178,7 @@ static void stm32f103_ep_nak_set(usbd_device *dev, uint8_t addr, uint8_t nak)
}
}
-/**
- * Copy a data buffer to packet memory.
- *
- * @param vPM Destination pointer into packet memory.
- * @param buf Source pointer to data buffer.
- * @param len Number of bytes to copy.
- */
-static void usb_copy_to_pm(volatile void *vPM, const void *buf, uint16_t len)
-{
- const uint16_t *lbuf = buf;
- volatile uint16_t *PM = vPM;
-
- for (len = (len + 1) >> 1; len; PM += 2, lbuf++, len--) {
- *PM = *lbuf;
- }
-}
-
-static uint16_t stm32f103_ep_write_packet(usbd_device *dev, uint8_t addr,
+uint16_t st_usbfs_ep_write_packet(usbd_device *dev, uint8_t addr,
const void *buf, uint16_t len)
{
(void)dev;
@@ -247,36 +188,14 @@ static uint16_t stm32f103_ep_write_packet(usbd_device *dev, uint8_t addr,
return 0;
}
- usb_copy_to_pm(USB_GET_EP_TX_BUFF(addr), buf, len);
+ st_usbfs_copy_to_pm(USB_GET_EP_TX_BUFF(addr), buf, len);
USB_SET_EP_TX_COUNT(addr, len);
USB_SET_EP_TX_STAT(addr, USB_EP_TX_STAT_VALID);
return len;
}
-/**
- * Copy a data buffer from packet memory.
- *
- * @param buf Source pointer to data buffer.
- * @param vPM Destination pointer into packet memory.
- * @param len Number of bytes to copy.
- */
-static void usb_copy_from_pm(void *buf, const volatile void *vPM, uint16_t len)
-{
- uint16_t *lbuf = buf;
- const volatile uint16_t *PM = vPM;
- uint8_t odd = len & 1;
-
- for (len >>= 1; len; PM += 2, lbuf++, len--) {
- *lbuf = *PM;
- }
-
- if (odd) {
- *(uint8_t *) lbuf = *(uint8_t *) PM;
- }
-}
-
-static uint16_t stm32f103_ep_read_packet(usbd_device *dev, uint8_t addr,
+uint16_t st_usbfs_ep_read_packet(usbd_device *dev, uint8_t addr,
void *buf, uint16_t len)
{
(void)dev;
@@ -285,34 +204,40 @@ static uint16_t stm32f103_ep_read_packet(usbd_device *dev, uint8_t addr,
}
len = MIN(USB_GET_EP_RX_COUNT(addr) & 0x3ff, len);
- usb_copy_from_pm(buf, USB_GET_EP_RX_BUFF(addr), len);
+ st_usbfs_copy_from_pm(buf, USB_GET_EP_RX_BUFF(addr), len);
USB_CLR_EP_RX_CTR(addr);
- if (!force_nak[addr]) {
+ if (!st_usbfs_force_nak[addr]) {
USB_SET_EP_RX_STAT(addr, USB_EP_RX_STAT_VALID);
}
return len;
}
-static void stm32f103_poll(usbd_device *dev)
+void st_usbfs_poll(usbd_device *dev)
{
uint16_t istr = *USB_ISTR_REG;
if (istr & USB_ISTR_RESET) {
USB_CLR_ISTR_RESET();
- dev->pm_top = 0x40;
+ dev->pm_top = USBD_PM_TOP;
_usbd_reset(dev);
return;
}
if (istr & USB_ISTR_CTR) {
uint8_t ep = istr & USB_ISTR_EP_ID;
- uint8_t type = (istr & USB_ISTR_DIR) ? 1 : 0;
+ uint8_t type;
- if (type) { /* OUT or SETUP transaction */
- type += (*USB_EP_REG(ep) & USB_EP_SETUP) ? 1 : 0;
- } else { /* IN transaction */
+ if (istr & USB_ISTR_DIR) {
+ /* OUT or SETUP? */
+ if (*USB_EP_REG(ep) & USB_EP_SETUP) {
+ type = USB_TRANSACTION_SETUP;
+ } else {
+ type = USB_TRANSACTION_OUT;
+ }
+ } else {
+ type = USB_TRANSACTION_IN;
USB_CLR_EP_TX_CTR(ep);
}
diff --git a/lib/stm32/common/st_usbfs_core.h b/lib/stm32/common/st_usbfs_core.h
new file mode 100644
index 00000000..c0467fff
--- /dev/null
+++ b/lib/stm32/common/st_usbfs_core.h
@@ -0,0 +1,74 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin
+ * Copyright (C) 2015 Robin Kreis
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see .
+ */
+
+/*
+ * This is a "private" header file for usbd implementations.
+ * As opposed to the "public" headers under include that describe the hardware,
+ * this is purely an implementation detail of usbd drivers.
+ */
+
+#ifndef ST_USBFS_CORE
+#define ST_USBFS_CORE
+
+#include
+#include
+
+#define USBD_PM_TOP 0x40
+
+void st_usbfs_set_address(usbd_device *dev, uint8_t addr);
+void st_usbfs_set_ep_rx_bufsize(usbd_device *dev, uint8_t ep, uint32_t size);
+
+void st_usbfs_ep_setup(usbd_device *usbd_dev, uint8_t addr,
+ uint8_t type, uint16_t max_size,
+ void (*callback) (usbd_device *usbd_dev,
+ uint8_t ep));
+
+void st_usbfs_endpoints_reset(usbd_device *usbd_dev);
+void st_usbfs_ep_stall_set(usbd_device *usbd_dev, uint8_t addr, uint8_t stall);
+uint8_t st_usbfs_ep_stall_get(usbd_device *usbd_dev, uint8_t addr);
+void st_usbfs_ep_nak_set(usbd_device *usbd_dev, uint8_t addr, uint8_t nak);
+uint16_t st_usbfs_ep_write_packet(usbd_device *usbd_dev, uint8_t addr, const void *buf, uint16_t len);
+uint16_t st_usbfs_ep_read_packet(usbd_device *usbd_dev, uint8_t addr, void *buf, uint16_t len);
+void st_usbfs_poll(usbd_device *usbd_dev);
+
+/* These must be implemented by the device specific driver */
+
+/**
+ * Copy a data buffer to packet memory.
+ *
+ * @param vPM Destination pointer into packet memory.
+ * @param buf Source pointer to data buffer.
+ * @param len Number of bytes to copy.
+ */
+void st_usbfs_copy_from_pm(void *buf, const volatile void *vPM, uint16_t len);
+
+/**
+ * Copy a data buffer from packet memory.
+ *
+ * @param vPM Destination pointer into packet memory.
+ * @param buf Source pointer to data buffer.
+ * @param len Number of bytes to copy.
+ */
+void st_usbfs_copy_to_pm(volatile void *vPM, const void *buf, uint16_t len);
+
+extern uint8_t st_usbfs_force_nak[8];
+extern struct _usbd_device st_usbfs_dev;
+
+#endif
diff --git a/lib/stm32/f1/Makefile b/lib/stm32/f1/Makefile
index a52e50ca..651c9fd8 100755
--- a/lib/stm32/f1/Makefile
+++ b/lib/stm32/f1/Makefile
@@ -46,8 +46,9 @@ OBJS += crc_common_all.o dac_common_all.o dma_common_l1f013.o \
rcc_common_all.o exti_common_all.o \
flash_common_f01.o
-OBJS += usb.o usb_control.o usb_standard.o usb_f103.o usb_f107.o \
- usb_fx07_common.o usb_msc.o
+OBJS += usb.o usb_control.o usb_standard.o usb_msc.o
+OBJS += usb_fx07_common.o usb_f107.o
+OBJS += st_usbfs_core.o st_usbfs_v1.o
VPATH += ../../usb:../:../../cm3:../common:../../ethernet
diff --git a/lib/stm32/f3/Makefile b/lib/stm32/f3/Makefile
index a8b1a75e..8ef009a5 100644
--- a/lib/stm32/f3/Makefile
+++ b/lib/stm32/f3/Makefile
@@ -44,7 +44,8 @@ OBJS += gpio_common_all.o gpio_common_f0234.o \
timer_common_all.o timer_common_f234.o flash_common_f234.o \
flash.o exti_common_all.o rcc_common_all.o spi_common_f03.o
-OBJS += usb.o usb_control.o usb_standard.o usb_f103.o
+OBJS += usb.o usb_control.o usb_standard.o
+OBJS += st_usbfs_core.o st_usbfs_v1.o
VPATH += ../../usb:../:../../cm3:../common
diff --git a/lib/stm32/l1/Makefile b/lib/stm32/l1/Makefile
index 3e719afb..2292b36c 100644
--- a/lib/stm32/l1/Makefile
+++ b/lib/stm32/l1/Makefile
@@ -44,9 +44,11 @@ OBJS += spi_common_all.o spi_common_l1f124.o timer_common_all.o
OBJS += usart_common_all.o usart_common_f124.o
OBJS += exti_common_all.o
OBJS += rcc_common_all.o
-OBJS += usb.o usb_control.o usb_standard.o usb_f103.o
OBJS += adc.o adc_common_v1.o
+OBJS += usb.o usb_control.o usb_standard.o
+OBJS += st_usbfs_core.o st_usbfs_v1.o
+
VPATH += ../../usb:../:../../cm3:../common
include ../../Makefile.include
diff --git a/lib/stm32/st_usbfs_v1.c b/lib/stm32/st_usbfs_v1.c
new file mode 100644
index 00000000..b6503596
--- /dev/null
+++ b/lib/stm32/st_usbfs_v1.c
@@ -0,0 +1,86 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2010 Gareth McMullin
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see .
+ */
+
+#include
+#include
+#include
+#include
+#include
+#include "../usb/usb_private.h"
+#include "common/st_usbfs_core.h"
+
+static usbd_device *st_usbfs_v1_usbd_init(void);
+
+const struct _usbd_driver st_usbfs_v1_usb_driver = {
+ .init = st_usbfs_v1_usbd_init,
+ .set_address = st_usbfs_set_address,
+ .ep_setup = st_usbfs_ep_setup,
+ .ep_reset = st_usbfs_endpoints_reset,
+ .ep_stall_set = st_usbfs_ep_stall_set,
+ .ep_stall_get = st_usbfs_ep_stall_get,
+ .ep_nak_set = st_usbfs_ep_nak_set,
+ .ep_write_packet = st_usbfs_ep_write_packet,
+ .ep_read_packet = st_usbfs_ep_read_packet,
+ .poll = st_usbfs_poll,
+};
+
+/** Initialize the USB device controller hardware of the STM32. */
+static usbd_device *st_usbfs_v1_usbd_init(void)
+{
+ rcc_periph_clock_enable(RCC_USB);
+ SET_REG(USB_CNTR_REG, 0);
+ SET_REG(USB_BTABLE_REG, 0);
+ SET_REG(USB_ISTR_REG, 0);
+
+ /* Enable RESET, SUSPEND, RESUME and CTR interrupts. */
+ SET_REG(USB_CNTR_REG, USB_CNTR_RESETM | USB_CNTR_CTRM |
+ USB_CNTR_SUSPM | USB_CNTR_WKUPM);
+ return &st_usbfs_dev;
+}
+
+void st_usbfs_copy_to_pm(volatile void *vPM, const void *buf, uint16_t len)
+{
+ const uint16_t *lbuf = buf;
+ volatile uint32_t *PM = vPM;
+ for (len = (len + 1) >> 1; len; len--) {
+ *PM++ = *lbuf++;
+ }
+}
+
+/**
+ * Copy a data buffer from packet memory.
+ *
+ * @param buf Source pointer to data buffer.
+ * @param vPM Destination pointer into packet memory.
+ * @param len Number of bytes to copy.
+ */
+void st_usbfs_copy_from_pm(void *buf, const volatile void *vPM, uint16_t len)
+{
+ uint16_t *lbuf = buf;
+ const volatile uint16_t *PM = vPM;
+ uint8_t odd = len & 1;
+
+ for (len >>= 1; len; PM += 2, lbuf++, len--) {
+ *lbuf = *PM;
+ }
+
+ if (odd) {
+ *(uint8_t *) lbuf = *(uint8_t *) PM;
+ }
+}
diff --git a/tests/gadget-zero/main-stm32f103-generic.c b/tests/gadget-zero/main-stm32f103-generic.c
index 10bc2730..d647341e 100644
--- a/tests/gadget-zero/main-stm32f103-generic.c
+++ b/tests/gadget-zero/main-stm32f103-generic.c
@@ -57,7 +57,7 @@ int main(void)
rcc_periph_clock_enable(RCC_OTGFS);
- usbd_device *usbd_dev = gadget0_init(&stm32f103_usb_driver, "stm32f103-generic");
+ usbd_device *usbd_dev = gadget0_init(&st_usbfs_v1_usb_driver, "stm32f103-generic");
ER_DPRINTF("bootup complete\n");
gpio_clear(GPIOC, GPIO13);
diff --git a/tests/gadget-zero/main-stm32l1-generic.c b/tests/gadget-zero/main-stm32l1-generic.c
index 751fe3dc..dc28a94a 100644
--- a/tests/gadget-zero/main-stm32l1-generic.c
+++ b/tests/gadget-zero/main-stm32l1-generic.c
@@ -57,7 +57,7 @@ int main(void)
gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO1);
gpio_set(GPIOB, GPIO1);
- usbd_device *usbd_dev = gadget0_init(&stm32f103_usb_driver, "stm32l1-generic");
+ usbd_device *usbd_dev = gadget0_init(&st_usbfs_v1_usb_driver, "stm32l1-generic");
ER_DPRINTF("bootup complete\n");
gpio_clear(GPIOB, GPIO1);