summaryrefslogtreecommitdiffstats
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
authorpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2012-08-16 22:48:26 +0000
committerpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2012-08-16 22:48:26 +0000
commit10138b6aa4378284dbbff7e017e76d6c55895db3 (patch)
tree471cf88312b1af5c229b81c5f8c7f69d0a622823 /nuttx/arch/arm
parent474632c4071e432edbe0b1e4c572b2d1f619c727 (diff)
Evolving STM32 USB host support
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@5031 7fd9a85b-ad96-42d3-883c-3090e2eb8679
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h14
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfsdev.c26
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfshost.c1105
5 files changed, 199 insertions, 950 deletions
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h b/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h
index d3bf7eb547..d04f2a67ff 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h
@@ -46,6 +46,12 @@
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
+/* General definitions */
+
+#define OTGFS_EPTYPE_CTRL (0) /* Control */
+#define OTGFS_EPTYPE_ISOC (1) /* Isochronous */
+#define OTGFS_EPTYPE_BULK (2) /* Bulk */
+#define OTGFS_EPTYPE_INTR (3) /* Interrupt */
/* Register Offsets *********************************************************************************/
/* Core global control and status registers */
@@ -125,8 +131,8 @@
#define STM32_OTGFS_HCTSIZ3_OFFSET 0x0570 /* Host channel-3 interrupt register */
#define STM32_OTGFS_HCTSIZ4_OFFSET 0x0590 /* Host channel-4 interrupt register */
#define STM32_OTGFS_HCTSIZ5_OFFSET 0x05b0 /* Host channel-5 interrupt register */
-#define STM32_OTGFS_HCTSIZ6_OFFSET 0x05d9 /* Host channel-6 interrupt register */
-#define STM32_OTGFS_HCTSIZ7_OFFSET 0x05f9 /* Host channel-7 interrupt register */
+#define STM32_OTGFS_HCTSIZ6_OFFSET 0x05d0 /* Host channel-6 interrupt register */
+#define STM32_OTGFS_HCTSIZ7_OFFSET 0x05f0 /* Host channel-7 interrupt register */
/* Device-mode control and status registers */
@@ -559,7 +565,7 @@
# define OTGFS_HNPTXSTS_EPNUM_SHIFT (27) /* Bits 27-30: Endpoint number */
# define OTGFS_HNPTXSTS_EPNUM_MASK (15 << OTGFS_HNPTXSTS_EPNUM_SHIFT)
/* Bit 31 Reserved, must be kept at reset value */
-/* general core configuration register */
+/* General core configuration register */
/* Bits 15:0 Reserved, must be kept at reset value */
#define OTGFS_GCCFG_PWRDWN (1 << 16) /* Bit 16: Power down */
/* Bit 17 Reserved, must be kept at reset value */
@@ -695,7 +701,7 @@
#define OTGFS_HCINT_STALL (1 << 3) /* Bit 3: STALL response received interrupt */
#define OTGFS_HCINT_NAK (1 << 4) /* Bit 4: NAK response received interrupt */
#define OTGFS_HCINT_ACK (1 << 5) /* Bit 5: ACK response received/transmitted interrupt */
-#define OTGFS_HCINTMSK_NYET (1 << 6) /* Bit 6: response received interrupt mask */
+#define OTGFS_HCINT_NYET (1 << 6) /* Bit 6: Response received interrupt */
#define OTGFS_HCINT_TXERR (1 << 7) /* Bit 7: Transaction error */
#define OTGFS_HCINT_BBERR (1 << 8) /* Bit 8: Babble error */
#define OTGFS_HCINT_FRMOR (1 << 9) /* Bit 9: Frame overrun */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
index 2c8587855e..c59cd565a2 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
@@ -365,7 +365,7 @@
#define GPIO_JTMS_SWDIO (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN13)
#define GPIO_JTRST (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4)
-/* OTG FS/HS */
+/* OTG FS/HS (VBUS PA9 is not an alternate configuration) */
#define GPIO_OTGFS_DM (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11)
#define GPIO_OTGFS_DP (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12)
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
index a588b56a27..ae2436a70f 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
@@ -365,7 +365,7 @@
#define GPIO_JTMS_SWDIO (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN13)
#define GPIO_JTRST (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4)
-/* OTG FS/HS */
+/* OTG FS/HS (VBUS PA9 is not an alternate configuration) */
#define GPIO_OTGFS_DM (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11)
#define GPIO_OTGFS_DP (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12)
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
index 39c40d80ab..81c919cdfd 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
@@ -4086,7 +4086,7 @@ static void *stm32_ep_allocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes)
*
*******************************************************************************/
-#ifdef CONFIG_LPC313x_USBDEV_DMA
+#ifdef CONFIG_STM32_USBDEV_DMA
static void stm32_ep_freebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf)
{
usbtrace(TRACE_EPFREEBUFFER, privep->epphy);
@@ -4645,7 +4645,6 @@ static int stm32_wakeup(struct usbdev_s *dev)
regval &= ~(OTGFS_PCGCCTL_STPPCLK | OTGFS_PCGCCTL_GATEHCLK);
stm32_putreg(regval, STM32_OTGFS_PCGCCTL);
#endif
-
/* Activate Remote wakeup signaling */
regval = stm32_getreg(STM32_OTGFS_DCTL);
@@ -4971,7 +4970,7 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv)
#ifndef CONFIG_USBDEV_VBUSSENSING
regval |= OTGFS_GCCFG_NOVBUSSENS;
#endif
-#ifdef CONFIG_USBDEV_SOFOUTPUT
+#ifdef CONFIG_STM32_OTGFS_SOFOUTPUT
regval |= OTGFS_GCCFG_SOFOUTEN;
#endif
stm32_putreg(regval, STM32_OTGFS_GCCFG);
@@ -5173,12 +5172,29 @@ void up_usbinitialize(void)
* current detection.
*/
- /* Configure OTG FS alternate function pins */
+ /* Configure OTG FS alternate function pins
+ *
+ * PIN* SIGNAL DIRECTION
+ * ---- ----------- ----------
+ * PA8 OTG_FS_SOF SOF clock output
+ * PA9 OTG_FS_VBUS VBUS input for device, Driven by external regulator by
+ * host (not an alternate function)
+ * PA10 OTG_FS_ID OTG ID pin (only needed in Dual mode)
+ * PA11 OTG_FS_DM D- I/O
+ * PA12 OTG_FS_DP D+ I/O
+ *
+ * *Pins may vary from device-to-device.
+ */
stm32_configgpio(GPIO_OTGFS_DM);
stm32_configgpio(GPIO_OTGFS_DP);
- stm32_configgpio(GPIO_OTGFS_ID);
+ stm32_configgpio(GPIO_OTGFS_ID); /* Only needed for OTG */
+
+ /* SOF output pin configuration is configurable. */
+
+#ifdef CONFIG_STM32_OTGFS_SOFOUTPUT
stm32_configgpio(GPIO_OTGFS_SOF);
+#endif
/* Uninitialize the hardware so that we know that we are starting from a
* known state. */
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfshost.c b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
index 57161088a7..6e7f8e41d1 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
@@ -60,15 +60,28 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "stm32_usbhost.h"
+#include "stm32_otgfs.h"
+
+#if defined(CONFIG_USBHOST) && defined(CONFIG_STM32_OTGFS)
/*******************************************************************************
* Definitions
*******************************************************************************/
/* Configuration ***************************************************************/
+/* Pre-requistites (partial) */
+
+#ifndef CONFIG_STM32_SYSCFG
+# error "CONFIG_STM32_SYSCFG is required"
+#endif
+
+/* Default RX buffer size */
-/* All I/O buffers must lie in AHB SRAM because of the OHCI DMA. It might be
+#ifndef CONFIG_STM32_OTGFS_RXBUFSIZE
+# define CONFIG_STM32_OTGFS_RXBUFSIZE 512
+#endif
+
+/* All I/O buffers must lie in AHB SRAM because of the OTGFS DMA. It might be
* okay if no I/O buffers are used *IF* the application can guarantee that all
* end-user I/O buffers reside in AHB SRAM.
*/
@@ -77,13 +90,20 @@
# warning "No IO buffers allocated"
#endif
-/* OHCI Setup ******************************************************************/
+/* HCD Setup *******************************************************************/
+/* Hardware capabilities */
+
+#define STM32_NHOST_CHANNELS 8 /* Number of host channels */
+#define STM32_MAX_PACKET_SIZE 64 /* Full speed max packet size */
+#define STM32_EP0_MAX_PACKET_SIZE 64 /* EP0 FS max packet size */
+#define STM32_MAX_TX_FIFOS 15 /* Max number of TX FIFOs */
+
/* Frame Interval / Periodic Start */
#define BITS_PER_FRAME 12000
#define FI (BITS_PER_FRAME-1)
#define FSMPS ((6 * (FI - 210)) / 7)
-#define DEFAULT_FMINTERVAL ((FSMPS << OHCI_FMINT_FSMPS_SHIFT) | FI)
+#define DEFAULT_FMINTERVAL ((FSMPS << OTGFS_FMINT_FSMPS_SHIFT) | FI)
#define DEFAULT_PERSTART (((9 * BITS_PER_FRAME) / 10) - 1)
/* CLKCTRL enable bits */
@@ -93,48 +113,82 @@
/* Interrupt enable bits */
#ifdef CONFIG_DEBUG_USB
-# define STM32_DEBUG_INTS (OHCI_INT_SO|OHCI_INT_RD|OHCI_INT_UE|OHCI_INT_OC)
+# define STM32_DEBUG_INTS (OTGFS_INT_SO|OTGFS_INT_RD|OTGFS_INT_UE|OTGFS_INT_OC)
#else
# define STM32_DEBUG_INTS 0
#endif
-#define STM32_NORMAL_INTS (OHCI_INT_WDH|OHCI_INT_RHSC)
+#define STM32_NORMAL_INTS (OTGFS_INT_WDH|OTGFS_INT_RHSC)
#define STM32_ALL_INTS (STM32_NORMAL_INTS|STM32_DEBUG_INTS)
-/* Dump GPIO registers */
+/* Ever-present MIN/MAX macros */
-#if defined(CONFIG_STM32_USBHOST_REGDEBUG) && defined(CONFIG_DEBUG_GPIO)
-# define usbhost_dumpgpio() \
- do { \
- stm32_dumpgpio(GPIO_USB_DP, "D+ P0.29; D- P0.30"); \
- stm32_dumpgpio(GPIO_USB_UPLED, "LED P1:18; PPWR P1:19 PWRD P1:22 PVRCR P1:27"); \
- } while (0);
-#else
-# define usbhost_dumpgpio()
+#ifndef MIN
+# define MIN(a, b) (((a) < (b)) ? (a) : (b))
#endif
-/* USB Host Memory *************************************************************/
+#ifndef MAX
+# define MAX(a, b) (((a) > (b)) ? (a) : (b))
+#endif
-/* Helper definitions */
+/*******************************************************************************
+ * Private Types
+ *******************************************************************************/
+/* USB Speeds */
-#define HCCA ((struct ohci_hcca_s *)STM32_HCCA_BASE)
-#define TDTAIL ((struct stm32_gtd_s *)STM32_TDTAIL_ADDR)
-#define EDCTRL ((struct stm32_ed_s *)STM32_EDCTRL_ADDR)
+enum stm32_usbspeed_e
+{
+ USBSPEED_LOW = 0, /* USB low speed */
+ USBSPEED_FULL, /* USB full speed (default) */
+ USBSPEED_HIGH /* USB high speed (not supported by OTG FS) */
+};
-/* Periodic intervals 2, 4, 8, 16,and 32 supported */
+/* This enumeration represents the state of one TX channel */
-#define MIN_PERINTERVAL 2
-#define MAX_PERINTERVAL 32
+enum stm32_chstate_e
+{
+ CHSTATE_IDLE = 0, /* Inactive */
+ CHSTATE_XFRC, /* Transfer complete */
+ CHSTATE_NAK, /* NAK received */
+ CHSTATE_NYET, /* NotYet received */
+ CHSTATE_STALL, /* Endpoint stalled */
+ CHSTATE_TXERR, /* Transfer error received */
+ CHSTATE_DTERR /* Data error received */
+};
-/* Descriptors *****************************************************************/
+/* This enumeration describes the state of the transfer on one TX channel */
-/* TD delay interrupt value */
+enum stm32_rqstate_e
+{
+ RQSTATE_IDLE = 0, /* No request in progress */
+ RQSTATE_DONE, /* Request complete */
+ RQSTATE_NOTREADY, /* Channel not ready */
+ RQSTATE_ERROR, /* An error occurred */
+ RQSTATE_STALL /* Endpoint is stalled */
+};
-#define TD_DELAY(n) (uint32_t)((n) << GTD_STATUS_DI_SHIFT)
+/* This structure retains the state of one host channel */
-/*******************************************************************************
- * Private Types
- *******************************************************************************/
+struct stn32_chan_s
+{
+ volatile uint8_t chstate; /* See enum stm32_chstate_e */
+ volatile uint8_t rqstate; /* See enum stm32_rqstate_e */
+ uint8_t devaddr; /* Device address */
+ uint8_t epno; /* Device endpoint number */
+ uint8_t speed; /* See enum stm32_usbspeed_e */
+ uint8_t eptype; /* See OTGFS_EPTYPE_* definitions */
+ uint8_t pid; /* Data PID */
+ bool isin; /* True: IN endpoint */
+ volatile uint16_t nerrors; /* Number of errors detecgted */
+ volatile uint16_t xfrd; /* Number of bytes transferred */
+ uint16_t channel; /* Encoded channel info */
+ uint16_t maxpacket; /* Max packet size */
+ uint16_t buflen; /* Buffer length (remaining) */
+ uint16_t xfrlen; /* Number of bytes transferrred */
+ uint8_t *buffer; /* Transfer buffer pointer */
+ uint8_t intoggle; /* IN data toggle */
+ uint8_t outtoggle; /* OUT data toggle */
+};
/* This structure retains the state of the USB host controller */
@@ -151,65 +205,21 @@ struct stm32_usbhost_s
struct usbhost_class_s *class;
- /* Driver status */
+ /* Overall driver status */
volatile bool connected; /* Connected to device */
volatile bool lowspeed; /* Low speed device attached. */
volatile bool rhswait; /* TRUE: Thread is waiting for Root Hub Status change */
-#ifndef CONFIG_USBHOST_INT_DISABLE
- uint8_t ininterval; /* Minimum periodic IN EP polling interval: 2, 4, 6, 16, or 32 */
- uint8_t outinterval; /* Minimum periodic IN EP polling interval: 2, 4, 6, 16, or 32 */
-#endif
sem_t exclsem; /* Support mutually exclusive access */
sem_t rhssem; /* Semaphore to wait Writeback Done Head event */
-};
-
-/* The OCHI expects the size of an endpoint descriptor to be 16 bytes.
- * However, the size allocated for an endpoint descriptor is 32 bytes in
- * stm32_ohciram.h. This extra 16-bytes is used by the OHCI host driver in
- * order to maintain additional endpoint-specific data.
- */
-
-struct stm32_ed_s
-{
- /* Hardware specific fields */
- struct ohci_ed_s hw;
+ /* The state of each host channel */
- /* Software specific fields */
+ struct stn32_chan_s chan[STM32_MAX_TX_FIFOS];
- uint8_t xfrtype; /* Transfer type. See SB_EP_ATTR_XFER_* in usb.h */
- uint8_t interval; /* Periodic EP polling interval: 2, 4, 6, 16, or 32 */
- volatile uint8_t tdstatus; /* TD control status bits from last Writeback Done Head event */
- volatile bool wdhwait; /* TRUE: Thread is waiting for WDH interrupt */
- sem_t wdhsem; /* Semaphore used to wait for Writeback Done Head event */
- /* Unused bytes follow, depending on the size of sem_t */
-};
-
-/* The OCHI expects the size of an transfer descriptor to be 16 bytes.
- * However, the size allocated for an endpoint descriptor is 32 bytes in
- * stm32_ohciram.h. This extra 16-bytes is used by the OHCI host driver in
- * order to maintain additional endpoint-specific data.
- */
-
-struct stm32_gtd_s
-{
- /* Hardware specific fields */
-
- struct ohci_gtd_s hw;
+ /* The RX buffer */
- /* Software specific fields */
-
- struct stm32_ed_s *ed; /* Pointer to parent ED */
- uint8_t pad[12];
-};
-
-/* The following is used to manage lists of free EDs, TDs, and TD buffers */
-
-struct stm32_list_s
-{
- struct stm32_list_s *flink; /* Link to next buffer in the list */
- /* Variable length buffer data follows */
+ uint8_t rxbuffer[CONFIG_STM32_OTGFS_RXBUFSIZE];
};
/*******************************************************************************
@@ -222,12 +232,15 @@ struct stm32_list_s
static void stm32_printreg(uint32_t addr, uint32_t val, bool iswrite);
static void stm32_checkreg(uint32_t addr, uint32_t val, bool iswrite);
static uint32_t stm32_getreg(uint32_t addr);
-static void stm32_putreg(uint32_t val, uint32_t addr);
+static void stm32_putreg(uint32_t addr, uint32_t value);
#else
# define stm32_getreg(addr) getreg32(addr)
# define stm32_putreg(val,addr) putreg32(val,addr)
#endif
+static inline void stm32_modifyreg(uint32_t addr, uint32_t clrbits,
+ uint32_t setbits);
+
/* Semaphores ******************************************************************/
static void stm32_takesem(sem_t *sem);
@@ -238,54 +251,16 @@ static void stm32_takesem(sem_t *sem);
static inline uint16_t stm32_getle16(const uint8_t *val);
static void stm32_putle16(uint8_t *dest, uint16_t val);
-/* OHCI memory pool helper functions *******************************************/
-
-static inline void stm32_edfree(struct stm32_ed_s *ed);
-static struct stm32_gtd_s *stm32_tdalloc(void);
-static void stm32_tdfree(struct stm32_gtd_s *buffer);
-static uint8_t *stm32_tballoc(void);
-static void stm32_tbfree(uint8_t *buffer);
-#if STM32_IOBUFFERS > 0
-static uint8_t *stm32_allocio(void);
-static void stm32_freeio(uint8_t *buffer);
-#endif
-
/* ED list helper functions ****************************************************/
-static inline int stm32_addbulked(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed);
-static inline int stm32_rembulked(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed);
-
#if !defined(CONFIG_USBHOST_INT_DISABLE) || !defined(CONFIG_USBHOST_ISOC_DISABLE)
static unsigned int stm32_getinterval(uint8_t interval);
static void stm32_setinttab(uint32_t value, unsigned int interval, unsigned int offset);
#endif
-static inline int stm32_addinted(struct stm32_usbhost_s *priv,
- const FAR struct usbhost_epdesc_s *epdesc,
- struct stm32_ed_s *ed);
-static inline int stm32_reminted(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed);
-
-static inline int stm32_addisoced(struct stm32_usbhost_s *priv,
- const FAR struct usbhost_epdesc_s *epdesc,
- struct stm32_ed_s *ed);
-static inline int stm32_remisoced(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed);
-
-/* Descriptor helper functions *************************************************/
-
-static int stm32_enqueuetd(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed, uint32_t dirpid,
- uint32_t toggle, volatile uint8_t *buffer,
- size_t buflen);
-static int stm32_ctrltd(struct stm32_usbhost_s *priv, uint32_t dirpid,
- uint8_t *buffer, size_t buflen);
-
/* Interrupt handling **********************************************************/
-static int stm32_usbinterrupt(int irq, FAR void *context);
+static int stm32_otgfs_interrupt(int irq, FAR void *context);
/* USB host controller operations **********************************************/
@@ -486,6 +461,19 @@ static void stm32_putreg(uint32_t val, uint32_t addr)
}
#endif
+/*******************************************************************************
+ * Name: stm32_modifyreg
+ *
+ * Description:
+ * Modify selected bits of an STM32 register.
+ *
+ *******************************************************************************/
+
+static inline void stm32_modifyreg(uint32_t addr, uint32_t clrbits, uint32_t setbits)
+{
+ stm32_putreg(addr, (((stm32_getreg(addr)) & ~clrbits) | setbits));
+}
+
/****************************************************************************
* Name: stm32_takesem
*
@@ -537,263 +525,6 @@ static void stm32_putle16(uint8_t *dest, uint16_t val)
}
/*******************************************************************************
- * Name: stm32_edfree
- *
- * Description:
- * Return an endpoint descriptor to the free list
- *
- *******************************************************************************/
-
-static inline void stm32_edfree(struct stm32_ed_s *ed)
-{
- struct stm32_list_s *entry = (struct stm32_list_s *)ed;
-
- /* Put the ED back into the free list */
-
- entry->flink = g_edfree;
- g_edfree = entry;
-}
-
-/*******************************************************************************
- * Name: stm32_tdalloc
- *
- * Description:
- * Allocate an transfer descriptor from the free list
- *
- * Assumptions:
- * - Never called from an interrupt handler.
- * - Protected from conconcurrent access to the TD pool by the interrupt
- * handler
- * - Protection from re-entrance must be assured by the caller
- *
- *******************************************************************************/
-
-static struct stm32_gtd_s *stm32_tdalloc(void)
-{
- struct stm32_gtd_s *ret;
- irqstate_t flags;
-
- /* Disable interrupts momentarily so that stm32_tdfree is not called from the
- * interrupt handler.
- */
-
- flags = irqsave();
- ret = (struct stm32_gtd_s *)g_tdfree;
- if (ret)
- {
- g_tdfree = ((struct stm32_list_s*)ret)->flink;
- }
-
- irqrestore(flags);
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_tdfree
- *
- * Description:
- * Return an transfer descriptor to the free list
- *
- * Assumptions:
- * - Only called from the WDH interrupt handler (and during initialization).
- * - Interrupts are disabled in any case.
- *
- *******************************************************************************/
-
-static void stm32_tdfree(struct stm32_gtd_s *td)
-{
- struct stm32_list_s *tdfree = (struct stm32_list_s *)td;
-
- /* This should not happen but just to be safe, don't free the common, pre-
- * allocated tail TD.
- */
-
- if (tdfree != NULL && td != TDTAIL)
- {
- tdfree->flink = g_tdfree;
- g_tdfree = tdfree;
- }
-}
-
-/*******************************************************************************
- * Name: stm32_tballoc
- *
- * Description:
- * Allocate an request/descriptor transfer buffer from the free list
- *
- * Assumptions:
- * - Never called from an interrupt handler.
- * - Protection from re-entrance must be assured by the caller
- *
- *******************************************************************************/
-
-static uint8_t *stm32_tballoc(void)
-{
- uint8_t *ret = (uint8_t *)g_tbfree;
- if (ret)
- {
- g_tbfree = ((struct stm32_list_s*)ret)->flink;
- }
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_tbfree
- *
- * Description:
- * Return an request/descriptor transfer buffer to the free list
- *
- *******************************************************************************/
-
-static void stm32_tbfree(uint8_t *buffer)
-{
- struct stm32_list_s *tbfree = (struct stm32_list_s *)buffer;
-
- if (tbfree)
- {
- tbfree->flink = g_tbfree;
- g_tbfree = tbfree;
- }
-}
-
-/*******************************************************************************
- * Name: stm32_allocio
- *
- * Description:
- * Allocate an IO buffer from the free list
- *
- * Assumptions:
- * - Never called from an interrupt handler.
- * - Protection from re-entrance must be assured by the caller
- *
- *******************************************************************************/
-
-#if STM32_IOBUFFERS > 0
-static uint8_t *stm32_allocio(void)
-{
- uint8_t *ret = (uint8_t *)g_iofree;
- if (ret)
- {
- g_iofree = ((struct stm32_list_s*)ret)->flink;
- }
- return ret;
-}
-#endif
-
-/*******************************************************************************
- * Name: stm32_freeio
- *
- * Description:
- * Return an TD buffer to the free list
- *
- *******************************************************************************/
-
-#if STM32_IOBUFFERS > 0
-static void stm32_freeio(uint8_t *buffer)
-{
- struct stm32_list_s *iofree = (struct stm32_list_s *)buffer;
- iofree->flink = g_iofree;
- g_iofree = iofree;
-}
-#endif
-
-/*******************************************************************************
- * Name: stm32_addbulked
- *
- * Description:
- * Helper function to add an ED to the bulk list.
- *
- *******************************************************************************/
-
-static inline int stm32_addbulked(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_BULK_DISABLE
- uint32_t regval;
-
- /* Add the new bulk ED to the head of the bulk list */
-
- ed->hw.nexted = stm32_getreg(STM32_USBHOST_BULKHEADED);
- stm32_putreg((uint32_t)ed, STM32_USBHOST_BULKHEADED);
-
- /* BulkListEnable. This bit is set to enable the processing of the
- * Bulk list. Note: once enabled, it remains. We really should
- * never modify the bulk list while BLE is set.
- */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval |= OHCI_CTRL_BLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
- return OK;
-#else
- return -ENOSYS;
-#endif
-}
-
-/*******************************************************************************
- * Name: stm32_rembulked
- *
- * Description:
- * Helper function remove an ED from the bulk list.
- *
- *******************************************************************************/
-
-static inline int stm32_rembulked(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_BULK_DISABLE
- struct stm32_ed_s *curr;
- struct stm32_ed_s *prev;
- uint32_t regval;
-
- /* Find the ED in the bulk list. NOTE: We really should never be mucking
- * with the bulk list while BLE is set.
- */
-
- for (curr = (struct stm32_ed_s *)stm32_getreg(STM32_USBHOST_BULKHEADED),
- prev = NULL;
- curr && curr != ed;
- prev = curr, curr = (struct stm32_ed_s *)curr->hw.nexted);
-
- /* Hmmm.. It would be a bug if we do not find the ED in the bulk list. */
-
- DEBUGASSERT(curr != NULL);
-
- /* Remove the ED from the bulk list */
-
- if (curr != NULL)
- {
- /* Is this ED the first on in the bulk list? */
-
- if (prev == NULL)
- {
- /* Yes... set the head of the bulk list to skip over this ED */
-
- stm32_putreg(ed->hw.nexted, STM32_USBHOST_BULKHEADED);
-
- /* If the bulk list is now empty, then disable it */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval &= ~OHCI_CTRL_BLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
- }
- else
- {
- /* No.. set the forward link of the previous ED in the list
- * skip over this ED.
- */
-
- prev->hw.nexted = ed->hw.nexted;
- }
- }
-
- return OK;
-#else
- return -ENOSYS;
-#endif
-}
-
-/*******************************************************************************
* Name: stm32_getinterval
*
* Description:
@@ -853,337 +584,6 @@ static void stm32_setinttab(uint32_t value, unsigned int interval, unsigned int
#endif
/*******************************************************************************
- * Name: stm32_addinted
- *
- * Description:
- * Helper function to add an ED to the HCCA interrupt table.
- *
- * To avoid reshuffling the table so much and to keep life simple in general,
- * the following rules are applied:
- *
- * 1. IN EDs get the even entries, OUT EDs get the odd entries.
- * 2. Add IN/OUT EDs are scheduled together at the minimum interval of all
- * IN/OUT EDs.
- *
- * This has the following consequences:
- *
- * 1. The minimum support polling rate is 2MS, and
- * 2. Some devices may get polled at a much higher rate than they request.
- *
- *******************************************************************************/
-
-static inline int stm32_addinted(struct stm32_usbhost_s *priv,
- const FAR struct usbhost_epdesc_s *epdesc,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_INT_DISABLE
- unsigned int interval;
- unsigned int offset;
- uint32_t head;
- uint32_t regval;
-
- /* Disable periodic list processing. Does this take effect immediately? Or
- * at the next SOF... need to check.
- */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval &= ~OHCI_CTRL_PLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
-
- /* Get the quanitized interval value associated with this ED and save it
- * in the ED.
- */
-
- interval = stm32_getinterval(epdesc->interval);
- ed->interval = interval;
- uvdbg("interval: %d->%d\n", epdesc->interval, interval);
-
- /* Get the offset associated with the ED direction. IN EDs get the even
- * entries, OUT EDs get the odd entries.
- *
- * Get the new, minimum interval. Add IN/OUT EDs are scheduled together
- * at the minimum interval of all IN/OUT EDs.
- */
-
- if (epdesc->in)
- {
- offset = 0;
- if (priv->ininterval > interval)
- {
- priv->ininterval = interval;
- }
- else
- {
- interval = priv->ininterval;
- }
- }
- else
- {
- offset = 1;
- if (priv->outinterval > interval)
- {
- priv->outinterval = interval;
- }
- else
- {
- interval = priv->outinterval;
- }
- }
- uvdbg("min interval: %d offset: %d\n", interval, offset);
-
- /* Get the head of the first of the duplicated entries. The first offset
- * entry is always guaranteed to contain the common ED list head.
- */
-
- head = HCCA->inttbl[offset];
-
- /* Clear all current entries in the interrupt table for this direction */
-
- stm32_setinttab(0, 2, offset);
-
- /* Add the new ED before the old head of the periodic ED list and set the
- * new ED as the head ED in all of the appropriate entries of the HCCA
- * interrupt table.
- */
-
- ed->hw.nexted = head;
- stm32_setinttab((uint32_t)ed, interval, offset);
- uvdbg("head: %08x next: %08x\n", ed, head);
-
- /* Re-enabled periodic list processing */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval |= OHCI_CTRL_PLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
- return OK;
-#else
- return -ENOSYS;
-#endif
-}
-
-/*******************************************************************************
- * Name: stm32_reminted
- *
- * Description:
- * Helper function to remove an ED from the HCCA interrupt table.
- *
- * To avoid reshuffling the table so much and to keep life simple in general,
- * the following rules are applied:
- *
- * 1. IN EDs get the even entries, OUT EDs get the odd entries.
- * 2. Add IN/OUT EDs are scheduled together at the minimum interval of all
- * IN/OUT EDs.
- *
- * This has the following consequences:
- *
- * 1. The minimum support polling rate is 2MS, and
- * 2. Some devices may get polled at a much higher rate than they request.
- *
- *******************************************************************************/
-
-static inline int stm32_reminted(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_INT_DISABLE
- struct stm32_ed_s *head;
- struct stm32_ed_s *curr;
- struct stm32_ed_s *prev;
- unsigned int interval;
- unsigned int offset;
- uint32_t regval;
-
- /* Disable periodic list processing. Does this take effect immediately? Or
- * at the next SOF... need to check.
- */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval &= ~OHCI_CTRL_PLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
-
- /* Get the offset associated with the ED direction. IN EDs get the even
- * entries, OUT EDs get the odd entries.
- */
-
- if ((ed->hw.ctrl & ED_CONTROL_D_MASK) == ED_CONTROL_D_IN)
- {
- offset = 0;
- }
- else
- {
- offset = 1;
- }
-
- /* Get the head of the first of the duplicated entries. The first offset
- * entry is always guaranteed to contain the common ED list head.
- */
-
- head = (struct stm32_ed_s *)HCCA->inttbl[offset];
- uvdbg("ed: %08x head: %08x next: %08x offset: %d\n",
- ed, head, head ? head->hw.nexted : 0, offset);
-
- /* Find the ED to be removed in the ED list */
-
- for (curr = head, prev = NULL;
- curr && curr != ed;
- prev = curr, curr = (struct stm32_ed_s *)curr->hw.nexted);
-
- /* Hmmm.. It would be a bug if we do not find the ED in the bulk list. */
-
- DEBUGASSERT(curr != NULL);
- if (curr != NULL)
- {
- /* Clear all current entries in the interrupt table for this direction */
-
- stm32_setinttab(0, 2, offset);
-
- /* Remove the ED from the list.. Is this ED the first on in the list? */
-
- if (prev == NULL)
- {
- /* Yes... set the head of the bulk list to skip over this ED */
-
- head = (struct stm32_ed_s *)ed->hw.nexted;
- }
- else
- {
- /* No.. set the forward link of the previous ED in the list
- * skip over this ED.
- */
-
- prev->hw.nexted = ed->hw.nexted;
- }
- uvdbg("ed: %08x head: %08x next: %08x\n",
- ed, head, head ? head->hw.nexted : 0);
-
- /* Calculate the new minimum interval for this list */
-
- interval = MAX_PERINTERVAL;
- for (curr = head; curr; curr = (struct stm32_ed_s *)curr->hw.nexted)
- {
- if (curr->interval < interval)
- {
- interval = curr->interval;
- }
- }
- uvdbg("min interval: %d offset: %d\n", interval, offset);
-
- /* Save the new minimum interval */
-
- if ((ed->hw.ctrl && ED_CONTROL_D_MASK) == ED_CONTROL_D_IN)
- {
- priv->ininterval = interval;
- }
- else
- {
- priv->outinterval = interval;
- }
-
- /* Set the head ED in all of the appropriate entries of the HCCA interrupt
- * table (head might be NULL).
- */
-
- stm32_setinttab((uint32_t)head, interval, offset);
- }
-
- /* Re-enabled periodic list processing */
-
- if (head != NULL)
- {
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval |= OHCI_CTRL_PLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
- }
-
- return OK;
-#else
- return -ENOSYS;
-#endif
-}
-
-/*******************************************************************************
- * Name: stm32_addisoced
- *
- * Description:
- * Helper functions to add an ED to the periodic table.
- *
- *******************************************************************************/
-
-static inline int stm32_addisoced(struct stm32_usbhost_s *priv,
- const FAR struct usbhost_epdesc_s *epdesc,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_ISOC_DISABLE
-# warning "Isochronous endpoints not yet supported"
-#endif
- return -ENOSYS;
-
-}
-
-/*******************************************************************************
- * Name: stm32_remisoced
- *
- * Description:
- * Helper functions to remove an ED from the periodic table.
- *
- *******************************************************************************/
-
-static inline int stm32_remisoced(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_ISOC_DISABLE
-# warning "Isochronous endpoints not yet supported"
-#endif
- return -ENOSYS;
-}
-
-/*******************************************************************************
- * Name: stm32_enqueuetd
- *
- * Description:
- * Enqueue a transfer descriptor. Notice that this function only supports
- * queue on TD per ED.
- *
- *******************************************************************************/
-
-static int stm32_enqueuetd(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed, uint32_t dirpid,
- uint32_t toggle, volatile uint8_t *buffer, size_t buflen)
-{
- struct stm32_gtd_s *td;
- int ret = -ENOMEM;
-
- /* Allocate a TD from the free list */
-
- td = stm32_tdalloc();
- if (td != NULL)
- {
- /* Initialize the allocated TD and link it before the common tail TD. */
-
- td->hw.ctrl = (GTD_STATUS_R | dirpid | TD_DELAY(0) | toggle | GTD_STATUS_CC_MASK);
- TDTAIL->hw.ctrl = 0;
- td->hw.cbp = (uint32_t)buffer;
- TDTAIL->hw.cbp = 0;
- td->hw.nexttd = (uint32_t)TDTAIL;
- TDTAIL->hw.nexttd = 0;
- td->hw.be = (uint32_t)(buffer + (buflen - 1));
- TDTAIL->hw.be = 0;
-
- /* Configure driver-only fields in the extended TD structure */
-
- td->ed = ed;
-
- /* Link the td to the head of the ED's TD list */
-
- ed->hw.headp = (uint32_t)td | ((ed->hw.headp) & ED_HEADP_C);
- ed->hw.tailp = (uint32_t)TDTAIL;
-
- ret = OK;
- }
-
- return ret;
-}
-
-/*******************************************************************************
* Name: stm32_wdhwait
*
* Description:
@@ -1267,10 +667,7 @@ static int stm32_ctrltd(struct stm32_usbhost_s *priv, uint32_t dirpid,
/* Set ControlListFilled. This bit is used to indicate whether there are
* TDs on the Control list.
*/
-
- regval = stm32_getreg(STM32_USBHOST_CMDST);
- regval |= OHCI_CMDST_CLF;
- stm32_putreg(regval, STM32_USBHOST_CMDST);
+#warning "Missing Logic"
/* Wait for the Writeback Done Head interrupt */
@@ -1296,14 +693,14 @@ static int stm32_ctrltd(struct stm32_usbhost_s *priv, uint32_t dirpid,
}
/*******************************************************************************
- * Name: stm32_usbinterrupt
+ * Name: stm32_otgfs_interrupt
*
* Description:
* USB interrupt handler
*
*******************************************************************************/
-static int stm32_usbinterrupt(int irq, FAR void *context)
+static int stm32_otgfs_interrupt(int irq, FAR void *context)
{
struct stm32_usbhost_s *priv = &g_usbhost;
uint32_t intst;
@@ -1311,9 +708,7 @@ static int stm32_usbinterrupt(int irq, FAR void *context)
uint32_t regval;
/* Read Interrupt Status and mask out interrupts that are not enabled. */
-
- intst = stm32_getreg(STM32_USBHOST_INTST);
- regval = stm32_getreg(STM32_USBHOST_INTEN);
+#warning "Missing Logic"
ullvdbg("INST: %08x INTEN: %08x\n", intst, regval);
pending = intst & regval;
@@ -1321,19 +716,19 @@ static int stm32_usbinterrupt(int irq, FAR void *context)
{
/* Root hub status change interrupt */
- if ((pending & OHCI_INT_RHSC) != 0)
+ if ((pending & OTGFS_INT_RHSC) != 0)
{
- uint32_t rhportst1 = stm32_getreg(STM32_USBHOST_RHPORTST1);
+#warning "Missing Logic"
ullvdbg("Root Hub Status Change, RHPORTST1: %08x\n", rhportst1);
- if ((rhportst1 & OHCI_RHPORTST_CSC) != 0)
+ if ((rhportst1 & OTGFS_RHPORTST_CSC) != 0)
{
- uint32_t rhstatus = stm32_getreg(STM32_USBHOST_RHSTATUS);
+#warning "Missing Logic"
ullvdbg("Connect Status Change, RHSTATUS: %08x\n", rhstatus);
/* If DRWE is set, Connect Status Change indicates a remote wake-up event */
- if (rhstatus & OHCI_RHSTATUS_DRWE)
+ if (rhstatus & OTGFS_RHSTATUS_DRWE)
{
ullvdbg("DRWE: Remote wake-up\n");
}
@@ -1344,7 +739,7 @@ static int stm32_usbinterrupt(int irq, FAR void *context)
{
/* Check current connect status */
- if ((rhportst1 & OHCI_RHPORTST_CCS) != 0)
+ if ((rhportst1 & OTGFS_RHPORTST_CCS) != 0)
{
/* Connected ... Did we just become connected? */
@@ -1372,7 +767,7 @@ static int stm32_usbinterrupt(int irq, FAR void *context)
* when CCS == 1.
*/
- priv->lowspeed = (rhportst1 & OHCI_RHPORTST_LSDA) != 0;
+ priv->lowspeed = (rhportst1 & OTGFS_RHPORTST_LSDA) != 0;
ullvdbg("Speed:%s\n", priv->lowspeed ? "LOW" : "FULL");
}
@@ -1411,23 +806,21 @@ static int stm32_usbinterrupt(int irq, FAR void *context)
}
/* Clear the status change interrupt */
-
- stm32_putreg(OHCI_RHPORTST_CSC, STM32_USBHOST_RHPORTST1);
+#warning "Missing Logic"
}
/* Check for port reset status change */
- if ((rhportst1 & OHCI_RHPORTST_PRSC) != 0)
+ if ((rhportst1 & OTGFS_RHPORTST_PRSC) != 0)
{
/* Release the RH port from reset */
-
- stm32_putreg(OHCI_RHPORTST_PRSC, STM32_USBHOST_RHPORTST1);
+#warning "Missing Logic"
}
}
/* Writeback Done Head interrupt */
- if ((pending & OHCI_INT_WDH) != 0)
+ if ((pending & OTGFS_INT_WDH) != 0)
{
struct stm32_gtd_s *td;
struct stm32_gtd_s *next;
@@ -1467,7 +860,7 @@ static int stm32_usbinterrupt(int irq, FAR void *context)
ulldbg("ERROR: ED xfrtype:%d TD CTRL:%08x/CC:%d RHPORTST1:%08x\n",
ed->xfrtype, td->hw.ctrl, ed->tdstatus,
- stm32_getreg(STM32_USBHOST_RHPORTST1));
+ stm32_getreg(???));
}
#endif
@@ -1494,8 +887,7 @@ static int stm32_usbinterrupt(int irq, FAR void *context)
#endif
/* Clear interrupt status register */
-
- stm32_putreg(intst, STM32_USBHOST_INTST);
+#warning "Missing Logic"
}
return OK;
@@ -1599,16 +991,14 @@ static int stm32_enumerate(FAR struct usbhost_driver_s *drvr)
up_mdelay(100);
/* Put RH port 1 in reset (the STM32 supports only a single downstream port) */
-
- stm32_putreg(OHCI_RHPORTST_PRS, STM32_USBHOST_RHPORTST1);
+#warning "Missing Logic"
/* Wait for the port reset to complete */
- while ((stm32_getreg(STM32_USBHOST_RHPORTST1) & OHCI_RHPORTST_PRS) != 0);
+ while ((stm32_getreg(???) & ???) != 0);
/* Release RH port 1 from reset and wait a bit */
-
- stm32_putreg(OHCI_RHPORTST_PRSC, STM32_USBHOST_RHPORTST1);
+#warning "Missing Logic"
up_mdelay(200);
/* Let the common usbhost_enumerate do all of the real work. Note that the
@@ -2299,10 +1689,7 @@ static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
/* BulkListFilled. This bit is used to indicate whether there are any
* TDs on the Bulk list.
*/
-
- regval = stm32_getreg(STM32_USBHOST_CMDST);
- regval |= OHCI_CMDST_BLF;
- stm32_putreg(regval, STM32_USBHOST_CMDST);
+#warning "Missing Logic"
/* Wait for the Writeback Done Head interrupt */
@@ -2421,18 +1808,14 @@ static inline void stm32_ep0init(struct stm32_usbhost_s *priv)
/* Set the head of the control list to the EP0 EDCTRL (this would have to
* change if we want more than on control EP queued at a time).
*/
-
- stm32_putreg(STM32_EDCTRL_ADDR, STM32_USBHOST_CTRLHEADED);
+#warning "Missing Logic"
/* ControlListEnable. This bit is set to enable the processing of the
* Control list. Note: once enabled, it remains enabled and we may even
* complete list processing before we get the bit set. We really
* should never modify the control list while CLE is set.
*/
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval |= OHCI_CTRL_CLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
+#warning "Missing Logic"
}
/*******************************************************************************
@@ -2485,231 +1868,75 @@ static inline int stm32_hcdinitialize(FAR struct stm32_usbhost_s *priv)
FAR struct usbhost_driver_s *usbhost_initialize(int controller)
{
- struct stm32_usbhost_s *priv = &g_usbhost;
- uint32_t regval;
- uint8_t *buffer;
- irqstate_t flags;
- int i;
-
- /* Sanity checks. NOTE: If certain OS features are enabled, it may be
- * necessary to increase the size of STM32_ED/TD_SIZE in stm32_ohciram.h
+ /* At present, there is only a single OTG FS device support. Hence it is
+ * pre-allocated as g_usbhost. However, in most code, the private data
+ * structure will be referenced using the 'priv' pointer (rather than the
+ * global data) in order to simplify any future support for multiple devices.
*/
+ FAR struct stm32_usbhost_s *priv = &g_usbhost;
+ int ret;
+
+ /* Sanity checks */
+
DEBUGASSERT(controller == 0);
- DEBUGASSERT(sizeof(struct stm32_ed_s) <= STM32_ED_SIZE);
- DEBUGASSERT(sizeof(struct stm32_gtd_s) <= STM32_TD_SIZE);
/* Initialize the state data structure */
sem_init(&priv->rhssem, 0, 0);
sem_init(&priv->exclsem, 0, 1);
-#ifndef CONFIG_USBHOST_INT_DISABLE
- priv->ininterval = MAX_PERINTERVAL;
- priv->outinterval = MAX_PERINTERVAL;
-#endif
+ /* Reset the state of the host driver */
- /* Enable power by setting PCUSB in the PCONP register. Disable interrupts
- * because this register may be shared with other drivers.
- */
+ stm32_swreset(priv);
- flags = irqsave();
- regval = stm32_getreg(STM32_SYSCON_PCONP);
- regval |= SYSCON_PCONP_PCUSB;
- stm32_putreg(regval, STM32_SYSCON_PCONP);
- irqrestore(flags);
-
- /* Enable clocking on USB (USB PLL clocking was initialized in very low-
- * evel clock setup logic (see stm32_clockconfig.c)). We do still need
- * to set up USBOTG CLKCTRL to enable clocking.
+ /* Alternate function pin configuration. Here we assume that:
*
- * NOTE: The PORTSEL clock needs to be enabled only when accessing OTGSTCTRL
+ * 1. GPIOA, SYSCFG, and OTG FS peripheral clocking have already been\
+ * enabled as part of the boot sequence.
+ * 2. Board-specific logic has already enabled other board specific GPIOs
+ * for things like soft pull-up, VBUS sensing, power controls, and over-
+ * current detection.
*/
- stm32_putreg(STM32_CLKCTRL_ENABLES, STM32_USBOTG_CLKCTRL);
-
- /* Then wait for the clocks to be reported as "ON" */
-
- do
- {
- regval = stm32_getreg(STM32_USBOTG_CLKST);
- }
- while ((regval & STM32_CLKCTRL_ENABLES) != STM32_CLKCTRL_ENABLES);
-
- /* Set the OTG status and control register. Bits 0:1 apparently mean:
+ /* Configure OTG FS alternate function pins for DM, DP, ID, and SOF.
*
- * 00: U1=device, U2=host
- * 01: U1=host, U2=host
- * 10: reserved
- * 11: U1=host, U2=device
+ * PIN* SIGNAL DIRECTION
+ * ---- ----------- ----------
+ * PA8 OTG_FS_SOF SOF clock output
+ * PA9 OTG_FS_VBUS VBUS input for device, Driven by external regulator by
+ * host (not an alternate function)
+ * PA10 OTG_FS_ID OTG ID pin (only needed in Dual mode)
+ * PA11 OTG_FS_DM D- I/O
+ * PA12 OTG_FS_DP D+ I/O
*
- * We need only select U1=host (Bit 0=1, Bit 1 is not used on STM32);
- * NOTE: The PORTSEL clock needs to be enabled when accessing OTGSTCTRL
+ * *Pins may vary from device-to-device.
*/
- stm32_putreg(1, STM32_USBOTG_STCTRL);
-
- /* Now we can turn off the PORTSEL clock */
-
- stm32_putreg((STM32_CLKCTRL_ENABLES & ~USBOTG_CLK_PORTSELCLK), STM32_USBOTG_CLKCTRL);
-
- /* Configure I/O pins */
-
- usbhost_dumpgpio();
- stm32_configgpio(GPIO_USB_DP); /* Positive differential data */
- stm32_configgpio(GPIO_USB_DM); /* Negative differential data */
- stm32_configgpio(GPIO_USB_UPLED); /* GoodLink LED control signal */
- stm32_configgpio(GPIO_USB_PPWR); /* Port Power enable signal for USB port */
- stm32_configgpio(GPIO_USB_PWRD); /* Power Status for USB port (host power switch) */
- stm32_configgpio(GPIO_USB_OVRCR); /* USB port Over-Current status */
- usbhost_dumpgpio();
-
- udbg("Initializing Host Stack\n");
+ stm32_configgpio(GPIO_OTGFS_DM);
+ stm32_configgpio(GPIO_OTGFS_DP);
+ stm32_configgpio(GPIO_OTGFS_ID); /* Only needed for OTG */
- /* Show AHB SRAM memory map */
+ /* SOF output pin configuration is configurable */
-#if 0 /* Useful if you have doubts about the layout */
- uvdbg("AHB SRAM:\n");
- uvdbg(" HCCA: %08x %d\n", STM32_HCCA_BASE, STM32_HCCA_SIZE);
- uvdbg(" TDTAIL: %08x %d\n", STM32_TDTAIL_ADDR, STM32_TD_SIZE);
- uvdbg(" EDCTRL: %08x %d\n", STM32_EDCTRL_ADDR, STM32_ED_SIZE);
- uvdbg(" EDFREE: %08x %d\n", STM32_EDFREE_BASE, STM32_ED_SIZE);
- uvdbg(" TDFREE: %08x %d\n", STM32_TDFREE_BASE, STM32_EDFREE_SIZE);
- uvdbg(" TBFREE: %08x %d\n", STM32_TBFREE_BASE, STM32_TBFREE_SIZE);
- uvdbg(" IOFREE: %08x %d\n", STM32_IOFREE_BASE, STM32_IOBUFFERS * CONFIG_USBHOST_IOBUFSIZE);
+#ifdef CONFIG_STM32_OTGFS_SOFOUTPUT
+ stm32_configgpio(GPIO_OTGFS_SOF);
#endif
- /* Initialize all the TDs, EDs and HCCA to 0 */
-
- memset((void*)HCCA, 0, sizeof(struct ohci_hcca_s));
- memset((void*)TDTAIL, 0, sizeof(struct ohci_gtd_s));
- memset((void*)EDCTRL, 0, sizeof(struct stm32_ed_s));
- sem_init(&EDCTRL->wdhsem, 0, 0);
-
- /* Initialize user-configurable EDs */
-
- buffer = (uint8_t *)STM32_EDFREE_BASE;
- for (i = 0; i < CONFIG_USBHOST_NEDS; i++)
- {
- /* Put the ED in a free list */
-
- stm32_edfree((struct stm32_ed_s *)buffer);
- buffer += STM32_ED_SIZE;
- }
-
- /* Initialize user-configurable TDs */
+ /* Initialize the USB OTG FS core */
- buffer = (uint8_t *)STM32_TDFREE_BASE;
- for (i = 0; i < CONFIG_USBHOST_NTDS; i++)
- {
- /* Put the ED in a free list */
-
- stm32_tdfree((struct stm32_gtd_s *)buffer);
- buffer += STM32_TD_SIZE;
- }
-
- /* Initialize user-configurable request/descriptor transfer buffers */
-
- buffer = (uint8_t *)STM32_TBFREE_BASE;
- for (i = 0; i < CONFIG_USBHOST_TDBUFFERS; i++)
- {
- /* Put the TD buffer in a free list */
-
- stm32_tbfree(buffer);
- buffer += CONFIG_USBHOST_TDBUFSIZE;
- }
-
-#if STM32_IOBUFFERS > 0
- /* Initialize user-configurable IO buffers */
-
- buffer = (uint8_t *)STM32_IOFREE_BASE;
- for (i = 0; i < STM32_IOBUFFERS; i++)
- {
- /* Put the IO buffer in a free list */
-
- stm32_freeio(buffer);
- buffer += CONFIG_USBHOST_IOBUFSIZE;
- }
-#endif
-
- /* Wait 50MS then perform hardware reset */
-
- up_mdelay(50);
-
- stm32_putreg(0, STM32_USBHOST_CTRL); /* Hardware reset */
- stm32_putreg(0, STM32_USBHOST_CTRLHEADED); /* Initialize control list head to Zero */
- stm32_putreg(0, STM32_USBHOST_BULKHEADED); /* Initialize bulk list head to Zero */
-
- /* Software reset */
-
- stm32_putreg(OHCI_CMDST_HCR, STM32_USBHOST_CMDST);
-
- /* Write Fm interval (FI), largest data packet counter (FSMPS), and
- * periodic start.
- */
-
- stm32_putreg(DEFAULT_FMINTERVAL, STM32_USBHOST_FMINT);
- stm32_putreg(DEFAULT_PERSTART, STM32_USBHOST_PERSTART);
-
- /* Put HC in operational state */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval &= ~OHCI_CTRL_HCFS_MASK;
- regval |= OHCI_CTRL_HCFS_OPER;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
-
- /* Set global power in HcRhStatus */
-
- stm32_putreg(OHCI_RHSTATUS_SGP, STM32_USBHOST_RHSTATUS);
-
- /* Set HCCA base address */
-
- stm32_putreg((uint32_t)HCCA, STM32_USBHOST_HCCA);
-
- /* Set up EP0 */
-
- stm32_ep0init(priv);
-
- /* Clear pending interrupts */
-
- regval = stm32_getreg(STM32_USBHOST_INTST);
- stm32_putreg(regval, STM32_USBHOST_INTST);
-
- /* Enable OHCI interrupts */
-
- stm32_putreg((STM32_ALL_INTS|OHCI_INT_MIE), STM32_USBHOST_INTEN);
+ stm32_hcdinitialize(priv);
/* Attach USB host controller interrupt handler */
- if (irq_attach(STM32_IRQ_USB, stm32_usbinterrupt) != 0)
+ if (irq_attach(STM32_IRQ_OTGFS, stm32_otgfs_interrupt) != 0)
{
udbg("Failed to attach IRQ\n");
return NULL;
}
- /* Enable USB interrupts at the SYCON controller. Disable interrupts
- * because this register may be shared with other drivers.
- */
-
- flags = irqsave();
- regval = stm32_getreg(STM32_SYSCON_USBINTST);
- regval |= SYSCON_USBINTST_ENINTS;
- stm32_putreg(regval, STM32_SYSCON_USBINTST);
- irqrestore(flags);
-
- /* If there is a USB device in the slot at power up, then we will not
- * get the status change interrupt to signal us that the device is
- * connected. We need to set the initial connected state accordingly.
- */
-
- regval = stm32_getreg(STM32_USBHOST_RHPORTST1);
- priv->connected = ((regval & OHCI_RHPORTST_CCS) != 0);
-
/* Enable interrupts at the interrupt controller */
- up_enable_irq(STM32_IRQ_USB); /* enable USB interrupt */
- udbg("USB host Initialized, Device connected:%s\n",
- priv->connected ? "YES" : "NO");
-
+ up_enable_irq(STM32_IRQ_OTGFS);
return &priv->drvr;
}