summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-09-08 13:42:56 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-09-08 13:42:56 -0600
commit8b5a8f98e261f31f15cae44fe8847ada4a0654e0 (patch)
tree7b76274110ab8ea553ae6629208a5bfa7410df90
parent56ecc7ff06b521dbda03a4c7b6274459a5709ab2 (diff)
downloadpx4-nuttx-8b5a8f98e261f31f15cae44fe8847ada4a0654e0.tar.gz
px4-nuttx-8b5a8f98e261f31f15cae44fe8847ada4a0654e0.tar.bz2
px4-nuttx-8b5a8f98e261f31f15cae44fe8847ada4a0654e0.zip
Trivial updates assocaited with USB host mass storage and SAMA5 EHCI
-rw-r--r--apps/examples/usbmsc/usbmsc_main.c2
-rwxr-xr-xnuttx/arch/arm/src/sama5/sam_ehci.c32
-rw-r--r--nuttx/drivers/usbhost/usbhost_storage.c13
-rwxr-xr-xnuttx/include/nuttx/usb/ehci.h4
4 files changed, 41 insertions, 10 deletions
diff --git a/apps/examples/usbmsc/usbmsc_main.c b/apps/examples/usbmsc/usbmsc_main.c
index 3140182a8..20938d6ca 100644
--- a/apps/examples/usbmsc/usbmsc_main.c
+++ b/apps/examples/usbmsc/usbmsc_main.c
@@ -582,6 +582,8 @@ int msconn_main(int argc, char *argv[])
* that the USB mass storage device is already configured). There is
* no handshaking so there is a race condition: We will check again
* when the daemon is started.
+ *
+ * REVISIT: This might a good application for vfork();
*/
if (g_usbmsc.mshandle)
diff --git a/nuttx/arch/arm/src/sama5/sam_ehci.c b/nuttx/arch/arm/src/sama5/sam_ehci.c
index 5ea84870a..b8741d20a 100755
--- a/nuttx/arch/arm/src/sama5/sam_ehci.c
+++ b/nuttx/arch/arm/src/sama5/sam_ehci.c
@@ -2415,9 +2415,33 @@ static int sam_qh_ioccheck(struct sam_qh_s *qh, uint32_t **bp, void *arg)
{
/* An error occurred */
- udbg("ERROR: EP%d TOKEN=%08x", epinfo->epno, token);
epinfo->status = (token & QH_TOKEN_STATUS_MASK) >> QH_TOKEN_STATUS_SHIFT;
- epinfo->result = -EIO;
+
+ /* The HALT condition is set on a variety of conditions: babble, error
+ * counter countdown to zero, or a STALL. If we can rule out babble
+ * (babble bit not set) and if the error counter is non-zero, then we can
+ * assume a STALL. In this case, we return -PERM to inform the class
+ * driver of the stall condition.
+ */
+
+ if ((token & (QH_TOKEN_BABBLE | QH_TOKEN_HALTED)) == QH_TOKEN_HALTED &&
+ (token & QH_TOKEN_CERR_MASK) != 0)
+ {
+ /* It is a stall, Note the that the data toggle is reset
+ * after the stall.
+ */
+
+ udbg("EP%d Stalled: TOKEN=%08x\n", epinfo->epno, token);
+ epinfo->result = -EPERM;
+ epinfo->toggle = 0;
+ }
+ else
+ {
+ /* Otherwise, it is some kind of data transfer error */
+
+ udbg("ERROR: EP%d TOKEN=%08x\n", epinfo->epno, token);
+ epinfo->result = -EIO;
+ }
}
/* Is there a thread waiting for this transfer to complete? */
@@ -3921,7 +3945,7 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
{
irqstate_t flags;
uint32_t regval;
-#ifdef CONFIG_DEBUG_USB
+#if defined(CONFIG_DEBUG_USB) && defined(CONFIG_DEBUG_VERBOSE)
uint16_t regval16;
unsigned int nports;
#endif
@@ -4152,7 +4176,7 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
sam_putreg(ECHI_INT_ALLINTS, &HCOR->usbsts);
-#ifdef CONFIG_DEBUG
+#if defined(CONFIG_DEBUG_USB) && defined(CONFIG_DEBUG_VERBOSE)
/* Show the ECHI version */
regval16 = sam_swap16(HCCR->hciversion);
diff --git a/nuttx/drivers/usbhost/usbhost_storage.c b/nuttx/drivers/usbhost/usbhost_storage.c
index 89ec6238f..d72203bdf 100644
--- a/nuttx/drivers/usbhost/usbhost_storage.c
+++ b/nuttx/drivers/usbhost/usbhost_storage.c
@@ -102,8 +102,9 @@
#define USBHOST_BOUTFOUND 0x04
#define USBHOST_ALLFOUND 0x07
-#define USBHOST_MAX_RETRIES 100
-#define USBHOST_MAX_CREFS 0x7fff
+#define USBHOST_RETRY_USEC (50*1000) /* Retry each 50 milliseconds */
+#define USBHOST_MAX_RETRIES 100 /* Give up after 5 seconds */
+#define USBHOST_MAX_CREFS INT16_MAX /* Max cref count before signed overflow */
/****************************************************************************
* Private Types
@@ -700,6 +701,7 @@ static inline int usbhost_maxlunreq(FAR struct usbhost_state_s *priv)
*(priv->tbuffer) = 0;
}
+
return OK;
}
@@ -1218,9 +1220,12 @@ static inline int usbhost_initvolume(FAR struct usbhost_state_s *priv)
/* Wait just a bit */
- usleep(50*1000);
+ usleep(USBHOST_RETRY_USEC);
- /* Send TESTUNITREADY to see if the unit is ready */
+ /* Send TESTUNITREADY to see if the unit is ready. The most likely error
+ * error that can occur here is a a stall which simply means that the
+ * the device is not yet able to respond.
+ */
ret = usbhost_testunitready(priv);
if (ret == OK)
diff --git a/nuttx/include/nuttx/usb/ehci.h b/nuttx/include/nuttx/usb/ehci.h
index dd96514d1..a10e6c99e 100755
--- a/nuttx/include/nuttx/usb/ehci.h
+++ b/nuttx/include/nuttx/usb/ehci.h
@@ -579,7 +579,7 @@
# define QTD_TOKEN_DBERR (1 << 5) /* Bit 5 Data Buffer Error */
# define QTD_TOKEN_HALTED (1 << 6) /* Bit 6 Halted */
# define QTD_TOKEN_ACTIVE (1 << 7) /* Bit 7 Active */
-# define QTD_TOKEN_ERRORS (0x7c << QTD_TOKEN_STATUS_SHIFT)
+# define QTD_TOKEN_ERRORS (0x78 << QTD_TOKEN_STATUS_SHIFT)
#define QTD_TOKEN_PID_SHIFT (8) /* Bits 8-9: PID Code */
#define QTD_TOKEN_PID_MASK (3 << QTD_TOKEN_PID_SHIFT)
# define QTD_TOKEN_PID_OUT (0 << QTD_TOKEN_PID_SHIFT) /* OUT Token generates token (E1H) */
@@ -700,7 +700,7 @@
# define QH_TOKEN_DBERR (1 << 5) /* Bit 5 Data Buffer Error */
# define QH_TOKEN_HALTED (1 << 6) /* Bit 6 Halted */
# define QH_TOKEN_ACTIVE (1 << 7) /* Bit 7 Active */
-# define QH_TOKEN_ERRORS (0x7c << QH_TOKEN_STATUS_SHIFT)
+# define QH_TOKEN_ERRORS (0x78 << QH_TOKEN_STATUS_SHIFT)
#define QH_TOKEN_PID_SHIFT (8) /* Bits 8-9: PID Code */
#define QH_TOKEN_PID_MASK (3 << QH_TOKEN_PID_SHIFT)
# define QH_TOKEN_PID_OUT (0 << QH_TOKEN_PID_SHIFT) /* OUT Token generates token (E1H) */