summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c11
-rwxr-xr-xnuttx/configs/nucleus2g/src/up_nsh.c14
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/up_nsh.c14
-rwxr-xr-xnuttx/drivers/usbhost/usbhost_enumerate.c40
-rw-r--r--nuttx/drivers/usbhost/usbhost_findclass.c11
-rw-r--r--nuttx/drivers/usbhost/usbhost_registerclass.c3
-rw-r--r--nuttx/drivers/usbhost/usbhost_storage.c4
-rwxr-xr-xnuttx/include/nuttx/usb/ohci.h2
8 files changed, 75 insertions, 24 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
index e25b2474a..0a566c9fe 100755
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
@@ -819,6 +819,17 @@ static int lpc17_usbinterrupt(int irq, FAR void *context)
priv->tdstatus = (TDHEAD->ctrl & GTD_STATUS_CC_MASK) >> GTD_STATUS_CC_SHIFT;
+#ifdef CONFIG_DEBUG_USB
+ if (priv->tdstatus != 0)
+ {
+ /* The transfer failed for some reason... dump some diagnostic info. */
+
+ ulldbg("ERROR: TD CTRL:%08x/CC:%d RHPORTST1:%08x\n",
+ TDHEAD->ctrl, priv->tdstatus,
+ lpc17_getreg(LPC17_USBHOST_RHPORTST1));
+ }
+#endif
+
/* And wake up the thread waiting for the WDH event */
DEBUGASSERT(priv->wdhsem.semcount <= 0);
diff --git a/nuttx/configs/nucleus2g/src/up_nsh.c b/nuttx/configs/nucleus2g/src/up_nsh.c
index d65516e18..084b95cbb 100755
--- a/nuttx/configs/nucleus2g/src/up_nsh.c
+++ b/nuttx/configs/nucleus2g/src/up_nsh.c
@@ -208,8 +208,20 @@ static int nsh_waiter(int argc, char *argv[])
static int nsh_usbhostinitialize(void)
{
int pid;
+ int ret;
+
+ /* First, register all of the class drivers needed to support the drivers
+ * that we care about:
+ */
+
+ message("nsh_usbhostinitialize: Register class drivers\n");
+ ret = usbhost_storageinit();
+ if (ret != OK)
+ {
+ message("nsh_usbhostinitialize: Failed to register the mass storage class\n");
+ }
- /* First, get an instance of the USB host interface */
+ /* Then get an instance of the USB host interface */
message("nsh_usbhostinitialize: Initialize USB host\n");
g_drvr = usbhost_initialize(0);
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
index 0d59dc4fa..afb6d084e 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
@@ -261,8 +261,20 @@ errout:
static int nsh_usbhostinitialize(void)
{
int pid;
+ int ret;
+
+ /* First, register all of the class drivers needed to support the drivers
+ * that we care about:
+ */
+
+ message("nsh_usbhostinitialize: Register class drivers\n");
+ ret = usbhost_storageinit();
+ if (ret != OK)
+ {
+ message("nsh_usbhostinitialize: Failed to register the mass storage class\n");
+ }
- /* First, get an instance of the USB host interface */
+ /* Then get an instance of the USB host interface */
message("nsh_usbhostinitialize: Initialize USB host\n");
g_drvr = usbhost_initialize(0);
diff --git a/nuttx/drivers/usbhost/usbhost_enumerate.c b/nuttx/drivers/usbhost/usbhost_enumerate.c
index 16a5802f0..cb82b6b14 100755
--- a/nuttx/drivers/usbhost/usbhost_enumerate.c
+++ b/nuttx/drivers/usbhost/usbhost_enumerate.c
@@ -139,6 +139,8 @@ static inline int usbhost_devdesc(const struct usb_devdesc_s *devdesc,
id->base = devdesc->class;
id->subclass = devdesc->subclass;
id->proto = devdesc->protocol;
+ uvdbg("class:%d subclass:%d protocol:%d\n",
+ id->base, id->subclass, id->proto);
/* Check if we have enough of the structure to see the VID/PID */
@@ -148,6 +150,7 @@ static inline int usbhost_devdesc(const struct usb_devdesc_s *devdesc,
id->vid = usbhost_getle16(devdesc->vendor);
id->pid = usbhost_getle16(devdesc->product);
+ uvdbg("vid:%d pid:%d\n", id->vid, id->pid);
}
}
@@ -163,38 +166,33 @@ static inline int usbhost_devdesc(const struct usb_devdesc_s *devdesc,
*
*******************************************************************************/
-static inline int usbhost_configdesc(const uint8_t *configdesc, int desclen,
+static inline int usbhost_configdesc(const uint8_t *configdesc, int cfglen,
struct usbhost_id_s *id)
{
struct usb_cfgdesc_s *cfgdesc;
struct usb_ifdesc_s *ifdesc;
int remaining;
- DEBUGASSERT(configdesc != NULL &&
- desclen >= sizeof(struct usb_cfgdesc_s));
-
+ DEBUGASSERT(configdesc != NULL && cfglen >= USB_SIZEOF_CFGDESC);
+
/* Verify that we were passed a configuration descriptor */
cfgdesc = (struct usb_cfgdesc_s *)configdesc;
+ uvdbg("cfg len:%d total len:%d\n", cfgdesc->len, cfglen);
+
if (cfgdesc->type != USB_DESC_TYPE_CONFIG)
{
return -EINVAL;
}
- /* Get the total length of the configuration descriptor (little endian).
- * It might be a good check to get the number of interfaces here too.
- */
-
- remaining = (int)usbhost_getle16(cfgdesc->totallen);
-
/* Skip to the next entry descriptor */
configdesc += cfgdesc->len;
- remaining -= cfgdesc->len;
+ remaining = cfglen - cfgdesc->len;
/* Loop where there are more dscriptors to examine */
- memset(&id, 0, sizeof(FAR struct usb_desc_s));
+ memset(id, 0, sizeof(FAR struct usb_desc_s));
while (remaining >= sizeof(struct usb_desc_s))
{
/* What is the next descriptor? Is it an interface descriptor? */
@@ -212,6 +210,8 @@ static inline int usbhost_configdesc(const uint8_t *configdesc, int desclen,
id->base = ifdesc->class;
id->subclass = ifdesc->subclass;
id->proto = ifdesc->protocol;
+ uvdbg("class:%d subclass:%d protocol:%d\n",
+ id->base, id->subclass, id->proto);
return OK;
}
@@ -319,8 +319,8 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr,
struct usb_ctrlreq_s *ctrlreq;
struct usbhost_id_s id;
size_t maxlen;
- unsigned int len;
- uint16_t maxpacketsize;
+ unsigned int cfglen;
+ uint8_t maxpacketsize;
uint8_t *buffer;
int ret;
@@ -370,6 +370,9 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr,
/* Extract the max packetsize for endpoint 0 */
+ maxpacketsize = devdesc->mxpacketsize;
+ uvdbg("maxpacksetsize: %d\n", maxpacketsize);
+
DRVR_EP0CONFIGURE(drvr, 0, maxpacketsize);
/* Get class identification information from the device descriptor. Most
@@ -426,7 +429,8 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr,
/* Extract the full size of the configuration data */
- len = ((struct usb_cfgdesc_s *)buffer)->len;
+ cfglen = (unsigned int)usbhost_getle16(((struct usb_cfgdesc_s *)buffer)->totallen);
+ uvdbg("sizeof config data: %d\n", cfglen);
/* Get all of the configuration descriptor data, index == 0 */
@@ -434,7 +438,7 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr,
ctrlreq->req = USB_REQ_GETDESCRIPTOR;
usbhost_putle16(ctrlreq->value, (USB_DESC_TYPE_CONFIG << 8));
usbhost_putle16(ctrlreq->index, 0);
- usbhost_putle16(ctrlreq->len, len);
+ usbhost_putle16(ctrlreq->len, cfglen);
ret = DRVR_CTRLIN(drvr, ctrlreq, buffer);
if (ret != OK)
@@ -477,7 +481,7 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr,
* case of multiple interface descriptors.
*/
- ret = usbhost_configdesc(buffer, len, &id);
+ ret = usbhost_configdesc(buffer, cfglen, &id);
if (ret != OK)
{
udbg("ERROR: usbhost_configdesc returned %d\n", ret);
@@ -494,7 +498,7 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr,
* will begin configuring the device.
*/
- ret = usbhost_classbind(drvr, buffer, len, &id, class);
+ ret = usbhost_classbind(drvr, buffer, cfglen, &id, class);
if (ret != OK)
{
udbg("ERROR: usbhost_classbind returned %d\n", ret);
diff --git a/nuttx/drivers/usbhost/usbhost_findclass.c b/nuttx/drivers/usbhost/usbhost_findclass.c
index 1b2a7edae..d4438d814 100644
--- a/nuttx/drivers/usbhost/usbhost_findclass.c
+++ b/nuttx/drivers/usbhost/usbhost_findclass.c
@@ -41,6 +41,7 @@
#include <sys/types.h>
#include <stdbool.h>
+#include <debug.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbhost.h>
@@ -86,6 +87,9 @@
static bool usbhost_idmatch(const struct usbhost_id_s *classid,
const struct usbhost_id_s *devid)
{
+ uvdbg("Compare to class:%d subclass:%d protocol:%d\n",
+ classid->base, classid->subclass, classid->proto);
+
/* The base class ID, subclass and protocol have to match up in any event */
if (devid->base == classid->base &&
@@ -151,6 +155,10 @@ const struct usbhost_registry_s *usbhost_findclass(const struct usbhost_id_s *id
irqstate_t flags;
int ndx;
+ DEBUGASSERT(id);
+ uvdbg("Looking for class:%d subclass:%d protocol:%d\n",
+ id->base, id->subclass, id->proto);
+
/* g_classregistry is a singly-linkedlist of class ID information added by
* calls to usbhost_registerclass(). Since this list is accessed from USB
* host controller interrupt handling logic, accesses to this list must be
@@ -167,7 +175,8 @@ const struct usbhost_registry_s *usbhost_findclass(const struct usbhost_id_s *id
* protocol, then try each.
*/
- for (ndx = 0; ndx < class->nids; ndx++)
+ uvdbg("Checking class:%p nids:%d\n", class, class->nids);
+ for (ndx = 0; ndx < class->nids; ndx++)
{
/* Did we find a matching ID? */
diff --git a/nuttx/drivers/usbhost/usbhost_registerclass.c b/nuttx/drivers/usbhost/usbhost_registerclass.c
index 0c8d3b20d..76ef511af 100644
--- a/nuttx/drivers/usbhost/usbhost_registerclass.c
+++ b/nuttx/drivers/usbhost/usbhost_registerclass.c
@@ -41,6 +41,7 @@
#include <sys/types.h>
#include <errno.h>
+#include <debug.h>
#include <arch/irq.h>
#include <nuttx/usb/usbhost.h>
@@ -95,6 +96,8 @@ int usbhost_registerclass(struct usbhost_registry_s *class)
{
irqstate_t flags;
+ uvdbg("Registering class:%p nids:%d\n", class, class->nids);
+
/* g_classregistry is a singly-linkedlist of class ID information added by
* calls to usbhost_registerclass(). Since this list is accessed from USB
* host controller interrupt handling logic, accesses to this list must be
diff --git a/nuttx/drivers/usbhost/usbhost_storage.c b/nuttx/drivers/usbhost/usbhost_storage.c
index cfe6af668..89b969b30 100644
--- a/nuttx/drivers/usbhost/usbhost_storage.c
+++ b/nuttx/drivers/usbhost/usbhost_storage.c
@@ -1343,7 +1343,7 @@ static int usbhost_connect(FAR struct usbhost_class_s *class,
case USB_DESC_TYPE_INTERFACE:
{
- DEBUGASSERT(remaining >= sizeof(struct usb_ifdesc_s));
+ DEBUGASSERT(remaining >= USB_SIZEOF_IFDESC);
if ((found & USBHOST_IFFOUND) != 0)
{
/* Oops.. more than one interface. We don't know what to do with this. */
@@ -1358,7 +1358,7 @@ static int usbhost_connect(FAR struct usbhost_class_s *class,
case USB_DESC_TYPE_ENDPOINT:
{
FAR struct usb_epdesc_s *epdesc = (FAR struct usb_epdesc_s *)configdesc;
- DEBUGASSERT(remaining >= sizeof(struct usb_epdesc_s));
+ DEBUGASSERT(remaining >= USB_SIZEOF_EPDESC);
/* Check for a bulk endpoint. We only support the bulk-only
* protocol so I suppose anything else should really be an error.
diff --git a/nuttx/include/nuttx/usb/ohci.h b/nuttx/include/nuttx/usb/ohci.h
index f8ddcdffc..2dc95aecc 100755
--- a/nuttx/include/nuttx/usb/ohci.h
+++ b/nuttx/include/nuttx/usb/ohci.h
@@ -202,7 +202,7 @@
#define OHCI_LSTHRES_SHIFT (0) /* Bits 0-11: LS threshold */
#define OHCI_LSTHRES_MASK (0x0fff << OHCI_PERSTART_SHIFT)
/* Bits 12-31: Reserved */
-/* HcRhDescriptorN: Describes root hub (7.4.1) */
+/* HcRhDescriptorN: Describes root hub (part A) (7.4.1) */
#define OHCI_RHDESCA_NDP_SHIFT (0) /* Bits 0-7: Number downstream ports */
#define OHCI_RHDESCA_NDP_MASK (0xff << OHCI_RHDESCA_NDP_SHIFT)