Changes for clean STM32 USB host driver build

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@5040 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-08-20 16:06:39 +00:00
parent 4f56a72bea
commit 27bd0bbee4
11 changed files with 309 additions and 140 deletions

View File

@ -60,15 +60,37 @@
#include "up_arch.h" #include "up_arch.h"
#include "up_internal.h" #include "up_internal.h"
#include "stm32_otgfs.h" #include "stm32_usbhost.h"
#if defined(CONFIG_USBHOST) && defined(CONFIG_STM32_OTGFS) #if defined(CONFIG_USBHOST) && defined(CONFIG_STM32_OTGFS)
/******************************************************************************* /*******************************************************************************
* Definitions * Definitions
*******************************************************************************/ *******************************************************************************/
/* Configuration ***************************************************************/ /* Configuration ***************************************************************/
/*
* STM32 USB OTG FS Host Driver Support
*
* Pre-requisites
*
* CONFIG_USBHOST - Enable general USB host support
* CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
* CONFIG_STM32_SYSCFG - Needed
*
* Options:
*
* CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words.
* Default 128 (512 bytes)
* CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO
* in 32-bit words. Default 96 (384 bytes)
* CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit
* words. Default 96 (384 bytes)
* CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever
* want to do that?
* CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access
* debug. Depends on CONFIG_DEBUG.
*/
/* Pre-requistites (partial) */ /* Pre-requistites (partial) */
#ifndef CONFIG_STM32_SYSCFG #ifndef CONFIG_STM32_SYSCFG
@ -83,12 +105,6 @@
/* Default host non-periodic transmit FIFO size */ /* Default host non-periodic transmit FIFO size */
#ifndef CONFIG_STM32_OTGFS_RXFIFO_SIZE
# define CONFIG_STM32_OTGFS_RXFIFO_SIZE 128
#endif
/* Default host non-periodic transmit FIFO size */
#ifndef CONFIG_STM32_OTGFS_NPTXFIFO_SIZE #ifndef CONFIG_STM32_OTGFS_NPTXFIFO_SIZE
# define CONFIG_STM32_OTGFS_NPTXFIFO_SIZE 96 # define CONFIG_STM32_OTGFS_NPTXFIFO_SIZE 96
#endif #endif
@ -99,6 +115,12 @@
# define CONFIG_STM32_OTGFS_PTXFIFO_SIZE 96 # define CONFIG_STM32_OTGFS_PTXFIFO_SIZE 96
#endif #endif
/* Register debug depends on CONFIG_DEBUG */
#ifndef CONFIG_DEBUG
# undef CONFIG_STM32_USBHOST_REGDEBUG
#endif
/* HCD Setup *******************************************************************/ /* HCD Setup *******************************************************************/
/* Hardware capabilities */ /* Hardware capabilities */
@ -169,7 +191,7 @@ struct stm32_chan_s
bool inuse; /* True: This channel is "in use" */ bool inuse; /* True: This channel is "in use" */
bool indata1; /* IN data toggle. True: DATA01 */ bool indata1; /* IN data toggle. True: DATA01 */
bool outdata1; /* OUT data toggle. True: DATA01 */ bool outdata1; /* OUT data toggle. True: DATA01 */
bool isin; /* True: IN endpoint */ bool in; /* True: IN endpoint */
volatile bool waiter; /* True: Thread is waiting for a channel event */ volatile bool waiter; /* True: Thread is waiting for a channel event */
volatile uint16_t nerrors; /* Number of errors detecgted */ volatile uint16_t nerrors; /* Number of errors detecgted */
volatile uint16_t xfrd; /* Number of bytes transferred */ volatile uint16_t xfrd; /* Number of bytes transferred */
@ -248,7 +270,7 @@ static inline void stm32_chan_freeall(FAR struct stm32_usbhost_s *priv);
static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx); static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx);
static int stm32_chan_waitsetup(FAR struct stm32_usbhost_s *priv, static int stm32_chan_waitsetup(FAR struct stm32_usbhost_s *priv,
FAR struct stm32_chan_s *chan); FAR struct stm32_chan_s *chan);
static void stm32_chan_wait(FAR struct stm32_usbhost_s *priv, static int stm32_chan_wait(FAR struct stm32_usbhost_s *priv,
FAR struct stm32_chan_s *chan); FAR struct stm32_chan_s *chan);
static void stm32_chan_wakeup(FAR struct stm32_usbhost_s *priv, static void stm32_chan_wakeup(FAR struct stm32_usbhost_s *priv,
FAR struct stm32_chan_s *chan); FAR struct stm32_chan_s *chan);
@ -256,7 +278,7 @@ static void stm32_chan_wakeup(FAR struct stm32_usbhost_s *priv,
/* Control/data transfer logic *************************************************/ /* Control/data transfer logic *************************************************/
static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx); static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx);
static inline uint32_t stm32_getframe(void); static inline uint16_t stm32_getframe(void);
static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv, static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
FAR const struct usb_ctrlreq_s *req); FAR const struct usb_ctrlreq_s *req);
static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv, static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv,
@ -298,7 +320,7 @@ static int stm32_gint_isr(int irq, FAR void *context);
static void stm32_gint_enable(void); static void stm32_gint_enable(void);
static void stm32_gint_disable(void); static void stm32_gint_disable(void);
static inline int stm32_hostinit_enable(void); static inline void stm32_hostinit_enable(void);
/* USB host controller operations **********************************************/ /* USB host controller operations **********************************************/
@ -645,7 +667,7 @@ static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx)
/* Additional setting for IN/OUT endpoints */ /* Additional setting for IN/OUT endpoints */
if (priv->chan[chidx].isin) if (priv->chan[chidx].in)
{ {
regval |= OTGFS_HCINT_BBERR; regval |= OTGFS_HCINT_BBERR;
} }
@ -665,7 +687,7 @@ static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx)
/* Additional setting for IN endpoints */ /* Additional setting for IN endpoints */
if (priv->chan[chidx].isin) if (priv->chan[chidx].in)
{ {
regval |= OTGFS_HCINT_BBERR; regval |= OTGFS_HCINT_BBERR;
} }
@ -680,7 +702,7 @@ static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx)
/* Additional setting for IN endpoints */ /* Additional setting for IN endpoints */
if (priv->chan[chidx].isin) if (priv->chan[chidx].in)
{ {
regval |= (OTGFS_HCINT_TXERR | OTGFS_HCINT_BBERR); regval |= (OTGFS_HCINT_TXERR | OTGFS_HCINT_BBERR);
} }
@ -688,7 +710,7 @@ static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx)
break; break;
} }
stm32_putreg(STM32_OTGFS_HCINTMSK(chidx), hcintmsk); stm32_putreg(STM32_OTGFS_HCINTMSK(chidx), regval);
/* Enable the top level host channel interrupt. */ /* Enable the top level host channel interrupt. */
@ -703,7 +725,7 @@ static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx)
regval = ((uint32_t)priv->chan[chidx].maxpacket << OTGFS_HCCHAR_MPSIZ_SHIFT) | regval = ((uint32_t)priv->chan[chidx].maxpacket << OTGFS_HCCHAR_MPSIZ_SHIFT) |
((uint32_t)priv->chan[chidx].epno << OTGFS_HCCHAR_EPNUM_SHIFT) | ((uint32_t)priv->chan[chidx].epno << OTGFS_HCCHAR_EPNUM_SHIFT) |
((uint32_t)priv->chan[chidx].eptype << OTGFS_HCCHAR_EPTYP_SHIFT) | ((uint32_t)priv->chan[chidx].eptype << OTGFS_HCCHAR_EPTYP_SHIFT) |
((uint32_t)priv->devaddr << OTGFS_HCCHAR_DAD_SHIFT) | ((uint32_t)priv->devaddr << OTGFS_HCCHAR_DAD_SHIFT);
/* Special case settings for low speed devices */ /* Special case settings for low speed devices */
@ -714,7 +736,7 @@ static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx)
/* Special case settings for IN endpoints */ /* Special case settings for IN endpoints */
if (priv->chan[chidx].isin) if (priv->chan[chidx].in)
{ {
regval |= OTGFS_HCCHAR_EPDIR_IN; regval |= OTGFS_HCCHAR_EPDIR_IN;
} }
@ -805,7 +827,7 @@ static int stm32_chan_wait(FAR struct stm32_usbhost_s *priv,
* wait here. * wait here.
*/ */
ret = sem_wait(chan->waitsem); ret = sem_wait(&chan->waitsem);
/* sem_wait should succeeed. But it is possible that we could be /* sem_wait should succeeed. But it is possible that we could be
* awakened by a signal too. * awakened by a signal too.
@ -840,7 +862,7 @@ static void stm32_chan_wakeup(FAR struct stm32_usbhost_s *priv,
{ {
/* Is there a thread waiting for this transfer to complete? */ /* Is there a thread waiting for this transfer to complete? */
if (priv->chan[chidx].result != EBUSY && chan->waiter) if (chan->result != EBUSY && chan->waiter)
{ {
stm32_givesem(&chan->waitsem); stm32_givesem(&chan->waitsem);
chan->waiter = false; chan->waiter = false;
@ -873,8 +895,8 @@ static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx)
* of full, maximally sized packets that can fit in the read buffer. * of full, maximally sized packets that can fit in the read buffer.
*/ */
mxpacket = priv->chan[chidx].maxpacket; maxpacket = priv->chan[chidx].maxpacket;
if (priv->chan[chidx].isin) if (priv->chan[chidx].in)
{ {
npackets = priv->chan[chidx].buflen / maxpacket; npackets = priv->chan[chidx].buflen / maxpacket;
@ -939,7 +961,7 @@ static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx)
* outgoing data into the correct TxFIFO. * outgoing data into the correct TxFIFO.
*/ */
if (!priv->chan[chidx].isin && priv->chan[chidx].buflen > 0) if (!priv->chan[chidx].in && priv->chan[chidx].buflen > 0)
{ {
/* Handle non-periodic (CTRL and BULK) OUT transfers differently than /* Handle non-periodic (CTRL and BULK) OUT transfers differently than
* perioci (INTR and ISOC) OUT transfers. * perioci (INTR and ISOC) OUT transfers.
@ -1009,7 +1031,7 @@ static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx)
static inline uint16_t stm32_getframe(void) static inline uint16_t stm32_getframe(void)
{ {
return (stm32_getreg(STM32_OTGFS_HFNUM) & OTGFS_HFNUM_FRNUM_MASK); return (uint16_t)(stm32_getreg(STM32_OTGFS_HFNUM) & OTGFS_HFNUM_FRNUM_MASK);
} }
/******************************************************************************* /*******************************************************************************
@ -1042,7 +1064,7 @@ static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
/* Set up for the wait BEFORE starting the transfer */ /* Set up for the wait BEFORE starting the transfer */
ret = stm32_chan_waitsetup(priv, chan) ret = stm32_chan_waitsetup(priv, chan);
if (ret != OK) if (ret != OK)
{ {
udbg("ERROR: Device disconnected\n"); udbg("ERROR: Device disconnected\n");
@ -1056,7 +1078,7 @@ static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
/* Wait for the transfer to complete */ /* Wait for the transfer to complete */
ret = stm32_chan_wait(priv, chan); ret = stm32_chan_wait(priv, chan);
if (ret != -EGAIN) if (ret != -EAGAIN)
{ {
udbg("Transfer failed: %d\n", ret); udbg("Transfer failed: %d\n", ret);
return ret; return ret;
@ -1084,6 +1106,7 @@ static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv,
FAR uint8_t *buffer, unsigned int buflen) FAR uint8_t *buffer, unsigned int buflen)
{ {
FAR struct stm32_chan_s *chan = &priv->chan[priv->ep0out]; FAR struct stm32_chan_s *chan = &priv->chan[priv->ep0out];
int ret;
/* Save buffer information */ /* Save buffer information */
@ -1101,22 +1124,11 @@ static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv,
/* Set the Data PID as per the outdata1 boolean */ /* Set the Data PID as per the outdata1 boolean */
if (!chan->outdata1) chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
{
/* Use PID == DATA0 */
chan->pid = OTGFS_PID_DATA0;
}
else
{
/* Put the PID 1 */
chan->pid = OTGFS_PID_DATA1 ;
}
/* Set up for the wait BEFORE starting the transfer */ /* Set up for the wait BEFORE starting the transfer */
ret = stm32_chan_waitsetup(priv, chan) ret = stm32_chan_waitsetup(priv, chan);
if (ret != OK) if (ret != OK)
{ {
udbg("ERROR: Device disconnected\n"); udbg("ERROR: Device disconnected\n");
@ -1142,9 +1154,10 @@ static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv,
*******************************************************************************/ *******************************************************************************/
static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv, static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
FAR uint8_t *buffer, unsigned int buflen); FAR uint8_t *buffer, unsigned int buflen)
{ {
FAR struct stm32_chan_s *chan = &priv->chan[pric->ep0in]; FAR struct stm32_chan_s *chan = &priv->chan[priv->ep0in];
int ret;
/* Save buffer information */ /* Save buffer information */
@ -1154,7 +1167,7 @@ static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
/* Set up for the wait BEFORE starting the transfer */ /* Set up for the wait BEFORE starting the transfer */
ret = stm32_chan_waitsetup(priv, chan) ret = stm32_chan_waitsetup(priv, chan);
if (ret != OK) if (ret != OK)
{ {
udbg("ERROR: Device disconnected\n"); udbg("ERROR: Device disconnected\n");
@ -1163,7 +1176,7 @@ static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
/* Start the transfer */ /* Start the transfer */
stm32_transfer_start(priv, pric->ep0in); stm32_transfer_start(priv, priv->ep0in);
/* Wait for the transfer to complete and return the result */ /* Wait for the transfer to complete and return the result */
@ -1182,8 +1195,8 @@ static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
static void stm32_gint_wrpacket(FAR struct stm32_usbhost_s *priv, static void stm32_gint_wrpacket(FAR struct stm32_usbhost_s *priv,
FAR uint8_t *buffer, int chidx, int buflen) FAR uint8_t *buffer, int chidx, int buflen)
{ {
FAR volatile uint32_t *fifo;
FAR uint32_t *src; FAR uint32_t *src;
uint32_t fifo;
int buflen32; int buflen32;
/* Get the number of 32-byte words associated with this byte size */ /* Get the number of 32-byte words associated with this byte size */
@ -1275,7 +1288,7 @@ static inline void stm32_gint_hcinisr(FAR struct stm32_usbhost_s *priv,
uint32_t hcint; uint32_t hcint;
uint32_t hcintmsk; uint32_t hcintmsk;
uint32_t hcchar; uint32_t hcchar;
uint32_t hctsiz; uint32_t pending;
unsigned int eptype; unsigned int eptype;
/* Read the HCINT register to get the pending HC interrupts. Read the /* Read the HCINT register to get the pending HC interrupts. Read the
@ -1647,8 +1660,6 @@ static inline void stm32_gint_hcoutisr(FAR struct stm32_usbhost_s *priv,
else if ((pending & OTGFS_HCINT_NAK) != 0) else if ((pending & OTGFS_HCINT_NAK) != 0)
{ {
uint32_t regval;
/* Clear the error count */ /* Clear the error count */
chan->nerrors = 0; chan->nerrors = 0;
@ -1782,7 +1793,7 @@ static inline void stm32_gint_hcoutisr(FAR struct stm32_usbhost_s *priv,
else if (chan->chstate == CHSTATE_NAK || else if (chan->chstate == CHSTATE_NAK ||
chan->chstate == CHSTATE_NYET) chan->chstate == CHSTATE_NYET)
{ {
chan->result = EGAIN; chan->result = EAGAIN;
} }
else if (chan->chstate == CHSTATE_STALL) else if (chan->chstate == CHSTATE_STALL)
{ {
@ -1832,7 +1843,7 @@ static void stm32_gint_connected(FAR struct stm32_usbhost_s *priv)
ullvdbg("Connected\n"); ullvdbg("Connected\n");
priv->connected = true; priv->connected = true;
DEBUGASSERT(priv->smstate == SMTATE_IDLE); DEBUGASSERT(priv->smstate == SMSTATE_DETACHED);
/* Notify any waiters */ /* Notify any waiters */
@ -1857,12 +1868,11 @@ static void stm32_gint_disconnected(FAR struct stm32_usbhost_s *priv)
{ {
/* Were we previously connected? */ /* Were we previously connected? */
if !priv->connected) if (!priv->connected)
{ {
/* Yes.. then we no longer connected */ /* Yes.. then we no longer connected */
ullvdbg("Disconnected\n"); ullvdbg("Disconnected\n");
priv->connected = false;
/* Are we bound to a class driver? */ /* Are we bound to a class driver? */
@ -1876,9 +1886,12 @@ static void stm32_gint_disconnected(FAR struct stm32_usbhost_s *priv)
/* Re-Initilaize Host for new Enumeration */ /* Re-Initilaize Host for new Enumeration */
stm32_swreset(priv);
stm32_chan_freeall(priv);
priv->smstate = SMSTATE_DETACHED; priv->smstate = SMSTATE_DETACHED;
priv->ep0size = STM32_EP0_MAX_PACKET_SIZE;
priv->devaddr = STM32_DEF_DEVADDR;
priv->connected = false;
priv->lowspeed = false;
stm32_chan_freeall(priv);
/* Notify any waiters that there is a change in the connection state */ /* Notify any waiters that there is a change in the connection state */
@ -1933,7 +1946,7 @@ static inline void stm32_gint_rxflvlisr(FAR struct stm32_usbhost_s *priv)
/* Disable the RxFIFO non-empty interrupt */ /* Disable the RxFIFO non-empty interrupt */
intmsk = stm32_getreg(STM32_OTGFS_GINTMSK) intmsk = stm32_getreg(STM32_OTGFS_GINTMSK);
intmsk &= ~OTGFS_GINT_RXFLVL; intmsk &= ~OTGFS_GINT_RXFLVL;
stm32_putreg(STM32_OTGFS_GINTMSK, intmsk); stm32_putreg(STM32_OTGFS_GINTMSK, intmsk);
@ -1957,18 +1970,16 @@ static inline void stm32_gint_rxflvlisr(FAR struct stm32_usbhost_s *priv)
{ {
/* Read the data into the host buffer. */ /* Read the data into the host buffer. */
int bcnt = (grxsts & OTGFS_GRXSTSH_BCNT_MASK) >> OTGFS_GRXSTSH_BCNT_SHIFT; bcnt = (grxsts & OTGFS_GRXSTSH_BCNT_MASK) >> OTGFS_GRXSTSH_BCNT_SHIFT;
if (bcnt > 0 && priv->chan[chidx].buffer != NULL) if (bcnt > 0 && priv->chan[chidx].buffer != NULL)
{ {
/* Transfer the packet from the Rx FIFO into the user buffer */ /* Transfer the packet from the Rx FIFO into the user buffer */
FAR uint32_t *dest = (FAR uint32_t *)priv->chan[chidx].buffer; dest = (FAR uint32_t *)priv->chan[chidx].buffer;
uint32_t fifo = STM32_OTGFS_DFIFO_HCH(0); fifo = STM32_OTGFS_DFIFO_HCH(0);
uint32_t hctsiz; bcnt32 = (bcnt + 3) >> 2;
int bcnt32 = (bcnt + 3) >> 2;
for (i = 0; i < count32b; i++, dest += 4) for (i = 0; i < bcnt32; i++)
{ {
*dest++ = stm32_getreg(fifo); *dest++ = stm32_getreg(fifo);
} }
@ -2043,7 +2054,7 @@ static inline void stm32_gint_nptxfeisr(FAR struct stm32_usbhost_s *priv)
/* Get the number of words remaining to be sent */ /* Get the number of words remaining to be sent */
buflen = priv->chan[chidx].buflen buflen = priv->chan[chidx].buflen;
buflen32 = (buflen + 3) >> 2; buflen32 = (buflen + 3) >> 2;
/* Break out of the loop if either (a) there is nothing more to be /* Break out of the loop if either (a) there is nothing more to be
@ -2120,7 +2131,7 @@ static inline void stm32_gint_ptxfeisr(FAR struct stm32_usbhost_s *priv)
/* Get the number of words remaining to be sent */ /* Get the number of words remaining to be sent */
buflen = priv->chan[chidx].buflen buflen = priv->chan[chidx].buflen;
buflen32 = (buflen + 3) >> 2; buflen32 = (buflen + 3) >> 2;
/* Break out of the loop if either (a) there is nothing more to be /* Break out of the loop if either (a) there is nothing more to be
@ -2269,8 +2280,6 @@ static inline void stm32_gint_hprtisr(FAR struct stm32_usbhost_s *priv)
if ((hprt & OTGFS_HPRT_PENA) != 0) if ((hprt & OTGFS_HPRT_PENA) != 0)
{ {
uint32_t hcfg;
/* Yes.. handle the new connection event */ /* Yes.. handle the new connection event */
stm32_gint_connected(priv); stm32_gint_connected(priv);
@ -2328,8 +2337,6 @@ static inline void stm32_gint_hprtisr(FAR struct stm32_usbhost_s *priv)
static inline void stm32_gint_discisr(FAR struct stm32_usbhost_s *priv) static inline void stm32_gint_discisr(FAR struct stm32_usbhost_s *priv)
{ {
uint32_t regval;
/* Handle the disconnection event */ /* Handle the disconnection event */
stm32_gint_disconnected(priv); stm32_gint_disconnected(priv);
@ -2410,49 +2417,49 @@ static int stm32_gint_isr(int irq, FAR void *context)
/* Handle the RxFIFO non-empty interrupt */ /* Handle the RxFIFO non-empty interrupt */
if ((pending & OTGFS_GINT_RXFLVL)) != 0) if ((pending & OTGFS_GINT_RXFLVL) != 0)
{ {
stm32_gint_rxflvlisr(priv); stm32_gint_rxflvlisr(priv);
} }
/* Handle the non-periodic TxFIFO empty interrupt */ /* Handle the non-periodic TxFIFO empty interrupt */
if ((pending & OTGFS_GINT_NPTXFE)) != 0) if ((pending & OTGFS_GINT_NPTXFE) != 0)
{ {
stm32_gint_nptxfeisr(priv); stm32_gint_nptxfeisr(priv);
} }
/* Handle the periodic TxFIFO empty interrupt */ /* Handle the periodic TxFIFO empty interrupt */
if ((pending & OTGFS_GINT_PTXFE)) != 0) if ((pending & OTGFS_GINT_PTXFE) != 0)
{ {
stm32_gint_ptxfeisr(priv); stm32_gint_ptxfeisr(priv);
} }
/* Handle the host channels interrupt */ /* Handle the host channels interrupt */
if ((pending & OTGFS_GINT_HC)) != 0) if ((pending & OTGFS_GINT_HC) != 0)
{ {
stm32_gint_hcisr(priv); stm32_gint_hcisr(priv);
} }
/* Handle the host port interrupt */ /* Handle the host port interrupt */
if ((pending & OTGFS_GINT_HPRT)) != 0) if ((pending & OTGFS_GINT_HPRT) != 0)
{ {
stm32_gint_hprtisr(priv); stm32_gint_hprtisr(priv);
} }
/* Handle the disconnect detected interrupt */ /* Handle the disconnect detected interrupt */
if ((pending & OTGFS_GINT_DISC)) != 0) if ((pending & OTGFS_GINT_DISC) != 0)
{ {
stm32_gint_discisr(priv); stm32_gint_discisr(priv);
} }
/* Handle the incomplete isochronous OUT transfer */ /* Handle the incomplete isochronous OUT transfer */
if ((pending & OTGFS_GINT_IISOOXFR)) != 0) if ((pending & OTGFS_GINT_IISOOXFR) != 0)
{ {
stm32_gint_iisooxfrisr(priv); stm32_gint_iisooxfrisr(priv);
} }
@ -2481,7 +2488,7 @@ static void stm32_gint_enable(void)
/* Set the GINTMSK bit to unmask the interrupt */ /* Set the GINTMSK bit to unmask the interrupt */
regval = stm32_getreg(STM32_OTGFS_GAHBCFG) regval = stm32_getreg(STM32_OTGFS_GAHBCFG);
regval |= OTGFS_GAHBCFG_GINTMSK; regval |= OTGFS_GAHBCFG_GINTMSK;
stm32_putreg(OTGFS_GAHBCFG_GINTMSK, regval); stm32_putreg(OTGFS_GAHBCFG_GINTMSK, regval);
} }
@ -2492,7 +2499,7 @@ static void stm32_gint_disable(void)
/* Clear the GINTMSK bit to mask the interrupt */ /* Clear the GINTMSK bit to mask the interrupt */
regval = stm32_getreg(STM32_OTGFS_GAHBCFG) regval = stm32_getreg(STM32_OTGFS_GAHBCFG);
regval &= ~OTGFS_GAHBCFG_GINTMSK; regval &= ~OTGFS_GAHBCFG_GINTMSK;
stm32_putreg(OTGFS_GAHBCFG_GINTMSK, regval); stm32_putreg(OTGFS_GAHBCFG_GINTMSK, regval);
} }
@ -2513,6 +2520,8 @@ static void stm32_gint_disable(void)
static inline void stm32_hostinit_enable(void) static inline void stm32_hostinit_enable(void)
{ {
uint32_t regval;
/* Disable all interrupts. */ /* Disable all interrupts. */
stm32_putreg(STM32_OTGFS_GINTMSK, 0); stm32_putreg(STM32_OTGFS_GINTMSK, 0);
@ -2671,7 +2680,7 @@ static int stm32_enumerate(FAR struct usbhost_driver_s *drvr)
priv->ep0out = chidx; priv->ep0out = chidx;
priv->chan[chidx].epno = 0; priv->chan[chidx].epno = 0;
priv->chan[chidx].isin = false; priv->chan[chidx].in = false;
priv->chan[chidx].eptype = OTGFS_EPTYPE_CTRL; priv->chan[chidx].eptype = OTGFS_EPTYPE_CTRL;
priv->chan[chidx].maxpacket = STM32_EP0_DEF_PACKET_SIZE; priv->chan[chidx].maxpacket = STM32_EP0_DEF_PACKET_SIZE;
priv->chan[chidx].indata1 = false; priv->chan[chidx].indata1 = false;
@ -2684,7 +2693,7 @@ static int stm32_enumerate(FAR struct usbhost_driver_s *drvr)
priv->ep0in = chidx; priv->ep0in = chidx;
priv->chan[chidx].epno = 0; priv->chan[chidx].epno = 0;
priv->chan[chidx].isin = true; priv->chan[chidx].in = true;
priv->chan[chidx].eptype = OTGFS_EPTYPE_CTRL; priv->chan[chidx].eptype = OTGFS_EPTYPE_CTRL;
priv->chan[chidx].maxpacket = STM32_EP0_DEF_PACKET_SIZE; priv->chan[chidx].maxpacket = STM32_EP0_DEF_PACKET_SIZE;
priv->chan[chidx].indata1 = false; priv->chan[chidx].indata1 = false;
@ -2713,7 +2722,7 @@ static int stm32_enumerate(FAR struct usbhost_driver_s *drvr)
*/ */
uvdbg("Enumerate the device\n"); uvdbg("Enumerate the device\n");
priv->smstate = SMSTATE_ENUM priv->smstate = SMSTATE_ENUM;
ret = usbhost_enumerate(drvr, 1, &priv->class); ret = usbhost_enumerate(drvr, 1, &priv->class);
/* The enumeration may fail either because of some HCD interfaces failure /* The enumeration may fail either because of some HCD interfaces failure
@ -2810,7 +2819,7 @@ static int stm32_ep0configure(FAR struct usbhost_driver_s *drvr, uint8_t funcadd
************************************************************************************/ ************************************************************************************/
static int stm32_epalloc(FAR struct usbhost_driver_s *drvr, static int stm32_epalloc(FAR struct usbhost_driver_s *drvr,
FAR const FAR struct usbhost_epdesc_s *epdesc, FAR const struct usbhost_epdesc_s *epdesc,
FAR usbhost_ep_t *ep) FAR usbhost_ep_t *ep)
{ {
FAR struct stm32_usbhost_s *priv = (FAR struct stm32_usbhost_s *)drvr; FAR struct stm32_usbhost_s *priv = (FAR struct stm32_usbhost_s *)drvr;
@ -2830,7 +2839,7 @@ static int stm32_epalloc(FAR struct usbhost_driver_s *drvr,
/* Allocate a host channel for the endpoint */ /* Allocate a host channel for the endpoint */
chidx = stm32_chan_alloc(priv) chidx = stm32_chan_alloc(priv);
if (chidx < 0) if (chidx < 0)
{ {
udbg("Failed to allocate a host channel\n"); udbg("Failed to allocate a host channel\n");
@ -2846,9 +2855,9 @@ static int stm32_epalloc(FAR struct usbhost_driver_s *drvr,
chan = &priv->chan[chidx]; chan = &priv->chan[chidx];
chan->epno = epdesc->addr & USB_EPNO_MASK; chan->epno = epdesc->addr & USB_EPNO_MASK;
chan->isin = ((epdesc->addr & USB_DIR_MASK) == USB_DIR_IN); chan->in = epdesc->in;
chan->eptype = eptype->attr & USB_EP_ATTR_XFERTYPE_MASK; chan->eptype = epdesc->xfrtype;
chan->maxpacket = stm32_getle16(epdesc->maxpacket); chan->maxpacket = epdesc->mxpacketsize;
chan->indata1 = false; chan->indata1 = false;
chan->outdata1 = false; chan->outdata1 = false;
@ -2891,7 +2900,7 @@ static int stm32_epfree(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep)
struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr; struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
int chidx = (int)ep; int chidx = (int)ep;
DEBUGASSERT(priv && ep < STM32_MAX_TX_FIFOS); DEBUGASSERT(priv && chidx < STM32_MAX_TX_FIFOS);
/* We must have exclusive access to the USB host hardware and state structures */ /* We must have exclusive access to the USB host hardware and state structures */
@ -3109,6 +3118,7 @@ static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
{ {
struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr; struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
uint16_t buflen; uint16_t buflen;
int retries;
int ret; int ret;
DEBUGASSERT(drvr && req); DEBUGASSERT(drvr && req);
@ -3272,7 +3282,7 @@ static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
unsigned int chidx = (unsigned int)ep; unsigned int chidx = (unsigned int)ep;
int ret; int ret;
DEBUGASSERT(priv && buffer && ep < STM32_MAX_TX_FIFOS && buflen > 0); DEBUGASSERT(priv && buffer && chidx < STM32_MAX_TX_FIFOS && buflen > 0);
chan = &priv->chan[chidx]; chan = &priv->chan[chidx];
/* We must have exclusive access to the USB host hardware and state structures */ /* We must have exclusive access to the USB host hardware and state structures */
@ -3315,7 +3325,7 @@ static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
{ {
/* Handle the bulk transfer based on the direction of the transfer. */ /* Handle the bulk transfer based on the direction of the transfer. */
if (chan->isin) if (chan->in)
{ {
/* Setup the IN data PID */ /* Setup the IN data PID */
@ -3336,7 +3346,7 @@ static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
* transfer. * transfer.
*/ */
if (chan->isin) if (chan->in)
{ {
/* Setup the OUT data PID */ /* Setup the OUT data PID */
@ -3436,7 +3446,7 @@ static void stm32_portreset(FAR struct stm32_usbhost_s *priv)
uint32_t regval; uint32_t regval;
regval = stm32_getreg(STM32_OTGFS_HPRT); regval = stm32_getreg(STM32_OTGFS_HPRT);
retval &= ~(OTGFS_HPRT_PENA|OTGFS_HPRT_PCDET|OTGFS_HPRT_PENCHNG|OTGFS_HPRT_POCCHNG); regval &= ~(OTGFS_HPRT_PENA|OTGFS_HPRT_PCDET|OTGFS_HPRT_PENCHNG|OTGFS_HPRT_POCCHNG);
regval |= OTGFS_HPRT_PRST; regval |= OTGFS_HPRT_PRST;
stm32_putreg(STM32_OTGFS_HPRT, regval); stm32_putreg(STM32_OTGFS_HPRT, regval);
@ -3548,7 +3558,7 @@ static void stm32_vbusdrive(FAR struct stm32_usbhost_s *priv, bool state)
/* Enable/disable the external charge pump */ /* Enable/disable the external charge pump */
stm32_usbhost_vbusdrive(state); stm32_usbhost_vbusdrive(0, state);
/* Turn on the Host port power. */ /* Turn on the Host port power. */
@ -3591,7 +3601,6 @@ static void stm32_host_initialize(FAR struct stm32_usbhost_s *priv)
{ {
uint32_t regval; uint32_t regval;
uint32_t offset; uint32_t offset;
int ret;
int i; int i;
/* Restart the PHY Clock */ /* Restart the PHY Clock */
@ -3623,13 +3632,13 @@ static void stm32_host_initialize(FAR struct stm32_usbhost_s *priv)
/* Setup the host non-periodic Tx FIFO size (HNPTXFSIZ) */ /* Setup the host non-periodic Tx FIFO size (HNPTXFSIZ) */
regval = (offset | (CONFIG_STM32_OTGFS_NPTXFIFO_SIZE << OTGFS_HNPTXFSIZ_NPTXFD_MASK); regval = (offset | (CONFIG_STM32_OTGFS_NPTXFIFO_SIZE << OTGFS_HNPTXFSIZ_NPTXFD_SHIFT));
stm32_putreg(STM32_OTGFS_DIEPTXF0_HNPTXFSIZ, regval); stm32_putreg(STM32_OTGFS_HNPTXFSIZ, regval);
offset += CONFIG_STM32_OTGFS_NPTXFIFO_SIZE offset += CONFIG_STM32_OTGFS_NPTXFIFO_SIZE;
/* Set up the host periodic Tx fifo size register (HPTXFSIZ) */ /* Set up the host periodic Tx fifo size register (HPTXFSIZ) */
regval = (offset | (CONFIG_STM32_OTGFS_PTXFIFO_SIZE << OTGFS_HPTXFSIZ_PTXFD_SHIFT); regval = (offset | (CONFIG_STM32_OTGFS_PTXFIFO_SIZE << OTGFS_HPTXFSIZ_PTXFD_SHIFT));
stm32_putreg(STM32_OTGFS_HPTXFSIZ, regval); stm32_putreg(STM32_OTGFS_HPTXFSIZ, regval);
/* If OTG were supported, we sould need to clear HNP enable bit in the /* If OTG were supported, we sould need to clear HNP enable bit in the
@ -3657,8 +3666,7 @@ static void stm32_host_initialize(FAR struct stm32_usbhost_s *priv)
/* Enable host interrupts */ /* Enable host interrupts */
stm32_hostinit_enable(priv); stm32_hostinit_enable();
return OK;
} }
/******************************************************************************* /*******************************************************************************
@ -3692,7 +3700,7 @@ static inline void stm32_sw_initialize(FAR struct stm32_usbhost_s *priv)
/* Put all of the channels back in their initial, allocated state */ /* Put all of the channels back in their initial, allocated state */
memset(priv-chan, 0, STM32_MAX_TX_FIFOS * sizeof(struct stm32_chan_s)); memset(priv->chan, 0, STM32_MAX_TX_FIFOS * sizeof(struct stm32_chan_s));
/* Initialize each channel */ /* Initialize each channel */
@ -3720,7 +3728,7 @@ static inline void stm32_sw_initialize(FAR struct stm32_usbhost_s *priv)
static inline int stm32_hw_initialize(FAR struct stm32_usbhost_s *priv) static inline int stm32_hw_initialize(FAR struct stm32_usbhost_s *priv)
{ {
uint32_t regval; uint32_t regval;
int ret; unsigned long timeout;
/* Set the PHYSEL bit in the GUSBCFG register to select the OTG FS serial /* Set the PHYSEL bit in the GUSBCFG register to select the OTG FS serial
* transceiver: "This bit is always 1 with write-only access" * transceiver: "This bit is always 1 with write-only access"
@ -3828,7 +3836,6 @@ FAR struct usbhost_driver_s *usbhost_initialize(int controller)
*/ */
FAR struct stm32_usbhost_s *priv = &g_usbhost; FAR struct stm32_usbhost_s *priv = &g_usbhost;
int ret;
/* Sanity checks */ /* Sanity checks */
@ -3896,3 +3903,5 @@ FAR struct usbhost_driver_s *usbhost_initialize(int controller)
up_enable_irq(STM32_IRQ_OTGFS); up_enable_irq(STM32_IRQ_OTGFS);
return &priv->drvr; return &priv->drvr;
} }
#endif /* CONFIG_USBHOST && CONFIG_STM32_OTGFS */

View File

@ -49,6 +49,32 @@
#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST) #if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST)
/************************************************************************************
* Public Functions
************************************************************************************/
/*
* STM32 USB OTG FS Host Driver Support
*
* Pre-requisites
*
* CONFIG_USBHOST - Enable general USB host support
* CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
* CONFIG_STM32_SYSCFG - Needed
*
* Options:
*
* CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words.
* Default 128 (512 bytes)
* CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO
* in 32-bit words. Default 96 (384 bytes)
* CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit
* words. Default 96 (384 bytes)
* CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever
* want to do that?
* CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access
* debug. Depends on CONFIG_DEBUG.
*/
/************************************************************************************ /************************************************************************************
* Public Functions * Public Functions
************************************************************************************/ ************************************************************************************/

View File

@ -669,6 +669,27 @@ STM3220G-EVAL-specific Configuration Options
STM3220G-EVAL LCD Hardware Configuration STM3220G-EVAL LCD Hardware Configuration
STM32 USB OTG FS Host Driver Support
Pre-requisites
CONFIG_USBHOST - Enable general USB host support
CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
CONFIG_STM32_SYSCFG - Needed
Options:
CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words.
Default 128 (512 bytes)
CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO
in 32-bit words. Default 96 (384 bytes)
CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit
words. Default 96 (384 bytes)
CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever
want to do that?
CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access
debug. Depends on CONFIG_DEBUG.
Configurations Configurations
============== ==============
@ -834,7 +855,15 @@ Where <subdir> is one of the following:
CONFIG_NX=y : Enable graphics suppport CONFIG_NX=y : Enable graphics suppport
CONFIG_MM_REGIONS=2 : When FSMC is enabled, so is the on-board SRAM memory region CONFIG_MM_REGIONS=2 : When FSMC is enabled, so is the on-board SRAM memory region
8. This configuration requires that jumper JP22 be set to enable RS-232 operation. 8. USB OTG FS Device or Host Support
CONFIG_USBDEV - Enable USB device support
CONFIG_USBHOST - Enable USB host support
CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
CONFIG_STM32_SYSCFG - Needed
CONFIG_SCHED_WORKQUEUE - Worker thread support is required
9. This configuration requires that jumper JP22 be set to enable RS-232 operation.
nsh2: nsh2:
----- -----

View File

@ -998,7 +998,7 @@ CONFIG_STMPE811_THRESHX=26
CONFIG_STMPE811_THRESHY=34 CONFIG_STMPE811_THRESHY=34
# #
# USB Device Configuration # STM32 USB OTG FS Device Configuration
# #
# CONFIG_USBDEV # CONFIG_USBDEV
# Enables USB device support # Enables USB device support
@ -1025,6 +1025,36 @@ CONFIG_USBDEV_MAXPOWER=100
CONFIG_USBDEV_TRACE=n CONFIG_USBDEV_TRACE=n
CONFIG_USBDEV_TRACE_NRECORDS=128 CONFIG_USBDEV_TRACE_NRECORDS=128
#
# STM32 USB OTG FS Host Configuration
#
# Pre-requisites
#
# CONFIG_USBHOST - Enable general USB host support
# CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
# CONFIG_STM32_SYSCFG - Needed
# CONFIG_SCHED_WORKQUEUE - Worker thread support is required
#
# Options:
#
# CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words.
# Default 128 (512 bytes)
# CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO
# in 32-bit words. Default 96 (384 bytes)
# CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit
# words. Default 96 (384 bytes)
# CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever
# want to do that?
# CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access
# debug. Depends on CONFIG_DEBUG.
#
CONFIG_USBHOST=n
# ONFIG_STM32_OTGFS_RXFIFO_SIZE
#CONFIG_STM32_OTGFS_NPTXFIFO_SIZE
#CONFIG_STM32_OTGFS_PTXFIFO_SIZE
CONFIG_STM32_OTGFS_SOFINTR=n
CONFIG_STM32_USBHOST_REGDEBUG=n
# #
# USB Serial Device Configuration # USB Serial Device Configuration
# #

View File

@ -55,7 +55,12 @@
# include <nuttx/mmcsd.h> # include <nuttx/mmcsd.h>
#endif #endif
#ifdef CONFIG_STM32_OTGFS
# include "stm32_usbhost.h"
#endif
#include "stm32_internal.h" #include "stm32_internal.h"
#include "stm3220g-internal.h"
/**************************************************************************** /****************************************************************************
* Pre-Processor Definitions * Pre-Processor Definitions
@ -67,29 +72,19 @@
#undef CONFIG_STM32_SPI1 #undef CONFIG_STM32_SPI1
/* PORT and SLOT number probably depend on the board configuration */ /* MMCSD PORT and SLOT number probably depend on the board configuration */
#ifdef CONFIG_ARCH_BOARD_STM3220G_EVAL #define HAVE_USBDEV 1
# define CONFIG_NSH_HAVEUSBDEV 1 #define HAVE_MMCSD 1
# define CONFIG_NSH_HAVEMMCSD 1 #define HAVE_USBHOST 1
# if defined(CONFIG_NSH_MMCSDSLOTNO) && CONFIG_NSH_MMCSDSLOTNO != 0
#if defined(CONFIG_NSH_MMCSDSLOTNO) && CONFIG_NSH_MMCSDSLOTNO != 0
# error "Only one MMC/SD slot" # error "Only one MMC/SD slot"
# undef CONFIG_NSH_MMCSDSLOTNO # undef CONFIG_NSH_MMCSDSLOTNO
# endif
# ifndef CONFIG_NSH_MMCSDSLOTNO
# define CONFIG_NSH_MMCSDSLOTNO 0
# endif
#else
/* Add configuration for new STM32 boards here */
# error "Unrecognized STM32 board"
# undef CONFIG_NSH_HAVEUSBDEV
# undef CONFIG_NSH_HAVEMMCSD
#endif #endif
/* Can't support USB features if USB is not enabled */ #ifndef CONFIG_NSH_MMCSDSLOTNO
# define CONFIG_NSH_MMCSDSLOTNO 0
#ifndef CONFIG_USBDEV
# undef CONFIG_NSH_HAVEUSBDEV
#endif #endif
/* Can't support MMC/SD features if mountpoints are disabled or if SDIO support /* Can't support MMC/SD features if mountpoints are disabled or if SDIO support
@ -97,13 +92,32 @@
*/ */
#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO) #if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO)
# undef CONFIG_NSH_HAVEMMCSD # undef HAVE_MMCSD
#endif #endif
#ifndef CONFIG_NSH_MMCSDMINOR #ifndef CONFIG_NSH_MMCSDMINOR
# define CONFIG_NSH_MMCSDMINOR 0 # define CONFIG_NSH_MMCSDMINOR 0
#endif #endif
/* Can't support USB host or device features if USB OTG FS is not enabled */
#ifndef CONFIG_STM32_OTGFS
# undef HAVE_USBDEV
# undef HAVE_USBHOST
#endif
/* Can't support USB device is USB device is not enabled */
#ifndef CONFIG_USBDEV
# undef HAVE_USBDEV
#endif
/* Can't support USB host is USB host is not enabled */
#ifndef CONFIG_USBHOST
# undef HAVE_USBHOST
#endif
/* Debug ********************************************************************/ /* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS #ifdef CONFIG_CPP_HAVE_VARARGS
@ -138,8 +152,10 @@ int nsh_archinitialize(void)
FAR struct spi_dev_s *spi; FAR struct spi_dev_s *spi;
FAR struct mtd_dev_s *mtd; FAR struct mtd_dev_s *mtd;
#endif #endif
#ifdef CONFIG_NSH_HAVEMMCSD #ifdef HAVE_MMCSD
FAR struct sdio_dev_s *sdio; FAR struct sdio_dev_s *sdio;
#endif
#if defined(HAVE_MMCSD) || defined (HAVE_USBHOST)
int ret; int ret;
#endif #endif
@ -169,7 +185,7 @@ int nsh_archinitialize(void)
/* Mount the SDIO-based MMC/SD block driver */ /* Mount the SDIO-based MMC/SD block driver */
#ifdef CONFIG_NSH_HAVEMMCSD #ifdef HAVE_MMCSD
/* First, get an instance of the SDIO interface */ /* First, get an instance of the SDIO interface */
message("nsh_archinitialize: Initializing SDIO slot %d\n", message("nsh_archinitialize: Initializing SDIO slot %d\n",
@ -203,7 +219,7 @@ int nsh_archinitialize(void)
* will monitor for USB connection and disconnection events. * will monitor for USB connection and disconnection events.
*/ */
#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST) #ifdef HAVE_USBHOST
ret = stm32_usbhost_initialize(); ret = stm32_usbhost_initialize();
if (ret != OK) if (ret != OK)
{ {

View File

@ -43,6 +43,8 @@
#include <sys/types.h> #include <sys/types.h>
#include <stdint.h> #include <stdint.h>
#include <stdbool.h> #include <stdbool.h>
#include <sched.h>
#include <errno.h>
#include <debug.h> #include <debug.h>
#include <nuttx/usb/usbdev.h> #include <nuttx/usb/usbdev.h>
@ -59,10 +61,10 @@
* Definitions * Definitions
************************************************************************************/ ************************************************************************************/
#if defined(CONFIG_USBDEV) || defined(CONFIG_USBDEV) #if defined(CONFIG_USBDEV) || defined(CONFIG_USBHOST)
# define HAVE_USB 1 # define HAVE_USB 1
#else #else
# warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBDEV" # warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBHOST"
# undef HAVE_USB # undef HAVE_USB
#endif #endif
@ -78,7 +80,7 @@
* Private Data * Private Data
************************************************************************************/ ************************************************************************************/
#ifdef CONFIG_NSH_HAVEUSBHOST #ifdef CONFIG_USBHOST
static struct usbhost_driver_s *g_drvr; static struct usbhost_driver_s *g_drvr;
#endif #endif
@ -94,7 +96,7 @@ static struct usbhost_driver_s *g_drvr;
* *
****************************************************************************/ ****************************************************************************/
#ifdef CONFIG_NSH_HAVEUSBHOST #ifdef CONFIG_USBHOST
static int usbhost_waiter(int argc, char *argv[]) static int usbhost_waiter(int argc, char *argv[])
{ {
bool connected = false; bool connected = false;

View File

@ -831,6 +831,28 @@ STM3240G-EVAL-specific Configuration Options
CONFIG_STM32_ILI9320_DISABLE (includes ILI9321) CONFIG_STM32_ILI9320_DISABLE (includes ILI9321)
CONFIG_STM32_ILI9325_DISABLE CONFIG_STM32_ILI9325_DISABLE
STM32 USB OTG FS Host Driver Support
Pre-requisites
CONFIG_USBHOST - Enable USB host support
CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
CONFIG_STM32_SYSCFG - Needed
CONFIG_SCHED_WORKQUEUE - Worker thread support is required
Options:
CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words.
Default 128 (512 bytes)
CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO
in 32-bit words. Default 96 (384 bytes)
CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit
words. Default 96 (384 bytes)
CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever
want to do that?
CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access
debug. Depends on CONFIG_DEBUG.
Configurations Configurations
============== ==============
@ -996,7 +1018,15 @@ Where <subdir> is one of the following:
CONFIG_NX=y : Enable graphics suppport CONFIG_NX=y : Enable graphics suppport
CONFIG_MM_REGIONS=3 : When FSMC is enabled, so is the on-board SRAM memory region CONFIG_MM_REGIONS=3 : When FSMC is enabled, so is the on-board SRAM memory region
8. This configuration requires that jumper JP22 be set to enable RS-232 8. USB OTG FS Device or Host Support
CONFIG_USBDEV - Enable USB device support
CONFIG_USBHOST - Enable USB host support
CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
CONFIG_STM32_SYSCFG - Needed
CONFIG_SCHED_WORKQUEUE - Worker thread support is required
9. This configuration requires that jumper JP22 be set to enable RS-232
operation. operation.
nsh2: nsh2:

View File

@ -883,6 +883,29 @@ STM32F4Discovery-specific Configuration Options
CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default: CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default:
4-bit transfer mode. 4-bit transfer mode.
STM32 USB OTG FS Host Driver Support
Pre-requisites
CONFIG_USBDEV - Enable USB device support
CONFIG_USBHOST - Enable USB host support
CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
CONFIG_STM32_SYSCFG - Needed
CONFIG_SCHED_WORKQUEUE - Worker thread support is required
Options:
CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words.
Default 128 (512 bytes)
CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO
in 32-bit words. Default 96 (384 bytes)
CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit
words. Default 96 (384 bytes)
CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever
want to do that?
CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access
debug. Depends on CONFIG_DEBUG.
Configurations Configurations
============== ==============

View File

@ -122,8 +122,8 @@ static void usbhost_putle16(uint8_t *dest, uint16_t val)
* *
*******************************************************************************/ *******************************************************************************/
static inline int usbhost_devdesc(const struct usb_devdesc_s *devdesc, static inline int usbhost_devdesc(FAR const struct usb_devdesc_s *devdesc,
struct usbhost_id_s *id) FAR struct usbhost_id_s *id)
{ {
/* Clear the ID info */ /* Clear the ID info */
@ -131,7 +131,7 @@ static inline int usbhost_devdesc(const struct usb_devdesc_s *devdesc,
/* Pick off the class ID info */ /* Pick off the class ID info */
id->base = devdesc->class; id->base = devdesc->classid;
id->subclass = devdesc->subclass; id->subclass = devdesc->subclass;
id->proto = devdesc->protocol; id->proto = devdesc->protocol;
@ -194,7 +194,7 @@ static inline int usbhost_configdesc(const uint8_t *configdesc, int cfglen,
*/ */
DEBUGASSERT(remaining >= sizeof(struct usb_ifdesc_s)); DEBUGASSERT(remaining >= sizeof(struct usb_ifdesc_s));
id->base = ifdesc->class; id->base = ifdesc->classid;
id->subclass = ifdesc->subclass; id->subclass = ifdesc->subclass;
id->proto = ifdesc->protocol; id->proto = ifdesc->protocol;
uvdbg("class:%d subclass:%d protocol:%d\n", uvdbg("class:%d subclass:%d protocol:%d\n",

View File

@ -255,7 +255,9 @@ static inline int usbhost_devinit(FAR struct usbhost_state_s *priv);
static inline uint16_t usbhost_getle16(const uint8_t *val); static inline uint16_t usbhost_getle16(const uint8_t *val);
static inline void usbhost_putle16(uint8_t *dest, uint16_t val); static inline void usbhost_putle16(uint8_t *dest, uint16_t val);
static inline uint32_t usbhost_getle32(const uint8_t *val); static inline uint32_t usbhost_getle32(const uint8_t *val);
#if 0 /* Not used */
static void usbhost_putle32(uint8_t *dest, uint32_t val); static void usbhost_putle32(uint8_t *dest, uint32_t val);
#endif
/* Transfer descriptor memory management */ /* Transfer descriptor memory management */
@ -701,7 +703,7 @@ static int usbhost_kbdpoll(int argc, char *argv[])
#if defined(CONFIG_DEBUG_USB) && defined(CONFIG_DEBUG_VERBOSE) #if defined(CONFIG_DEBUG_USB) && defined(CONFIG_DEBUG_VERBOSE)
unsigned int npolls = 0; unsigned int npolls = 0;
#endif #endif
unsigned int nerrors; unsigned int nerrors = 0;
int ret; int ret;
uvdbg("Started\n"); uvdbg("Started\n");
@ -1381,6 +1383,7 @@ static inline uint32_t usbhost_getle32(const uint8_t *val)
* *
****************************************************************************/ ****************************************************************************/
#if 0 /* Not used */
static void usbhost_putle32(uint8_t *dest, uint32_t val) static void usbhost_putle32(uint8_t *dest, uint32_t val)
{ {
/* Little endian means LS halfword first in byte stream */ /* Little endian means LS halfword first in byte stream */
@ -1388,6 +1391,7 @@ static void usbhost_putle32(uint8_t *dest, uint32_t val)
usbhost_putle16(dest, (uint16_t)(val & 0xffff)); usbhost_putle16(dest, (uint16_t)(val & 0xffff));
usbhost_putle16(dest+2, (uint16_t)(val >> 16)); usbhost_putle16(dest+2, (uint16_t)(val >> 16));
} }
#endif
/**************************************************************************** /****************************************************************************
* Name: usbhost_tdalloc * Name: usbhost_tdalloc

View File

@ -562,7 +562,7 @@ struct usbhost_epdesc_s
uint8_t addr; /* Endpoint address */ uint8_t addr; /* Endpoint address */
bool in; /* Direction: true->IN */ bool in; /* Direction: true->IN */
uint8_t funcaddr; /* USB address of function containing endpoint */ uint8_t funcaddr; /* USB address of function containing endpoint */
uint8_t xfrtype; /* Transfer type. See SB_EP_ATTR_XFER_* in usb.h */ uint8_t xfrtype; /* Transfer type. See USB_EP_ATTR_XFER_* in usb.h */
uint8_t interval; /* Polling interval */ uint8_t interval; /* Polling interval */
uint16_t mxpacketsize; /* Max packetsize */ uint16_t mxpacketsize; /* Max packetsize */
}; };