forked from Archive/PX4-Autopilot
This appears to fix the NAK-issues for IN data transfers. Still an issue with OUT
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@5063 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
parent
8e68b6f0af
commit
4794a491c1
|
@ -43,15 +43,12 @@
|
|||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#if !defined(CONFIG_DEBUG_VERBOSE) && !defined(CONFIG_DEBUG_USB)
|
||||
# include <debug.h>
|
||||
#endif
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/usb/usb.h>
|
||||
|
@ -315,6 +312,10 @@ static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv,
|
|||
FAR uint8_t *buffer, unsigned int buflen);
|
||||
static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
|
||||
FAR uint8_t *buffer, unsigned int buflen);
|
||||
static int stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
|
||||
FAR uint8_t *buffer, size_t buflen);
|
||||
static int stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
|
||||
FAR uint8_t *buffer, size_t buflen);
|
||||
|
||||
/* Interrupt handling **********************************************************/
|
||||
/* Lower level interrupt handlers */
|
||||
|
@ -1354,6 +1355,222 @@ static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
|
|||
return stm32_chan_wait(priv, chan);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Name: stm32_in_transfer
|
||||
*
|
||||
* Description:
|
||||
* Transfer 'buflen' bytes into 'buffer' from an IN channel.
|
||||
*
|
||||
*******************************************************************************/
|
||||
|
||||
static int stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
|
||||
FAR uint8_t *buffer, size_t buflen)
|
||||
{
|
||||
FAR struct stm32_chan_s *chan;
|
||||
uint16_t start;
|
||||
uint16_t elapsed;
|
||||
int ret = OK;
|
||||
|
||||
/* Loop until the transfer completes (i.e., buflen is decremented to zero)
|
||||
* or a fatal error occurs (any error other than a simple NAK)
|
||||
*/
|
||||
|
||||
chan = &priv->chan[chidx];
|
||||
chan->buffer = buffer;
|
||||
chan->buflen = buflen;
|
||||
|
||||
start = stm32_getframe();
|
||||
while (chan->buflen > 0)
|
||||
{
|
||||
/* Set up for the wait BEFORE starting the transfer */
|
||||
|
||||
ret = stm32_chan_waitsetup(priv, chan);
|
||||
if (ret != OK)
|
||||
{
|
||||
udbg("ERROR: Device disconnected\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Set up for the transfer based on the direction and the endpoint type */
|
||||
|
||||
switch (chan->eptype)
|
||||
{
|
||||
default:
|
||||
case OTGFS_EPTYPE_CTRL: /* Control */
|
||||
{
|
||||
/* This kind of transfer on control endpoints other than EP0 are not
|
||||
* currently supported
|
||||
*/
|
||||
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
case OTGFS_EPTYPE_ISOC: /* Isochronous */
|
||||
{
|
||||
/* Set up the IN data PID */
|
||||
|
||||
chan->pid = OTGFS_PID_DATA0;
|
||||
}
|
||||
break;
|
||||
|
||||
case OTGFS_EPTYPE_BULK: /* Bulk */
|
||||
case OTGFS_EPTYPE_INTR: /* Interrupt */
|
||||
{
|
||||
/* Setup the IN data PID */
|
||||
|
||||
chan->pid = chan->indata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
/* Start the transfer */
|
||||
|
||||
stm32_transfer_start(priv, chidx);
|
||||
|
||||
/* Wait for the transfer to complete and get the result */
|
||||
|
||||
ret = stm32_chan_wait(priv, chan);
|
||||
|
||||
/* EAGAIN indicates that the device NAKed the transfer and we need
|
||||
* do try again. Anything else (success or other errors) will
|
||||
* cause use to return
|
||||
*/
|
||||
|
||||
if (ret != OK)
|
||||
{
|
||||
udbg("Transfer failed: %d\n", ret);
|
||||
|
||||
/* Check for a special case: If (1) the transfer was NAKed and (2)
|
||||
* no Tx FIFO empty or Rx FIFO not-empty event occurred, then we
|
||||
* should be able to just flush the Rx and Tx FIFOs and try again.
|
||||
* We can detect this latter case becasue the then the transfer
|
||||
* buffer pointer and buffer size will be unaltered.
|
||||
*/
|
||||
|
||||
elapsed = stm32_getframe() - start;
|
||||
if (ret != -EAGAIN || /* Not a NAK condition OR */
|
||||
elapsed >= STM32_DATANAK_DELAY || /* Timeout has elapsed OR */
|
||||
chan->buflen != buflen) /* Data has been partially transferred */
|
||||
{
|
||||
/* Break out and return the error */
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Name: stm32_out_transfer
|
||||
*
|
||||
* Description:
|
||||
* Transfer the 'buflen' bytes in 'buffer' through an OUT channel.
|
||||
*
|
||||
*******************************************************************************/
|
||||
|
||||
static int stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
|
||||
FAR uint8_t *buffer, size_t buflen)
|
||||
{
|
||||
FAR struct stm32_chan_s *chan;
|
||||
int ret;
|
||||
|
||||
/* Loop until the transfer completes (i.e., buflen is decremented to zero)
|
||||
* or a fatal error occurs (any error other than a simple NAK)
|
||||
*/
|
||||
|
||||
chan = &priv->chan[chidx];
|
||||
chan->buffer = buffer;
|
||||
chan->buflen = buflen;
|
||||
|
||||
while (chan->buflen > 0)
|
||||
{
|
||||
/* Set up for the wait BEFORE starting the transfer */
|
||||
|
||||
ret = stm32_chan_waitsetup(priv, chan);
|
||||
if (ret != OK)
|
||||
{
|
||||
udbg("ERROR: Device disconnected\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Set up for the transfer based on the direction and the endpoint type */
|
||||
|
||||
switch (chan->eptype)
|
||||
{
|
||||
default:
|
||||
case OTGFS_EPTYPE_CTRL: /* Control */
|
||||
{
|
||||
/* This kind of transfer on control endpoints other than EP0 are not
|
||||
* currently supported
|
||||
*/
|
||||
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
case OTGFS_EPTYPE_ISOC: /* Isochronous */
|
||||
{
|
||||
/* Set up the OUT data PID */
|
||||
|
||||
chan->pid = OTGFS_PID_DATA0;
|
||||
}
|
||||
break;
|
||||
|
||||
case OTGFS_EPTYPE_BULK: /* Bulk */
|
||||
{
|
||||
/* Setup the OUT data PID */
|
||||
|
||||
chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
|
||||
}
|
||||
break;
|
||||
|
||||
case OTGFS_EPTYPE_INTR: /* Interrupt */
|
||||
{
|
||||
/* Setup the OUT data PID */
|
||||
|
||||
chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
|
||||
|
||||
/* Toggle the OUT data PID for the next transfer */
|
||||
|
||||
chan->outdata1 ^= true;
|
||||
}
|
||||
}
|
||||
|
||||
/* There is a bug in the code at present. With debug OFF, this driver
|
||||
* overruns the typical FLASH device and there are many problems with
|
||||
* NAKS sticking a big delay here allows the driver to work but with
|
||||
* very poor performance when debug is off.
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_DEBUG_VERBOSE) && !defined(CONFIG_DEBUG_USB)
|
||||
#warning "REVISIT this delay"
|
||||
usleep(100*1000);
|
||||
#endif
|
||||
|
||||
/* Start the transfer */
|
||||
|
||||
stm32_transfer_start(priv, chidx);
|
||||
|
||||
/* Wait for the transfer to complete and get the result */
|
||||
|
||||
ret = stm32_chan_wait(priv, chan);
|
||||
|
||||
/* EAGAIN indicates that the device NAKed the transfer and we need
|
||||
* do try again. Anything else (success or other errors) will
|
||||
* cause use to return
|
||||
*/
|
||||
|
||||
if (ret != OK)
|
||||
{
|
||||
udbg("Transfer failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Name: stm32_gint_wrpacket
|
||||
*
|
||||
|
@ -3496,141 +3713,29 @@ static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
|
|||
static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
|
||||
FAR uint8_t *buffer, size_t buflen)
|
||||
{
|
||||
struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
|
||||
FAR struct stm32_chan_s *chan;
|
||||
FAR struct stm32_usbhost_s *priv = (FAR struct stm32_usbhost_s *)drvr;
|
||||
unsigned int chidx = (unsigned int)ep;
|
||||
int ret = OK;
|
||||
int ret;
|
||||
|
||||
uvdbg("chidx: %d buflen: %d\n", (unsigned int)ep, buflen);
|
||||
|
||||
DEBUGASSERT(priv && buffer && chidx < STM32_MAX_TX_FIFOS && buflen > 0);
|
||||
chan = &priv->chan[chidx];
|
||||
|
||||
/* We must have exclusive access to the USB host hardware and state structures */
|
||||
|
||||
stm32_takesem(&priv->exclsem);
|
||||
|
||||
/* Loop until the transfer completes (i.e., buflen is decremented to zero)
|
||||
* or a fatal error occurs (any error other than a simple NAK)
|
||||
*/
|
||||
/* Handle IN and OUT transfer slightly differently */
|
||||
|
||||
chan->buffer = buffer;
|
||||
chan->buflen = buflen;
|
||||
|
||||
while (chan->buflen > 0)
|
||||
if (priv->chan[chidx].in)
|
||||
{
|
||||
/* Set up for the wait BEFORE starting the transfer */
|
||||
|
||||
ret = stm32_chan_waitsetup(priv, chan);
|
||||
if (ret != OK)
|
||||
{
|
||||
udbg("ERROR: Device disconnected\n");
|
||||
goto errout;
|
||||
}
|
||||
|
||||
/* Set up for the transfer based on the direction and the endpoint type */
|
||||
|
||||
switch (chan->eptype)
|
||||
{
|
||||
default:
|
||||
case OTGFS_EPTYPE_CTRL: /* Control */
|
||||
{
|
||||
/* This kind of transfer on control endpoints other than EP0 are not
|
||||
* currently supported
|
||||
*/
|
||||
|
||||
ret = -ENOSYS;
|
||||
goto errout;
|
||||
}
|
||||
|
||||
case OTGFS_EPTYPE_ISOC: /* Isochronous */
|
||||
{
|
||||
/* Set up the IN/OUT data PID */
|
||||
|
||||
chan->pid = OTGFS_PID_DATA0;
|
||||
}
|
||||
break;
|
||||
|
||||
case OTGFS_EPTYPE_BULK: /* Bulk */
|
||||
{
|
||||
/* Handle the bulk transfer based on the direction of the transfer. */
|
||||
|
||||
if (chan->in)
|
||||
{
|
||||
/* Setup the IN data PID */
|
||||
|
||||
chan->pid = chan->indata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
|
||||
ret = stm32_in_transfer(priv, chidx, buffer, buflen);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Setup the OUT data PID */
|
||||
|
||||
chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case OTGFS_EPTYPE_INTR: /* Interrupt */
|
||||
{
|
||||
/* Handle the interrupt transfer based on the direction of the
|
||||
* transfer.
|
||||
*/
|
||||
|
||||
if (chan->in)
|
||||
{
|
||||
/* Setup the IN data PID */
|
||||
|
||||
chan->pid = chan->indata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
|
||||
|
||||
/* The indata1 data toggle will be updated in the Rx FIFO
|
||||
* interrupt handling logic as each packet is received.
|
||||
*/
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Setup the OUT data PID */
|
||||
|
||||
chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
|
||||
|
||||
/* Toggle the OUT data PID for the next transfer */
|
||||
|
||||
chan->outdata1 ^= true;
|
||||
}
|
||||
}
|
||||
ret = stm32_out_transfer(priv, chidx, buffer, buflen);
|
||||
}
|
||||
|
||||
/* There is a bug in the code at present. With debug OFF, this driver
|
||||
* overruns the typical FLASH device and there are many problems with
|
||||
* NAKS sticking a big delay here allows the driver to work but with
|
||||
* very poor performance when debug is off.
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_DEBUG_VERBOSE) && !defined(CONFIG_DEBUG_USB)
|
||||
#warning "REVISIT this delay"
|
||||
usleep(100*1000);
|
||||
#endif
|
||||
|
||||
/* Start the transfer */
|
||||
|
||||
stm32_transfer_start(priv, chidx);
|
||||
|
||||
/* Wait for the transfer to complete and get the result */
|
||||
|
||||
ret = stm32_chan_wait(priv, chan);
|
||||
|
||||
/* EAGAIN indicates that the device NAKed the transfer and we need
|
||||
* do try again. Anything else (success or other errors) will
|
||||
* cause use to return
|
||||
*/
|
||||
|
||||
if (ret != OK)
|
||||
{
|
||||
udbg("Transfer failed: %d\n", ret);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
errout:
|
||||
stm32_givesem(&priv->exclsem);
|
||||
return ret;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue