summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-09-09 14:01:52 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-09-09 14:01:52 -0600
commit845f1694727937478ab8487d2b7a2150ad0cc858 (patch)
tree489dfc47cb660b1843af6f4a5b4b3329621c5142
parent4425b0261bfdcd4cf8765917dc2b3a8b0d80c177 (diff)
downloadpx4-nuttx-845f1694727937478ab8487d2b7a2150ad0cc858.tar.gz
px4-nuttx-845f1694727937478ab8487d2b7a2150ad0cc858.tar.bz2
px4-nuttx-845f1694727937478ab8487d2b7a2150ad0cc858.zip
Beginning of support for USB host side tracing
-rw-r--r--nuttx/arch/arm/src/sama5/Make.defs8
-rwxr-xr-xnuttx/arch/arm/src/sama5/sam_ehci.c89
-rw-r--r--nuttx/arch/arm/src/sama5/sam_usbhost.c154
-rw-r--r--nuttx/arch/arm/src/sama5/sam_usbhost.h44
-rw-r--r--nuttx/drivers/usbdev/Kconfig10
-rw-r--r--nuttx/drivers/usbhost/Kconfig15
-rw-r--r--nuttx/drivers/usbhost/Make.defs20
-rw-r--r--nuttx/drivers/usbhost/usbhost_trace.c305
-rwxr-xr-xnuttx/include/nuttx/usb/ehci.h54
-rw-r--r--nuttx/include/nuttx/usb/usbhost_trace.h104
10 files changed, 713 insertions, 90 deletions
diff --git a/nuttx/arch/arm/src/sama5/Make.defs b/nuttx/arch/arm/src/sama5/Make.defs
index 1d77ebf55..d2d087e49 100644
--- a/nuttx/arch/arm/src/sama5/Make.defs
+++ b/nuttx/arch/arm/src/sama5/Make.defs
@@ -139,3 +139,11 @@ CHIP_CSRCS += sam_hsmci.c
endif
endif
endif
+
+ifeq ($(CONFIG_USBHOST_TRACE),y)
+CHIP_CSRCS += sam_usbhost.c
+else
+ifeq ($(CONFIG_DEBUG_USB),y)
+CHIP_CSRCS += sam_usbhost.c
+endif
+endif
diff --git a/nuttx/arch/arm/src/sama5/sam_ehci.c b/nuttx/arch/arm/src/sama5/sam_ehci.c
index b8741d20a..8b4e3297e 100755
--- a/nuttx/arch/arm/src/sama5/sam_ehci.c
+++ b/nuttx/arch/arm/src/sama5/sam_ehci.c
@@ -53,6 +53,7 @@
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbhost.h>
#include <nuttx/usb/ehci.h>
+#include <nuttx/usb/usbhost_trace.h>
#include "up_arch.h"
#include "cache.h"
@@ -723,7 +724,7 @@ static int ehci_wait_usbsts(uint32_t maskbits, uint32_t donebits,
regval = sam_getreg(&HCOR->usbsts);
if ((regval & EHCI_INT_SYSERROR) != 0)
{
- udbg("ERROR: System error: %08x\n", regval);
+ usbhost_trace1(EHCI_TRACE1_SYSTEMERROR, regval);
return -EIO;
}
@@ -1081,7 +1082,7 @@ static int sam_qh_discard(struct sam_qh_s *qh)
ret = sam_qtd_foreach(qh, sam_qtd_discard, NULL);
if (ret < 0)
{
- udbg("ERROR: sam_qtd_foreach failed: %d\n", ret);
+ usbhost_trace1(EHCI_TRACE1_QTDFOREACH_FAILED, -ret);
}
/* Then free the QH itself */
@@ -1418,7 +1419,7 @@ static struct sam_qh_s *sam_qh_create(struct sam_rhport_s *rhport,
qh = sam_qh_alloc();
if (qh == NULL)
{
- udbg("ERROR: Failed to allocate a QH\n");
+ usbhost_trace1(EHCI_TRACE1_QHALLOC_FAILED, 0);
return NULL;
}
@@ -1590,7 +1591,7 @@ static int sam_qtd_addbpl(struct sam_qtd_s *qtd, const void *buffer, size_t bufl
if (ndx >= 5)
{
- udbg("ERROR: Buffer too big. Remaining %d\n", buflen);
+ usbhost_trace1(EHCI_TRACE1_BUFTOOBIG, buflen);
return -EFBIG;
}
@@ -1617,7 +1618,7 @@ static struct sam_qtd_s *sam_qtd_setupphase(struct sam_epinfo_s *epinfo,
qtd = sam_qtd_alloc();
if (qtd == NULL)
{
- udbg("ERROR: Failed to allocate request qTD");
+ usbhost_trace1(EHCI_TRACE1_REQQTDALLOC_FAILED, 0);
return NULL;
}
@@ -1652,7 +1653,7 @@ static struct sam_qtd_s *sam_qtd_setupphase(struct sam_epinfo_s *epinfo,
ret = sam_qtd_addbpl(qtd, req, USB_SIZEOF_CTRLREQ);
if (ret < 0)
{
- udbg("ERROR: sam_qtd_addbpl failed: %d\n", ret);
+ usbhost_trace1(EHCI_TRACE1_ADDBPL_FAILED, -ret);
sam_qtd_free(qtd);
return NULL;
}
@@ -1685,7 +1686,7 @@ static struct sam_qtd_s *sam_qtd_dataphase(struct sam_epinfo_s *epinfo,
qtd = sam_qtd_alloc();
if (qtd == NULL)
{
- udbg("ERROR: Failed to allocate data buffer qTD");
+ usbhost_trace1(EHCI_TRACE1_DATAQTDALLOC_FAILED, 0);
return NULL;
}
@@ -1720,7 +1721,7 @@ static struct sam_qtd_s *sam_qtd_dataphase(struct sam_epinfo_s *epinfo,
ret = sam_qtd_addbpl(qtd, buffer, buflen);
if (ret < 0)
{
- udbg("ERROR: sam_qtd_addbpl failed: %d\n", ret);
+ usbhost_trace1(EHCI_TRACE1_ADDBPL_FAILED, -ret);
sam_qtd_free(qtd);
return NULL;
}
@@ -1750,7 +1751,7 @@ static struct sam_qtd_s *sam_qtd_statusphase(uint32_t tokenbits)
qtd = sam_qtd_alloc();
if (qtd == NULL)
{
- udbg("ERROR: Failed to allocate request qTD");
+ usbhost_trace1(EHCI_TRACE1_REQQTDALLOC_FAILED, 0);
return NULL;
}
@@ -1836,7 +1837,7 @@ static ssize_t sam_async_transfer(struct sam_rhport_s *rhport,
ret = sam_ioc_setup(rhport, epinfo);
if (ret != OK)
{
- udbg("ERROR: Device disconnected\n");
+ usbhost_trace1(EHCI_TRACE1_DEVDISCONNECTED, -ret);
return ret;
}
@@ -1845,7 +1846,7 @@ static ssize_t sam_async_transfer(struct sam_rhport_s *rhport,
qh = sam_qh_create(rhport, epinfo);
if (qh == NULL)
{
- udbg("ERROR: sam_qh_create failed\n");
+ usbhost_trace1(EHCI_TRACE1_QHCREATE_FAILED, 0);
ret = -ENOMEM;
goto errout_with_iocwait;
}
@@ -1878,7 +1879,7 @@ static ssize_t sam_async_transfer(struct sam_rhport_s *rhport,
qtd = sam_qtd_setupphase(epinfo, req);
if (qtd == NULL)
{
- udbg("ERROR: sam_qtd_setupphase failed\n");
+ usbhost_trace1(EHCI_TRACE1_QTDSETUP_FAILED, 0);
goto errout_with_qh;
}
@@ -1954,7 +1955,7 @@ static ssize_t sam_async_transfer(struct sam_rhport_s *rhport,
qtd = sam_qtd_dataphase(epinfo, buffer, buflen, tokenbits);
if (qtd == NULL)
{
- udbg("ERROR: sam_qtd_dataphase failed\n");
+ usbhost_trace1(EHCI_TRACE1_QTDDATA_FAILED, 0);
goto errout_with_qh;
}
@@ -2011,7 +2012,7 @@ static ssize_t sam_async_transfer(struct sam_rhport_s *rhport,
qtd = sam_qtd_statusphase(tokenbits);
if (qtd == NULL)
{
- udbg("ERROR: sam_qtd_statusphase failed\n");
+ usbhost_trace1(EHCI_TRACE1_QTDSTATUS_FAILED, 0);
goto errout_with_qh;
}
@@ -2051,7 +2052,7 @@ static ssize_t sam_async_transfer(struct sam_rhport_s *rhport,
*
* REVISIT: Is this safe? NO. This is a bug and needs rethinking.
* We need to lock all of the port-resources (not EHCI common) until
- * the transfer is complete. But we can't use the common ECHI exclsem
+ * the transfer is complete. But we can't use the common EHCI exclsem
* or we will deadlock while waiting (because the working thread that
* wakes this thread up needs the exclsem).
*/
@@ -2062,7 +2063,7 @@ static ssize_t sam_async_transfer(struct sam_rhport_s *rhport,
ret = sam_ioc_wait(epinfo);
- /* Re-aquire the ECHI semaphore. The caller expects to be holding
+ /* Re-aquire the EHCI semaphore. The caller expects to be holding
* this upon return.
*/
@@ -2072,7 +2073,7 @@ static ssize_t sam_async_transfer(struct sam_rhport_s *rhport,
if (ret < 0)
{
- udbg("ERROR: Transfer failed\n");
+ usbhost_trace1(EHCI_TRACE1_TRANSFER_FAILED, -ret);
goto errout_with_iocwait;
}
@@ -2164,7 +2165,7 @@ static ssize_t sam_intr_transfer(struct sam_rhport_s *rhport,
ret = sam_ioc_setup(rhport, epinfo);
if (ret != OK)
{
- udbg("ERROR: Device disconnected\n");
+ usbhost_trace1(EHCI_TRACE1_DEVDISCONNECTED, -ret);
return ret;
}
@@ -2173,7 +2174,7 @@ static ssize_t sam_intr_transfer(struct sam_rhport_s *rhport,
qh = sam_qh_create(rhport, epinfo);
if (qh == NULL)
{
- udbg("ERROR: sam_qh_create failed\n");
+ usbhost_trace1(EHCI_TRACE1_QHCREATE_FAILED, 0);
ret = -ENOMEM;
goto errout_with_iocwait;
}
@@ -2202,7 +2203,7 @@ static ssize_t sam_intr_transfer(struct sam_rhport_s *rhport,
qtd = sam_qtd_dataphase(epinfo, buffer, buflen, tokenbits);
if (qtd == NULL)
{
- udbg("ERROR: sam_qtd_dataphase failed\n");
+ usbhost_trace1(EHCI_TRACE1_QTDDATA_FAILED, 0);
goto errout_with_qh;
}
@@ -2231,7 +2232,7 @@ static ssize_t sam_intr_transfer(struct sam_rhport_s *rhport,
*
* REVISIT: Is this safe? NO. This is a bug and needs rethinking.
* We need to lock all of the port-resources (not EHCI common) until
- * the transfer is complete. But we can't use the common ECHI exclsem
+ * the transfer is complete. But we can't use the common EHCI exclsem
* or we will deadlock while waiting (because the working thread that
* wakes this thread up needs the exclsem).
*/
@@ -2242,7 +2243,7 @@ static ssize_t sam_intr_transfer(struct sam_rhport_s *rhport,
ret = sam_ioc_wait(epinfo);
- /* Re-aquire the ECHI semaphore. The caller expects to be holding
+ /* Re-aquire the EHCI semaphore. The caller expects to be holding
* this upon return.
*/
@@ -2252,7 +2253,7 @@ static ssize_t sam_intr_transfer(struct sam_rhport_s *rhport,
if (ret < 0)
{
- udbg("ERROR: Transfer failed\n");
+ usbhost_trace1(EHCI_TRACE1_TRANSFER_FAILED, -ret);
goto errout_with_iocwait;
}
@@ -2382,7 +2383,7 @@ static int sam_qh_ioccheck(struct sam_qh_s *qh, uint32_t **bp, void *arg)
ret = sam_qtd_foreach(qh, sam_qtd_ioccheck, (void *)qh->epinfo);
if (ret < 0)
{
- udbg("ERROR: sam_qtd_foreach failed: %d\n", ret);
+ usbhost_trace1(EHCI_TRACE1_QTDFOREACH_FAILED, -ret);
}
/* If there is no longer anything attached to the QH, then remove it from
@@ -2431,7 +2432,7 @@ static int sam_qh_ioccheck(struct sam_qh_s *qh, uint32_t **bp, void *arg)
* after the stall.
*/
- udbg("EP%d Stalled: TOKEN=%08x\n", epinfo->epno, token);
+ usbhost_trace2(EHCI_TRACE2_EPSTALLED, epinfo->epno, token);
epinfo->result = -EPERM;
epinfo->toggle = 0;
}
@@ -2439,7 +2440,7 @@ static int sam_qh_ioccheck(struct sam_qh_s *qh, uint32_t **bp, void *arg)
{
/* Otherwise, it is some kind of data transfer error */
- udbg("ERROR: EP%d TOKEN=%08x\n", epinfo->epno, token);
+ usbhost_trace2(EHCI_TRACE2_EPIOERROR, epinfo->epno, token);
epinfo->result = -EIO;
}
}
@@ -2514,7 +2515,7 @@ static inline void sam_ioc_bottomhalf(void)
ret = sam_qh_foreach(qh, &bp, sam_qh_ioccheck, NULL);
if (ret < 0)
{
- udbg("ERROR: sam_qh_foreach failed: %d\n", ret);
+ usbhost_trace1(EHCI_TRACE1_QHFOREACH_FAILED, -ret);
}
}
@@ -2540,7 +2541,7 @@ static inline void sam_ioc_bottomhalf(void)
ret = sam_qh_foreach(qh, &bp, sam_qh_ioccheck, NULL);
if (ret < 0)
{
- udbg("ERROR: sam_qh_foreach failed: %d\n", ret);
+ usbhost_trace1(EHCI_TRACE1_QHFOREACH_FAILED, -ret);
}
}
#endif
@@ -2679,7 +2680,7 @@ static inline void sam_portsc_bottomhalf(void)
static inline void sam_syserr_bottomhalf(void)
{
- udbg("Host System Error Interrupt\n");
+ usbhost_trace1(EHCI_TRACE1_SYSERR_INTR, 0);
PANIC();
}
@@ -2749,7 +2750,7 @@ static void sam_ehci_bottomhalf(FAR void *arg)
{
if ((pending & EHCI_INT_USBERRINT) != 0)
{
- udbg("USB Error Interrupt (USBERRINT) Interrupt\n");
+ usbhost_trace1(EHCI_TRACE1_USBERR_INTR, 0);
}
else
{
@@ -2885,7 +2886,7 @@ static int sam_ehci_tophalf(int irq, FAR void *context)
* interrupt bits back to the status register.
*/
- sam_putreg(usbsts & ECHI_INT_ALLINTS, &HCOR->usbsts);
+ sam_putreg(usbsts & EHCI_INT_ALLINTS, &HCOR->usbsts);
}
return OK;
@@ -3398,7 +3399,7 @@ static int sam_epalloc(FAR struct usbhost_driver_s *drvr,
epinfo = (struct sam_epinfo_s *)kzalloc(sizeof(struct sam_epinfo_s));
if (!epinfo)
{
- udbg("ERROR: Failed to allocate EP info structure\n");
+ usbhost_trace1(EHCI_TRACE1_EPALLOC_FAILED, 0);
return -ENOMEM;
}
@@ -3760,7 +3761,7 @@ static int sam_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
#endif
case USB_EP_ATTR_XFER_CONTROL:
default:
- udbg("ERROR: Support for transfer type %d not implemented\n");
+ usbhost_trace1(EHCI_TRACE1_BADXFRTYPE, epinfo->xfrtype);
nbytes = -ENOSYS;
break;
}
@@ -3880,7 +3881,7 @@ static int sam_reset(void)
if ((regval & EHCI_USBSTS_HALTED) == 0)
{
- udbg("ERROR: Timed out waiting for HCHalted. USBSTS: %08x", regval);
+ usbhost_trace1(EHCI_TRACE1_HCHALTED_TIMEOUT, regval);
return -ETIMEDOUT;
}
@@ -4079,7 +4080,7 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
kmemalign(32, CONFIG_SAMA5_EHCI_NQHS * sizeof(struct sam_qh_s));
if (!g_qhpool)
{
- udbg("ERROR: Failed to allocate the QH pool\n");
+ usbhost_trace1(EHCI_TRACE1_QHPOOLALLOC_FAILED, 0);
return NULL;
}
#endif
@@ -4100,7 +4101,7 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
kmemalign(32, CONFIG_SAMA5_EHCI_NQTDS * sizeof(struct sam_qtd_s));
if (!g_qtdpool)
{
- udbg("ERROR: Failed to allocate the qTD pool\n");
+ usbhost_trace1(EHCI_TRACE1_QTDPOOLALLOC_FAILED, 0);
kfree(g_qhpool);
return NULL;
}
@@ -4113,7 +4114,7 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
kmemalign(4096, FRAME_LIST_SIZE * sizeof(uint32_t));
if (!g_framelist)
{
- udbg("ERROR: Failed to allocate the periodic frame list\n");
+ usbhost_trace1(EHCI_TRACE1_PERFLALLOC_FAILED, 0);
kfree(g_qhpool);
kfree(g_qtdpool);
return NULL;
@@ -4136,7 +4137,7 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
ret = sam_reset();
if (ret < 0)
{
- udbg("ERROR: sam_reset failed: %d\n", ret);
+ usbhost_trace1(EHCI_TRACE1_RESET_FAILED, -ret);
return NULL;
}
@@ -4174,10 +4175,10 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
* writing a '1' to the corresponding bit.
*/
- sam_putreg(ECHI_INT_ALLINTS, &HCOR->usbsts);
+ sam_putreg(EHCI_INT_ALLINTS, &HCOR->usbsts);
#if defined(CONFIG_DEBUG_USB) && defined(CONFIG_DEBUG_VERBOSE)
- /* Show the ECHI version */
+ /* Show the EHCI version */
regval16 = sam_swap16(HCCR->hciversion);
uvdbg("HCIVERSION %x.%02x\n", regval16 >> 8, regval16 & 0xff);
@@ -4295,14 +4296,12 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
regval |= EHCI_CONFIGFLAG;
sam_putreg(regval, &HCOR->configflag);
- /* Wait for the ECHI to run (i.e., not longer report halted) */
+ /* Wait for the EHCI to run (i.e., no longer report halted) */
ret = ehci_wait_usbsts(EHCI_USBSTS_HALTED, 0, 100*1000);
if (ret < 0)
{
- udbg("ERROR: EHCI Failed to run: USBSTS=%08x\n",
- sam_getreg(&HCOR->usbsts));
-
+ usbhost_trace1(EHCI_TRACE1_RUN_FAILED, sam_getreg(&HCOR->usbsts));
return NULL;
}
@@ -4318,7 +4317,7 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
#endif
if (ret != 0)
{
- udbg("ERROR: Failed to attach IRQ\n");
+ usbhost_trace1(EHCI_TRACE1_IRQATTACH_FAILED, SAM_IRQ_UHPHS);
return NULL;
}
diff --git a/nuttx/arch/arm/src/sama5/sam_usbhost.c b/nuttx/arch/arm/src/sama5/sam_usbhost.c
new file mode 100644
index 000000000..5b3ee84e7
--- /dev/null
+++ b/nuttx/arch/arm/src/sama5/sam_usbhost.c
@@ -0,0 +1,154 @@
+/********************************************************************************************
+ * arch/arm/src/sama5/sam_host.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+
+#include <nuttx/usb/usbhost_trace.h>
+
+#include "sam_usbhost.h"
+
+#if defined(CONFIG_USBHOST_TRACE) || \
+ (defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_USB))
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+
+#define TR_OHCI false
+#define TR_EHCI true
+
+#define TR_FMT1 false
+#define TR_FMT2 true
+
+#define TRENTRY(id,ehci,fmt1,string) {string}
+
+/********************************************************************************************
+ * Private Types
+ ********************************************************************************************/
+
+struct sam_usbhost_trace_s
+{
+#if 0
+ uint16_t id;
+ bool ehci;
+ bool fmt2;
+#endif
+ FAR const char *string;
+};
+
+/********************************************************************************************
+ * Private Data
+ ********************************************************************************************/
+
+static const struct sam_usbhost_trace_s g_trace1[TRACE1_NSTRINGS] =
+{
+ TRENTRY(EHCI_TRACE1_SYSTEMERROR, TR_EHCI, TR_FMT1, "EHCI ERROR: System error: %06x\n"),
+ TRENTRY(EHCI_TRACE1_QTDFOREACH_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: sam_qtd_foreach failed: %d\n"),
+ TRENTRY(EHCI_TRACE1_QHALLOC_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: Failed to allocate a QH\n"),
+ TRENTRY(EHCI_TRACE1_BUFTOOBIG, TR_EHCI, TR_FMT1, "EHCI ERROR: Buffer too big. Remaining %d\n"),
+ TRENTRY(EHCI_TRACE1_REQQTDALLOC_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: Failed to allocate request qTD"),
+ TRENTRY(EHCI_TRACE1_ADDBPL_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: sam_qtd_addbpl failed: %d\n"),
+ TRENTRY(EHCI_TRACE1_DATAQTDALLOC_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: Failed to allocate data buffer qTD, 0"),
+ TRENTRY(EHCI_TRACE1_DEVDISCONNECTED, TR_EHCI, TR_FMT1, "EHCI ERROR: Device disconnected %d\n"),
+ TRENTRY(EHCI_TRACE1_QHCREATE_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: sam_qh_create failed\n"),
+ TRENTRY(EHCI_TRACE1_QTDSETUP_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: sam_qtd_setupphase failed\n"),
+ TRENTRY(EHCI_TRACE1_QTDDATA_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: sam_qtd_dataphase failed\n"),
+ TRENTRY(EHCI_TRACE1_QTDSTATUS_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: sam_qtd_statusphase failed\n"),
+ TRENTRY(EHCI_TRACE1_TRANSFER_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: Transfer failed %d\n"),
+ TRENTRY(EHCI_TRACE1_QHFOREACH_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: sam_qh_foreach failed: %d\n"),
+ TRENTRY(EHCI_TRACE1_SYSERR_INTR, TR_EHCI, TR_FMT1, "EHCI: Host System Error Interrupt\n"),
+ TRENTRY(EHCI_TRACE1_USBERR_INTR, TR_EHCI, TR_FMT1, "EHCI: USB Error Interrupt (USBERRINT) Interrupt\n"),
+ TRENTRY(EHCI_TRACE1_EPALLOC_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: Failed to allocate EP info structure\n"),
+ TRENTRY(EHCI_TRACE1_BADXFRTYPE, TR_EHCI, TR_FMT1, "EHCI ERROR: Support for transfer type %d not implemented\n"),
+ TRENTRY(EHCI_TRACE1_HCHALTED_TIMEOUT, TR_EHCI, TR_FMT1, "EHCI ERROR: Timed out waiting for HCHalted. USBSTS: %06x\n"),
+ TRENTRY(EHCI_TRACE1_QHPOOLALLOC_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: Failed to allocate the QH pool\n"),
+ TRENTRY(EHCI_TRACE1_QTDPOOLALLOC_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: Failed to allocate the qTD pool\n"),
+ TRENTRY(EHCI_TRACE1_PERFLALLOC_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: Failed to allocate the periodic frame list\n"),
+ TRENTRY(EHCI_TRACE1_RESET_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: sam_reset failed: %d\n"),
+ TRENTRY(EHCI_TRACE1_RUN_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: EHCI Failed to run: USBSTS=%08x\n"),
+ TRENTRY(EHCI_TRACE1_IRQATTACH_FAILED, TR_EHCI, TR_FMT1, "EHCI ERROR: Failed to attach IRQ%d\n"),
+};
+
+static const struct sam_usbhost_trace_s g_trace2[TRACE2_NSTRINGS] =
+{
+ TRENTRY(EHCI_TRACE2_EPSTALLED, TR_EHCI, TR_FMT2, "EHCI EP%d Stalled: TOKEN=%08x\n"),
+ TRENTRY(EHCI_TRACE2_EPIOERROR, TR_EHCI, TR_FMT2, "EHCI ERROR: EP%d TOKEN=%08x\n"),
+};
+
+/********************************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Global Functions
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Name: usbhost_trformat1 and usbhost_trformat2
+ *
+ * Description:
+ * This interface must be provided by platform specific logic that knows
+ * the HCDs encoding of USB trace data.
+ *
+ * Given an 9-bit index, return a format string suitable for use with, say,
+ * printf. The returned format is expected to handle two unsigned integer
+ * values.
+ *
+ ********************************************************************************************/
+
+FAR const char *usbhost_trformat1(uint16_t id)
+{
+ int ndx = TRACE1_INDEX(id);
+ DEBUGASSERT(ndx < TRACE1_NSTRINGS);
+ return g_trace1[ndx].string;
+}
+
+FAR const char *usbhost_trformat2(uint16_t id)
+{
+ int ndx = TRACE2_INDEX(id);
+ DEBUGASSERT(ndx < TRACE2_NSTRINGS);
+ return g_trace2[ndx].string;
+}
+
+#endif /* CONFIG_USBHOST_TRACE || CONFIG_DEBUG && CONFIG_DEBUG_USB */
+
diff --git a/nuttx/arch/arm/src/sama5/sam_usbhost.h b/nuttx/arch/arm/src/sama5/sam_usbhost.h
index 7ab5cca85..f64c94635 100644
--- a/nuttx/arch/arm/src/sama5/sam_usbhost.h
+++ b/nuttx/arch/arm/src/sama5/sam_usbhost.h
@@ -66,6 +66,50 @@
* Public Types
************************************************************************************/
+enum usbhost_trace1codes_e
+{
+ EHCI_TRACE1_SYSTEMERROR = 0, /* EHCI ERROR: System error */
+ EHCI_TRACE1_QTDFOREACH_FAILED, /* EHCI ERROR: sam_qtd_foreach failed */
+ EHCI_TRACE1_QHALLOC_FAILED, /* EHCI ERROR: Failed to allocate a QH */
+ EHCI_TRACE1_BUFTOOBIG, /* EHCI ERROR: Buffer too big */
+ EHCI_TRACE1_REQQTDALLOC_FAILED, /* EHCI ERROR: Failed to allocate request qTD */
+ EHCI_TRACE1_ADDBPL_FAILED, /* EHCI ERROR: sam_qtd_addbpl failed */
+ EHCI_TRACE1_DATAQTDALLOC_FAILED, /* EHCI ERROR: Failed to allocate data buffer qTD */
+ EHCI_TRACE1_DEVDISCONNECTED, /* EHCI ERROR: Device disconnected */
+ EHCI_TRACE1_QHCREATE_FAILED, /* EHCI ERROR: sam_qh_create failed */
+ EHCI_TRACE1_QTDSETUP_FAILED, /* EHCI ERROR: sam_qtd_setupphase failed */
+ EHCI_TRACE1_QTDDATA_FAILED, /* EHCI ERROR: sam_qtd_dataphase failed */
+ EHCI_TRACE1_QTDSTATUS_FAILED, /* EHCI ERROR: sam_qtd_statusphase failed */
+ EHCI_TRACE1_TRANSFER_FAILED, /* EHCI ERROR: Transfer failed */
+ EHCI_TRACE1_QHFOREACH_FAILED, /* EHCI ERROR: sam_qh_foreach failed: */
+ EHCI_TRACE1_SYSERR_INTR, /* EHCI: Host System Error Interrup */
+ EHCI_TRACE1_USBERR_INTR, /* EHCI: USB Error Interrupt (USBERRINT) Interrupt */
+ EHCI_TRACE1_EPALLOC_FAILED, /* EHCI ERROR: Failed to allocate EP info structure */
+ EHCI_TRACE1_BADXFRTYPE, /* EHCI ERROR: Support for transfer type not implemented */
+ EHCI_TRACE1_HCHALTED_TIMEOUT, /* EHCI ERROR: Timed out waiting for HCHalted */
+ EHCI_TRACE1_QHPOOLALLOC_FAILED, /* EHCI ERROR: Failed to allocate the QH pool */
+ EHCI_TRACE1_QTDPOOLALLOC_FAILED, /* EHCI ERROR: Failed to allocate the qTD pool */
+ EHCI_TRACE1_PERFLALLOC_FAILED, /* EHCI ERROR: Failed to allocate the periodic frame list */
+ EHCI_TRACE1_RESET_FAILED, /* EHCI ERROR: sam_reset failed */
+ EHCI_TRACE1_RUN_FAILED, /* EHCI ERROR: EHCI Failed to run: USBSTS=%08x */
+ EHCI_TRACE1_IRQATTACH_FAILED, /* EHCI ERROR: Failed to attach IRQ%d */
+
+ __TRACE1_NSTRINGS,
+
+ EHCI_TRACE2_EPSTALLED, /* EHCI EP Stalled */
+ EHCI_TRACE2_EPIOERROR, /* EHCI ERROR: EP TOKEN */
+
+ __TRACE2_NSTRINGS
+};
+
+#define TRACE1_FIRST 0
+#define TRACE1_INDEX(id) ((int)(id) - TRACE1_FIRST)
+#define TRACE1_NSTRINGS TRACE1_INDEX(__TRACE1_NSTRINGS)
+
+#define TRACE2_FIRST (__TRACE1_NSTRINGS + 1)
+#define TRACE2_INDEX(id) ((int)(id) - TRACE2_FIRST)
+#define TRACE2_NSTRINGS TRACE2_INDEX(__TRACE2_NSTRINGS)
+
/************************************************************************************
* Public Data
************************************************************************************/
diff --git a/nuttx/drivers/usbdev/Kconfig b/nuttx/drivers/usbdev/Kconfig
index 2adc79fe7..3151d04bd 100644
--- a/nuttx/drivers/usbdev/Kconfig
+++ b/nuttx/drivers/usbdev/Kconfig
@@ -80,7 +80,7 @@ config USBDEV_TRACE
config USBDEV_TRACE_NRECORDS
int "Number of trace entries to remember"
- default 32
+ default 128
depends on USBDEV_TRACE
---help---
Number of trace entries to remember
@@ -277,7 +277,7 @@ config CDCACM_IFNOBASE
default 0
depends on CDCACM_COMPOSITE
---help---
- If the CDC driver is part of a composite device, then this may need to
+ If the CDC driver is part of a composite device, then this may need to
be defined to offset the CDC/ACM interface numbers so that they are
unique and contiguous. When used with the Mass Storage driver, the
correct value for this offset is zero.
@@ -287,7 +287,7 @@ config CDCACM_STRBASE
default 0
depends on CDCACM_COMPOSITE
---help---
- If the CDC driver is part of a composite device, then this may need to
+ If the CDC driver is part of a composite device, then this may need to
be defined to offset the CDC/ACM string numbers so that they are
unique and contiguous. When used with the Mass Storage driver, the
correct value for this offset is four (this value actuallly only needs
@@ -461,7 +461,7 @@ config USBMSC_IFNOBASE
default 2
depends on USBMSC_COMPOSITE
---help---
- If the CDC driver is part of a composite device, then this may need to
+ If the CDC driver is part of a composite device, then this may need to
be defined to offset the mass storage interface number so that it is
unique and contiguous. When used with the CDC/ACM driver, the
correct value for this offset is two (because of the two CDC/ACM
@@ -472,7 +472,7 @@ config USBMSC_STRBASE
default 2
depends on USBMSC_COMPOSITE
---help---
- If the CDC driver is part of a composite device, then this may need to
+ If the CDC driver is part of a composite device, then this may need to
be defined to offset the mass storage string numbers so that they are
unique and contiguous. When used with the CDC/ACM driver, the
correct value for this offset is four (or perhaps 5 or 6, depending
diff --git a/nuttx/drivers/usbhost/Kconfig b/nuttx/drivers/usbhost/Kconfig
index 8975ecf56..b33bbf887 100644
--- a/nuttx/drivers/usbhost/Kconfig
+++ b/nuttx/drivers/usbhost/Kconfig
@@ -111,4 +111,19 @@ config HIDKBD_NODEBOUNCE
---help---
If set to y normal debouncing is disabled. Default:
Debounce enabled (No repeat keys).
+
endif
+
+config USBHOST_TRACE
+ bool "Enable USB HCD tracing for debug"
+ default n
+ ---help---
+ Enables USB tracing for debug. Only supported for the HCD and,
+ further, no supported by all HCD implementations.
+
+config USBHOST_TRACE_NRECORDS
+ int "Number of trace entries to remember"
+ default 128
+ depends on USBHOST_TRACE
+ ---help---
+ Number of trace entries to remember.
diff --git a/nuttx/drivers/usbhost/Make.defs b/nuttx/drivers/usbhost/Make.defs
index ac9eba6a6..2e00fd6cf 100644
--- a/nuttx/drivers/usbhost/Make.defs
+++ b/nuttx/drivers/usbhost/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# drivers/usbhost/Make.defs
#
-# Copyright (C) 2010-2012 Gregory Nutt. All rights reserved.
+# Copyright (C) 2010-2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -33,15 +33,25 @@
#
############################################################################
-CSRCS += hid_parser.c
+CSRCS += hid_parser.c
ifeq ($(CONFIG_USBHOST),y)
# Include built-in USB host driver logic
-CSRCS += usbhost_registry.c usbhost_registerclass.c usbhost_findclass.c
-CSRCS += usbhost_enumerate.c usbhost_storage.c usbhost_hidkbd.c
-CSRCS += usbhost_devaddr.c
+CSRCS += usbhost_registry.c usbhost_registerclass.c usbhost_findclass.c
+CSRCS += usbhost_enumerate.c usbhost_storage.c usbhost_hidkbd.c
+CSRCS += usbhost_devaddr.c
+
+# HCD debug/trace logic
+
+ifeq ($(CONFIG_USBHOST_TRACE),y)
+CSRCS += usbhost_trace.c
+else
+ifeq ($(CONFIG_DEBUG_USB),y)
+CSRCS += usbhost_trace.c
+endif
+endif
# Include add-on USB host driver logic (see misc/drivers)
diff --git a/nuttx/drivers/usbhost/usbhost_trace.c b/nuttx/drivers/usbhost/usbhost_trace.c
new file mode 100644
index 000000000..cb34d8fd2
--- /dev/null
+++ b/nuttx/drivers/usbhost/usbhost_trace.c
@@ -0,0 +1,305 @@
+/****************************************************************************
+ * drivers/usbhost/usbhost_trace.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <nuttx/usb/usbhost_trace.h>
+#undef usbtrace
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_USBHOST_TRACE_NRECORDS
+# define CONFIG_USBHOST_TRACE_NRECORDS 128
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#ifdef CONFIG_USBHOST_TRACE
+static uint32_t g_trace[CONFIG_USBHOST_TRACE_NRECORDS];
+static uint16_t g_head = 0;
+static uint16_t g_tail = 0;
+static volatile bool g_disabled = false;
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbhost_trsyslog
+ *
+ * Description:
+ * Dump trace data to the syslog()
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USBHOST_TRACE
+static int usbhost_trsyslog(uint32_t event, FAR void *arg)
+{
+ FAR const char *fmt;
+ uint16_t id;
+
+ /* Decode the trace data */
+
+ id = TRACE_DECODE_NDX(event);
+
+ /* Get the format associated with the trace. Try the one argument format
+ * first.
+ */
+
+ fmt = usbhost_trformat1(id);
+ if (fmt)
+ {
+ /* Just print the data using syslog() */
+
+ syslog(fmt, (unsigned int)TRACE_DECODE_U23(event));
+ }
+
+ /* No, then it must the the two argument format first. */
+
+ else
+ {
+ fmt = usbhost_trformat2(id);
+ DEBUGASSERT(fmt);
+ if (fmt)
+ {
+ /* Just print the data using syslog() */
+
+ syslog(fmt, (unsigned int)TRACE_DECODE_U7(event),
+ (unsigned int)TRACE_DECODE_U16(event));
+ }
+ }
+
+ return OK;
+}
+#endif /* CONFIG_USBHOST_TRACE */
+
+/****************************************************************************
+ * Name: usbhost_trace_common
+ *
+ * Description:
+ * Record a USB event (tracing or USB debug must be enabled)
+ *
+ * Assumptions:
+ * May be called from an interrupt handler
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USBHOST_TRACE
+void usbhost_trace_common(uint32_t event)
+{
+ irqstate_t flags;
+
+ /* Check if tracing is enabled for this ID */
+
+ flags = irqsave();
+ if (!g_disabled)
+ {
+ /* Yes... save the new trace data at the head */
+
+ g_trace[g_head] = event;
+
+ /* Increment the head and (probably) the tail index */
+
+ if (++g_head >= CONFIG_USBHOST_TRACE_NRECORDS)
+ {
+ g_head = 0;
+ }
+
+ if (g_head == g_tail)
+ {
+ if (++g_tail >= CONFIG_USBHOST_TRACE_NRECORDS)
+ {
+ g_tail = 0;
+ }
+ }
+ }
+ irqrestore(flags);
+}
+#endif /* CONFIG_USBHOST_TRACE */
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbhost_trace1 and usbhost_trace2
+ *
+ * Description:
+ * Record a USB event (tracing or USB debug must be enabled)
+ *
+ * Assumptions:
+ * May be called from an interrupt handler
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_USBHOST_TRACE) || \
+ (defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_USB))
+
+void usbhost_trace1(uint16_t id, uint32_t u23)
+{
+#ifdef CONFIG_USBHOST_TRACE
+ usbhost_trace_common(TRACE_ENCODE1(id, u23));
+#else
+ FAR const char *fmt;
+
+ /* Get the format associated with the trace */
+
+ fmt = usbhost_trformat1(id);
+ DEBUGASSERT(fmt);
+
+ /* Just print the data using syslog() */
+
+ syslog(fmt, (unsigned int)u23);
+#endif
+}
+
+void usbhost_trace2(uint16_t id, uint8_t u7, uint16_t u16)
+{
+#ifdef CONFIG_USBHOST_TRACE
+ usbhost_trace_common(TRACE_ENCODE2(id, u7, u16));
+#else
+ FAR const char *fmt;
+
+ /* Get the format associated with the trace */
+
+ fmt = usbhost_trformat2(id);
+ DEBUGASSERT(fmt);
+
+ /* Just print the data using syslog() */
+
+ syslog(fmt, u7, u16);
+#endif
+}
+
+#endif /* CONFIG_USBHOST_TRACE || CONFIG_DEBUG && CONFIG_DEBUG_USB */
+
+/*******************************************************************************
+ * Name: usbtrace_enumerate
+ *
+ * Description:
+ * Enumerate all buffer trace data (will temporarily disable tracing)
+ *
+ * Assumptions:
+ * NEVER called from an interrupt handler
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_USBHOST_TRACE
+int usbhost_trenumerate(usbhost_trcallback_t callback, FAR void *arg)
+{
+ uint16_t ndx;
+ int ret = OK;
+
+ /* Temporarily disable tracing to avoid conflicts */
+
+ g_disabled = true;
+
+ /* Visit every entry, starting with the tail */
+
+ for (ndx = g_tail; ndx != g_head; )
+ {
+ /* Call the user provided callback */
+
+ ret = callback(g_trace[ndx], arg);
+ if (ret != OK)
+ {
+ /* Abort the enumeration */
+
+ break;
+ }
+
+ /* Increment the index */
+
+ if (++ndx >= CONFIG_USBHOST_TRACE_NRECORDS)
+ {
+ ndx = 0;
+ }
+ }
+
+ /* Discard the trace data after it has been reported */
+
+ g_tail = g_head;
+
+ /* Restore tracing state */
+
+ g_disabled = false;
+ return ret;
+}
+#endif /* CONFIG_USBHOST_TRACE */
+
+/****************************************************************************
+ * Name: usbhost_trdump
+ *
+ * Description:
+ * Used usbhost_trenumerate to dump all buffer trace data to syslog().
+ *
+ * Assumptions:
+ * NEVER called from an interrupt handler
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USBHOST_TRACE
+int usbhost_trdump(void)
+{
+ return usbhost_trenumerate(usbhost_trsyslog, NULL);
+}
+#endif /* CONFIG_USBHOST_TRACE */
+
+
diff --git a/nuttx/include/nuttx/usb/ehci.h b/nuttx/include/nuttx/usb/ehci.h
index a10e6c99e..4b1ad8f1b 100755
--- a/nuttx/include/nuttx/usb/ehci.h
+++ b/nuttx/include/nuttx/usb/ehci.h
@@ -137,11 +137,11 @@
/* Debug Register Offsets *******************************************************************/
/* Paragraph C.3 */
-#define ECHI_DEBUG_PCS_OFFSET 0x0000 /* Debug Port Control/Status Register */
-#define ECHI_DEBUG_USBPIDS_OFFSET 0x0004 /* Debug USB PIDs Register */
-#define ECHI_DEBUG_DATA0_OFFSET 0x0008 /* Debug Data Buffer 0 Register [31:0] */
-#define ECHI_DEBUG_DATA1_OFFSET 0x000c /* Debug Data Buffer 1 Register [63:32] */
-#define ECHI_DEBUG_DEVADDR_OFFSET 0x0010 /* Debug Device Address Register */
+#define EHCI_DEBUG_PCS_OFFSET 0x0000 /* Debug Port Control/Status Register */
+#define EHCI_DEBUG_USBPIDS_OFFSET 0x0004 /* Debug USB PIDs Register */
+#define EHCI_DEBUG_DATA0_OFFSET 0x0008 /* Debug Data Buffer 0 Register [31:0] */
+#define EHCI_DEBUG_DATA1_OFFSET 0x000c /* Debug Data Buffer 1 Register [63:32] */
+#define EHCI_DEBUG_DEVADDR_OFFSET 0x0010 /* Debug Device Address Register */
/* PCI Configuration Space Register Bit Definitions *****************************************/
@@ -295,7 +295,7 @@
#define EHCI_INT_FLROLL (1 << 3) /* Bit 3: Frame List Rollover */
#define EHCI_INT_SYSERROR (1 << 4) /* Bit 4: Host System Error */
#define EHCI_INT_AAINT (1 << 5) /* Bit 5: Interrupt on Async Advance */
-#define ECHI_INT_ALLINTS (0x3f) /* Bits 0-5: All interrupts */
+#define EHCI_INT_ALLINTS (0x3f) /* Bits 0-5: All interrupts */
/* Bits 6-11: Reserved */
#define EHCI_USBSTS_HALTED (1 << 12) /* Bit 12: HC Halted */
#define EHCI_USBSTS_RECLAM (1 << 13) /* Bit 13: Reclamation */
@@ -368,41 +368,41 @@
/* Debug Port Control/Status Register. Paragraph C.3.1 */
-#define ECHI_DEBUG_PCS_LENGTH_SHIFT (0) /* Bits 0-3: Data Length */
-#define ECHI_DEBUG_PCS_LENGTH_MASK (15 << ECHI_DEBUG_PCS_LENGTH_SHIFT)
-#define ECHI_DEBUG_PCS_WRITE (1 << 4) /* Bit 6: Write/Read# */
-#define ECHI_DEBUG_PCS_GO (1 << 5) /* Bit 5: Go */
-#define ECHI_DEBUG_PCS_ERROR (1 << 6) /* Bit 6: Error/Good# */
-#define ECHI_DEBUG_PCS_EXCEPTION_SHIFT (17) /* Bits 7-9: Exception */
-#define ECHI_DEBUG_PCS_EXCEPTION_MASK (7 << ECHI_DEBUG_PCS_EXCEPTION_SHIFT)
-#define ECHI_DEBUG_PCS_INUSE (1 << 10) /* Bit 10: In Use */
+#define EHCI_DEBUG_PCS_LENGTH_SHIFT (0) /* Bits 0-3: Data Length */
+#define EHCI_DEBUG_PCS_LENGTH_MASK (15 << EHCI_DEBUG_PCS_LENGTH_SHIFT)
+#define EHCI_DEBUG_PCS_WRITE (1 << 4) /* Bit 6: Write/Read# */
+#define EHCI_DEBUG_PCS_GO (1 << 5) /* Bit 5: Go */
+#define EHCI_DEBUG_PCS_ERROR (1 << 6) /* Bit 6: Error/Good# */
+#define EHCI_DEBUG_PCS_EXCEPTION_SHIFT (17) /* Bits 7-9: Exception */
+#define EHCI_DEBUG_PCS_EXCEPTION_MASK (7 << EHCI_DEBUG_PCS_EXCEPTION_SHIFT)
+#define EHCI_DEBUG_PCS_INUSE (1 << 10) /* Bit 10: In Use */
/* Bits 11-15: Reserved */
-#define ECHI_DEBUG_PCS_DONE (1 << 16) /* Bit 16: Done */
+#define EHCI_DEBUG_PCS_DONE (1 << 16) /* Bit 16: Done */
/* Bits 17-27: Reserved */
-#define ECHI_DEBUG_PCS_ENABLED (1 << 28) /* Bit 28: Enabled */
+#define EHCI_DEBUG_PCS_ENABLED (1 << 28) /* Bit 28: Enabled */
/* Bit 29: Reserved */
-#define ECHI_DEBUG_PCS_OWNER (1 << 30) /* Bit 30: Owner */
+#define EHCI_DEBUG_PCS_OWNER (1 << 30) /* Bit 30: Owner */
/* Bit 31: Reserved */
/* Debug USB PIDs Register. Paragraph C.3.2 */
-#define ECHI_DEBUG_USBPIDS_TKPID_SHIFT (0) /* Bits 0-7: Token PID */
-#define ECHI_DEBUG_USBPIDS_TKPID_MASK (0xff << ECHI_DEBUG_USBPIDS_TKPID_SHIFT)
-#define ECHI_DEBUG_USBPIDS_SPID_SHIFT (8) /* Bits 8-15: Sent PID */
-#define ECHI_DEBUG_USBPIDS_SPID_MASK (0xff << ECHI_DEBUG_USBPIDS_SPID_SHIFT)
-#define ECHI_DEBUG_USBPIDS_RPID_SHIFT (16) /* Bits 16-23: Received PID */
-#define ECHI_DEBUG_USBPIDS_RPID_MASK (0xff << ECHI_DEBUG_USBPIDS_RPID_SHIFT)
+#define EHCI_DEBUG_USBPIDS_TKPID_SHIFT (0) /* Bits 0-7: Token PID */
+#define EHCI_DEBUG_USBPIDS_TKPID_MASK (0xff << EHCI_DEBUG_USBPIDS_TKPID_SHIFT)
+#define EHCI_DEBUG_USBPIDS_SPID_SHIFT (8) /* Bits 8-15: Sent PID */
+#define EHCI_DEBUG_USBPIDS_SPID_MASK (0xff << EHCI_DEBUG_USBPIDS_SPID_SHIFT)
+#define EHCI_DEBUG_USBPIDS_RPID_SHIFT (16) /* Bits 16-23: Received PID */
+#define EHCI_DEBUG_USBPIDS_RPID_MASK (0xff << EHCI_DEBUG_USBPIDS_RPID_SHIFT)
/* Bits 24-31: Reserved */
/* Debug Data Buffer 0/1 Register [64:0]. Paragreph C.3.3. 64 bits of data. */
/* Debug Device Address Register. Paragraph C.3.4 */
-#define ECHI_DEBUG_DEVADDR_ENDPT_SHIFT (0) /* Bit 0-3: USB Endpoint */
-#define ECHI_DEBUG_DEVADDR_ENDPT_MASK (15 << ECHI_DEBUG_DEVADDR_ENDPT_SHIFT)
+#define EHCI_DEBUG_DEVADDR_ENDPT_SHIFT (0) /* Bit 0-3: USB Endpoint */
+#define EHCI_DEBUG_DEVADDR_ENDPT_MASK (15 << EHCI_DEBUG_DEVADDR_ENDPT_SHIFT)
/* Bits 4-7: Reserved */
-#define ECHI_DEBUG_DEVADDR_ADDR_SHIFT (8) /* Bits 8-14: USB Address */
-#define ECHI_DEBUG_DEVADDR_ADDR_MASK (0x7f << ECHI_DEBUG_DEVADDR_ADDR_SHIFT)
+#define EHCI_DEBUG_DEVADDR_ADDR_SHIFT (8) /* Bits 8-14: USB Address */
+#define EHCI_DEBUG_DEVADDR_ADDR_MASK (0x7f << EHCI_DEBUG_DEVADDR_ADDR_SHIFT)
/* Bits 15-31: Reserved */
/* Data Structures **************************************************************************/
diff --git a/nuttx/include/nuttx/usb/usbhost_trace.h b/nuttx/include/nuttx/usb/usbhost_trace.h
index db263c40d..2e5dcd00a 100644
--- a/nuttx/include/nuttx/usb/usbhost_trace.h
+++ b/nuttx/include/nuttx/usb/usbhost_trace.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/usb/usbhost_trace.h
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -42,21 +42,32 @@
#include <nuttx/config.h>
-/* NOTE: Trace debug capability has not been implemented for USB host. It
- * should be a simple port of the USB device trace logic. But that has not
- * yet been done.
- */
-
/****************************************************************************
- * Preprocessor definitions
+ * Pre-processor definitions
****************************************************************************/
+/* Event encoding/decoding macros *******************************************/
+
+#define TRACE_ENCODE1(id,u23) (((uint32_t)(id) & 0x1ff) << 23 | \
+ ((uint32_t)(u23) & 0x007fffff))
+#define TRACE_ENCODE2(id,u7,u16) (((uint32_t)(id) & 0x1ff) << 23 | \
+ ((uint32_t)(u7) & 0x7f) << 16 | \
+ ((u16) & 0x0000ffff))
+
+#define TRACE_DECODE_NDX(ev) (((ev) >> 23) & 0x1ff)
+#define TRACE_DECODE_U7(ev) (((ev) >> 16) & 0x7f)
+#define TRACE_DECODE_U16(ev) ((ev) & 0x0000ffff)
+#define TRACE_DECODE_U23(ev) ((ev) & 0x007fffff)
/****************************************************************************
* Public Types
****************************************************************************/
+/* Enumeration callback function signature */
+
+typedef int (*usbhost_trcallback_t)(FAR uint32_t trace, FAR void *arg);
+
/****************************************************************************
- * Public Function Prototypes
+ * Public Data
****************************************************************************/
#undef EXTERN
@@ -67,6 +78,83 @@ extern "C" {
# define EXTERN extern
#endif
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbhost_trace and usbhost_trace2
+ *
+ * Description:
+ * Record a USB event (tracing or USB debug must be enabled)
+ *
+ * Assumptions:
+ * May be called from an interrupt handler
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_USBHOST_TRACE) || \
+ (defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_USB))
+void usbhost_trace1(uint16_t id, uint32_t u23);
+void usbhost_trace2(uint16_t id, uint8_t u7, uint16_t u16);
+#else
+# define usbhost_trace1(id, u23)
+# define usbhost_trace2(id, u7, u16)
+#endif
+
+/****************************************************************************
+ * Name: usbhost_trenumerate
+ *
+ * Description:
+ * Enumerate all buffer trace data (will temporarily disable tracing)
+ *
+ * Assumptions:
+ * NEVER called from an interrupt handler
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_USBHOST_TRACE)
+int usbhost_trenumerate(usbhost_trcallback_t callback, FAR void *arg);
+#else
+# define usbhost_trenumerate(callback,arg)
+#endif
+
+/****************************************************************************
+ * Name: usbhost_trdump
+ *
+ * Description:
+ * Used usbhost_trenumerate to dump all buffer trace data to syslog().
+ *
+ * Assumptions:
+ * NEVER called from an interrupt handler
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_USBHOST_TRACE)
+int usbhost_trdump(void);
+#else
+# define usbhost_trdump(void)
+#endif
+
+/****************************************************************************
+ * Name: usbhost_trformat1 and usbhost_trformat2
+ *
+ * Description:
+ * This interface must be provided by platform specific logic that knows
+ * the HCDs encoding of USB trace data.
+ *
+ * Given an 9-bit index, return a format string suitable for use with, say,
+ * printf. The returned format is expected to handle two unsigned integer
+ * values.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_USBHOST_TRACE) || \
+ (defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_USB))
+FAR const char *usbhost_trformat1(uint16_t id);
+FAR const char *usbhost_trformat2(uint16_t id);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}