summaryrefslogtreecommitdiff
path: root/nuttx/drivers
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 /nuttx/drivers
parent4425b0261bfdcd4cf8765917dc2b3a8b0d80c177 (diff)
downloadpx4-nuttx-845f1694727937478ab8487d2b7a2150ad0cc858.tar.gz
px4-nuttx-845f1694727937478ab8487d2b7a2150ad0cc858.tar.bz2
px4-nuttx-845f1694727937478ab8487d2b7a2150ad0cc858.zip
Beginning of support for USB host side tracing
Diffstat (limited to 'nuttx/drivers')
-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
4 files changed, 340 insertions, 10 deletions
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 */
+
+