summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-24 21:51:26 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-24 21:51:26 +0000
commit73914fb947019bd12dc1bd95e6e425db0c0b0550 (patch)
tree74afe39d652f36825427c2041504b676f83894c8 /nuttx/drivers
parentb4b6ea430cde3670d7f069311576abf9c725024c (diff)
downloadpx4-nuttx-73914fb947019bd12dc1bd95e6e425db0c0b0550.tar.gz
px4-nuttx-73914fb947019bd12dc1bd95e6e425db0c0b0550.tar.bz2
px4-nuttx-73914fb947019bd12dc1bd95e6e425db0c0b0550.zip
Lots of re-organization -- getting ready to support a composite USB device
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4329 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/usbdev/Make.defs14
-rw-r--r--nuttx/drivers/usbdev/cdcacm.c (renamed from nuttx/drivers/usbdev/cdc_serial.c)21
-rw-r--r--nuttx/drivers/usbdev/cdcacm.h (renamed from nuttx/drivers/usbdev/cdc_serial.h)130
-rw-r--r--nuttx/drivers/usbdev/cdcacm_descriptors.c (renamed from nuttx/drivers/usbdev/cdc_serdesc.c)82
-rw-r--r--nuttx/drivers/usbdev/composite.c292
-rw-r--r--nuttx/drivers/usbdev/composite.h (renamed from nuttx/drivers/usbdev/usbdev_composite.h)114
-rw-r--r--nuttx/drivers/usbdev/composite_descriptors.c366
-rw-r--r--nuttx/drivers/usbdev/msc.c (renamed from nuttx/drivers/usbdev/usbdev_storage.c)17
-rw-r--r--nuttx/drivers/usbdev/msc.h (renamed from nuttx/drivers/usbdev/usbdev_storage.h)133
-rw-r--r--nuttx/drivers/usbdev/msc_descriptors.c (renamed from nuttx/drivers/usbdev/usbdev_stordesc.c)55
-rw-r--r--nuttx/drivers/usbdev/msc_scsi.c (renamed from nuttx/drivers/usbdev/usbdev_scsi.c)8
-rw-r--r--nuttx/drivers/usbdev/pl2303.c (renamed from nuttx/drivers/usbdev/usbdev_serial.c)6
-rw-r--r--nuttx/drivers/usbdev/usbdev_composite.c85
-rw-r--r--nuttx/drivers/usbdev/usbdev_trace.c4
-rw-r--r--nuttx/drivers/usbdev/usbdev_trprintf.c4
15 files changed, 1094 insertions, 237 deletions
diff --git a/nuttx/drivers/usbdev/Make.defs b/nuttx/drivers/usbdev/Make.defs
index 4ae4a49e1..348799849 100644
--- a/nuttx/drivers/usbdev/Make.defs
+++ b/nuttx/drivers/usbdev/Make.defs
@@ -1,8 +1,8 @@
############################################################################
# drivers/usbdev/Make.defs
#
-# Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Copyright (C) 2008, 2010-2012 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
@@ -38,22 +38,22 @@ ifeq ($(CONFIG_USBDEV),y)
# Include USB device drivers
ifeq ($(CONFIG_USBSER),y)
- CSRCS += usbdev_serial.c
+ CSRCS += pl2303.c
endif
ifeq ($(CONFIG_CDCSER),y)
- CSRCS += cdc_serial.c cdc_serdesc.c
+ CSRCS += cdcacm.c cdcacm_descriptors.c
endif
ifeq ($(CONFIG_USBSTRG),y)
- CSRCS += usbdev_storage.c usbdev_stordesc.c usbdev_scsi.c
+ CSRCS += msc.c msc_descriptors.c msc_scsi.c
endif
ifeq ($(CONFIG_USBDEV_COMPOSITE),y)
- CSRCS += usbdev_composite.c
+ CSRCS += composite.c composite_descriptors.c
endif
-CSRCS += usbdev_trace.c usbdev_trprintf.c
+CSRCS += usbdev_trace.c usbdev_trprintf.c
# Include USB device build support
diff --git a/nuttx/drivers/usbdev/cdc_serial.c b/nuttx/drivers/usbdev/cdcacm.c
index c91b451c3..9c6c36625 100644
--- a/nuttx/drivers/usbdev/cdc_serial.c
+++ b/nuttx/drivers/usbdev/cdcacm.c
@@ -1,8 +1,8 @@
/****************************************************************************
- * drivers/usbdev/cdc_serial.c
+ * drivers/usbdev/cdcacm.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2011-2012 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
@@ -61,7 +61,7 @@
#include <nuttx/usb/cdc_serial.h>
#include <nuttx/usb/usbdev_trace.h>
-#include "cdc_serial.h"
+#include "cdcacm.h"
/****************************************************************************
* Pre-processor Definitions
@@ -158,8 +158,10 @@ static void cdcser_resetconfig(FAR struct cdcser_dev_s *priv);
static int cdcser_epconfigure(FAR struct usbdev_ep_s *ep,
enum cdcser_epdesc_e epid, uint16_t mxpacket, bool last);
#endif
+#ifndef CONFIG_CDCSER_COMPOSITE
static int cdcser_setconfig(FAR struct cdcser_dev_s *priv,
uint8_t config);
+#endif
/* Completion event handlers ***********************************************/
@@ -589,6 +591,7 @@ static int cdcser_epconfigure(FAR struct usbdev_ep_s *ep,
*
****************************************************************************/
+#ifndef CONFIG_CDCSER_COMPOSITE
static int cdcser_setconfig(FAR struct cdcser_dev_s *priv, uint8_t config)
{
FAR struct usbdev_req_s *req;
@@ -722,6 +725,7 @@ errout:
cdcser_resetconfig(priv);
return ret;
}
+#endif
/****************************************************************************
* Name: cdcser_ep0incomplete
@@ -1190,6 +1194,14 @@ static int cdcser_setup(FAR struct usbdev_s *dev, const struct usb_ctrlreq_s *ct
case USB_REQ_TYPE_STANDARD:
{
+ /* If the serial device is used in as part of a composite device,
+ * then standard descriptors are handled by logic in the composite
+ * device logic.
+ */
+
+#ifdef CONFIG_CDCSER_COMPOSITE
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDSTDREQ), ctrl->req);
+#else
switch (ctrl->req)
{
case USB_REQ_GETDESCRIPTOR:
@@ -1302,6 +1314,7 @@ static int cdcser_setup(FAR struct usbdev_s *dev, const struct usb_ctrlreq_s *ct
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDSTDREQ), ctrl->req);
break;
}
+#endif
}
break;
diff --git a/nuttx/drivers/usbdev/cdc_serial.h b/nuttx/drivers/usbdev/cdcacm.h
index 818cd4935..ca7352da8 100644
--- a/nuttx/drivers/usbdev/cdc_serial.h
+++ b/nuttx/drivers/usbdev/cdcacm.h
@@ -1,8 +1,8 @@
/****************************************************************************
- * drivers/usbdev/cdc_serial.h
+ * drivers/usbdev/cdcacm.h
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2011-2012 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
@@ -33,8 +33,8 @@
*
****************************************************************************/
-#ifndef __DRIVERS_USBDEV_USBDEV_CDC_SERIAL_H
-#define __DRIVERS_USBDEV_USBDEV_CDC_SERIAL_H 1
+#ifndef __DRIVERS_USBDEV_CDCACM_H
+#define __DRIVERS_USBDEV_CDCACM_H 1
/****************************************************************************
* Included Files
@@ -45,14 +45,37 @@
#include <stdint.h>
#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/cdc.h>
#include <nuttx/usb/usbdev_trace.h>
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
+/* Configuration ************************************************************/
+/* If the serial device is configured as part of a composite device than both
+ * CONFIG_USBDEV_COMPOSITE and CONFIG_CDCSER_COMPOSITE must be defined.
+ */
+
+#ifndef CONFIG_USBDEV_COMPOSITE
+# undef CONFIG_CDCSER_COMPOSITE
+#endif
+
+#if defined(CONFIG_CDCSER_COMPOSITE) && !defined(CONFIG_CDCSER_STRBASE)
+# define CONFIG_CDCSER_STRBASE (4)
+#endif
+
+/* Packet and request buffer sizes */
+
+#ifndef CONFIG_CDCSER_COMPOSITE
+# ifndef CONFIG_CDCSER_EP0MAXPACKET
+# define CONFIG_CDCSER_EP0MAXPACKET 64
+# endif
+#endif
+
/* Descriptors **************************************************************/
/* These settings are not modifiable via the NuttX configuration */
+#define CDC_VERSIONNO 0x0110 /* CDC version number 1.10 (BCD) */
#define CDCSER_CONFIGIDNONE (0) /* Config ID means to return to address mode */
#define CDCSER_INTERFACEID (0)
#define CDCSER_ALTINTERFACEID (0)
@@ -61,7 +84,88 @@
#define CDCSER_CONFIGID (1) /* The only supported configuration ID */
-/* Endpoint configuration */
+/* Buffer big enough for any of our descriptors (the config descriptor is the
+ * biggest).
+ */
+
+#define CDCSER_MXDESCLEN (64)
+
+/* Device descriptor values */
+
+#define CDCSER_VERSIONNO (0x0101) /* Device version number 1.1 (BCD) */
+#define CDCSER_NCONFIGS (1) /* Number of configurations supported */
+
+/* Configuration descriptor values */
+
+#define CDCSER_NINTERFACES (2) /* Number of interfaces in the configuration */
+
+/* String language */
+
+#define CDCSER_STR_LANGUAGE (0x0409) /* en-us */
+
+/* Descriptor strings. If there serial device is part of a composite device
+ * then the manufacturer, product, and serial number strings will be provided
+ * by the composite logic.
+ */
+
+#ifndef CONFIG_CDCSER_COMPOSITE
+# define CDCSER_MANUFACTURERSTRID (1)
+# define CDCSER_PRODUCTSTRID (2)
+# define CDCSER_SERIALSTRID (3)
+# define CDCSER_CONFIGSTRID (4)
+
+# undef CONFIG_CDCSER_STRBASE
+# define CONFIG_CDCSER_STRBASE (4)
+#endif
+
+/* These string IDs only exist if a user-defined string is provided */
+
+#ifdef CONFIG_CDCSER_NOTIFSTR
+# define CDCSER_NOTIFSTRID (CONFIG_CDCSER_STRBASE+1)
+#else
+# define CDCSER_NOTIFSTRID CONFIG_CDCSER_STRBASE
+#endif
+
+#ifdef CONFIG_CDCSER_DATAIFSTR
+# define CDCSER_DATAIFSTRID (CDCSER_NOTIFSTRID+1)
+#else
+# define CDCSER_DATAIFSTRID CDCSER_NOTIFSTRID
+#endif
+
+#define CDCSER_LASTSTRID CDCSER_DATAIFSTRID
+
+/* Configuration descriptor size */
+
+#ifndef CONFIG_CDCSER_COMPOSITE
+
+/* Number of individual descriptors in the configuration descriptor:
+ * Configuration descriptor + (2) interface descriptors + (3) endpoint
+ * descriptors + (3) ACM descriptors.
+ */
+
+# define CDCSER_CFGGROUP_SIZE (9)
+
+/* The size of the config descriptor: (9 + 2*9 + 3*7 + 4 + 5 + 5) = 62 */
+
+# define SIZEOF_CDCSER_CFGDESC \
+ (USB_SIZEOF_CFGDESC + 2*USB_SIZEOF_IFDESC + 3*USB_SIZEOF_EPDESC + \
+ SIZEOF_ACM_FUNCDESC + SIZEOF_HDR_FUNCDESC + SIZEOF_UNION_FUNCDESC(1))
+#else
+
+/* Number of individual descriptors in the configuration descriptor:
+ * (2) interface descriptors + (3) endpoint descriptors + (3) ACM descriptors.
+ */
+
+# define CDCSER_CFGGROUP_SIZE (8)
+
+/* The size of the config descriptor: (2*9 + 3*7 + 4 + 5 + 5) = 53 */
+
+# define SIZEOF_CDCSER_CFGDESC \
+ (2*USB_SIZEOF_IFDESC + 3*USB_SIZEOF_EPDESC + SIZEOF_ACM_FUNCDESC + \
+ SIZEOF_HDR_FUNCDESC + SIZEOF_UNION_FUNCDESC(1))
+#endif
+
+/* Endpoint configuration ****************************************************/
#define CDCSER_EPINTIN_ADDR (USB_DIR_IN|CONFIG_CDCSER_EPINTIN)
#define CDCSER_EPINTIN_ATTR (USB_EP_ATTR_XFER_INT)
@@ -72,12 +176,6 @@
#define CDCSER_EPINBULK_ADDR (USB_DIR_IN|CONFIG_CDCSER_EPBULKIN)
#define CDCSER_EPINBULK_ATTR (USB_EP_ATTR_XFER_BULK)
-/* Buffer big enough for any of our descriptors (the config descriptor is the
- * biggest).
- */
-
-#define CDCSER_MXDESCLEN (64)
-
/* Misc Macros **************************************************************/
/* min/max macros */
@@ -141,7 +239,9 @@ int cdcser_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc);
*
****************************************************************************/
+#ifndef CONFIG_CDCSER_COMPOSITE
FAR const struct usb_devdesc_s *cdcser_getdevdesc(void);
+#endif
/****************************************************************************
* Name: cdcser_getepdesc
@@ -189,8 +289,8 @@ int16_t cdcser_mkcfgdesc(FAR uint8_t *buf);
*
****************************************************************************/
-#ifdef CONFIG_USBDEV_DUALSPEED
+#if !defined(CONFIG_CDCSER_COMPOSITE) && defined(CONFIG_USBDEV_DUALSPEED)
FAR const struct usb_qualdesc_s *cdcser_getqualdesc(void);
#endif
-#endif /* __DRIVERS_USBDEV_USBDEV_CDC_SERIAL_H */
+#endif /* __DRIVERS_USBDEV_CDCACM_H */
diff --git a/nuttx/drivers/usbdev/cdc_serdesc.c b/nuttx/drivers/usbdev/cdcacm_descriptors.c
index 990704a1b..b8affe3cc 100644
--- a/nuttx/drivers/usbdev/cdc_serdesc.c
+++ b/nuttx/drivers/usbdev/cdcacm_descriptors.c
@@ -1,8 +1,8 @@
/****************************************************************************
- * drivers/usbdev/cdc_serdesc.c
+ * drivers/usbdev/cdcacm_descriptors.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2011-2012 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
@@ -50,46 +50,11 @@
#include <nuttx/usb/cdc_serial.h>
#include <nuttx/usb/usbdev_trace.h>
-#include "cdc_serial.h"
+#include "cdcacm.h"
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
-/* Descriptors **************************************************************/
-/* These settings are not modifiable via the NuttX configuration */
-
-#define CDC_VERSIONNO 0x0110 /* CDC version number 1.10 (BCD) */
-
-/* Device descriptor values */
-
-#define CDCSER_VERSIONNO (0x0101) /* Device version number 1.1 (BCD) */
-#define CDCSER_NCONFIGS (1) /* Number of configurations supported */
-
-/* Configuration descriptor values */
-
-#define CDCSER_NINTERFACES (2) /* Number of interfaces in the configuration */
-
-/* String language */
-
-#define CDCSER_STR_LANGUAGE (0x0409) /* en-us */
-
-/* Descriptor strings */
-
-#define CDCSER_MANUFACTURERSTRID (1)
-#define CDCSER_PRODUCTSTRID (2)
-#define CDCSER_SERIALSTRID (3)
-#define CDCSER_CONFIGSTRID (4)
-#define CDCSER_NOTIFSTRID (5)
-#define CDCSER_DATAIFSTRID (6)
-
-/* Number of individual descriptors in the configuration descriptor */
-
-#define CDCSER_CFGGROUP_SIZE (9)
-
-/* The size of the config descriptor: (9 + 2*9 + 3*7 + 4 + 5 + 5) = 62 */
-
-#define SIZEOF_CDCSER_CFGDESC \
- (USB_SIZEOF_CFGDESC + 2*USB_SIZEOF_IFDESC + 3*USB_SIZEOF_EPDESC + SIZEOF_ACM_FUNCDESC + SIZEOF_HDR_FUNCDESC + SIZEOF_UNION_FUNCDESC(1))
/****************************************************************************
* Private Types
@@ -115,7 +80,12 @@ struct cfgdecsc_group_s
****************************************************************************/
/* USB descriptor templates these will be copied and modified **************/
+/* Device Descriptor. If the USB serial device is configured as part of
+ * composite device, then the device descriptor will be provided by the
+ * composite device logic.
+ */
+#ifndef CONFIG_CDCSER_COMPOSITE
static const struct usb_devdesc_s g_devdesc =
{
USB_SIZEOF_DEVDESC, /* len */
@@ -145,9 +115,14 @@ static const struct usb_devdesc_s g_devdesc =
CDCSER_SERIALSTRID, /* serno */
CDCSER_NCONFIGS /* nconfigs */
};
+#endif
-/* Configuration descriptor */
+/* Configuration descriptor. If the USB serial device is configured as part of
+ * composite device, then the configuration descriptor will be provided by the
+ * composite device logic.
+ */
+#ifndef CONFIG_CDCSER_COMPOSITE
static const struct usb_cfgdesc_s g_cfgdesc =
{
USB_SIZEOF_CFGDESC, /* len */
@@ -162,6 +137,7 @@ static const struct usb_cfgdesc_s g_cfgdesc =
USB_CONFIG_ATTR_ONE|SELFPOWERED|REMOTEWAKEUP, /* attr */
(CONFIG_USBDEV_MAXPOWER + 1) / 2 /* mxpower */
};
+#endif
/* Notification interface */
@@ -290,12 +266,20 @@ static const struct usb_epdesc_s g_epbulkindesc =
* instead of compile time, there should no issues there either.
*/
-static const struct cfgdecsc_group_s g_cfggroup[CDCSER_CFGGROUP_SIZE] = {
+static const struct cfgdecsc_group_s g_cfggroup[CDCSER_CFGGROUP_SIZE] =
+{
+ /* Configuration Descriptor. If the serial device is used in as part
+ * or a composite device, then the configuration descriptor is
+ * provided by the composite device logic.
+ */
+
+#ifndef CONFIG_CDCSER_COMPOSITE
{
USB_SIZEOF_CFGDESC, /* 1. Configuration descriptor */
0,
(FAR void *)&g_cfgdesc
},
+#endif
{
USB_SIZEOF_IFDESC, /* 2. Notification interface */
0,
@@ -338,7 +322,7 @@ static const struct cfgdecsc_group_s g_cfggroup[CDCSER_CFGGROUP_SIZE] = {
}
};
-#ifdef CONFIG_USBDEV_DUALSPEED
+#if !defined(CONFIG_CDCSER_COMPOSITE) && defined(CONFIG_USBDEV_DUALSPEED)
static const struct usb_qualdesc_s g_qualdesc =
{
USB_SIZEOF_QUALDESC, /* len */
@@ -374,6 +358,9 @@ static const struct usb_qualdesc_s g_qualdesc =
int cdcser_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
{
+#if !defined(CONFIG_CDCSER_COMPOSITE) || defined(CONFIG_CDCSER_NOTIFSTR) || \
+ defined(CONFIG_CDCSER_DATAIFSTR)
+
const char *str;
int len;
int ndata;
@@ -381,6 +368,7 @@ int cdcser_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
switch (id)
{
+#ifndef CONFIG_CDCSER_COMPOSITE
case 0:
{
/* Descriptor 0 is the language id */
@@ -407,6 +395,7 @@ int cdcser_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
case CDCSER_CONFIGSTRID:
str = CONFIG_CDCSER_CONFIGSTR;
break;
+#endif
#ifdef CONFIG_CDCSER_NOTIFSTR
case CDCSER_NOTIFSTRID:
@@ -438,6 +427,9 @@ int cdcser_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
strdesc->len = ndata+2;
strdesc->type = USB_DESC_TYPE_STRING;
return strdesc->len;
+#else
+ return -EINVAL;
+#endif
}
/****************************************************************************
@@ -448,10 +440,12 @@ int cdcser_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
*
****************************************************************************/
+#ifndef CONFIG_CDCSER_COMPOSITE
FAR const struct usb_devdesc_s *cdcser_getdevdesc(void)
{
return &g_devdesc;
}
+#endif
/****************************************************************************
* Name: cdcser_getepdesc
@@ -582,7 +576,7 @@ int16_t cdcser_mkcfgdesc(FAR uint8_t *buf)
*
****************************************************************************/
-#ifdef CONFIG_USBDEV_DUALSPEED
+#if !defined(CONFIG_CDCSER_COMPOSITE) && defined(CONFIG_USBDEV_DUALSPEED)
FAR const struct usb_qualdesc_s *cdcser_getqualdesc(void)
{
return &g_qualdesc;
diff --git a/nuttx/drivers/usbdev/composite.c b/nuttx/drivers/usbdev/composite.c
new file mode 100644
index 000000000..4c9582355
--- /dev/null
+++ b/nuttx/drivers/usbdev/composite.c
@@ -0,0 +1,292 @@
+/****************************************************************************
+ * drivers/usbdev/composite.c
+ *
+ * Copyright (C) 2012 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 <nuttx/usb/usbdev_trace.h>
+
+#include "composite.h"
+
+#ifdef CONFIG_USBDEV_COMPOSITE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+ /****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: composite_setup
+ *
+ * Description:
+ * Invoked for ep0 control requests. This function probably executes
+ * in the context of an interrupt handler.
+ *
+ ****************************************************************************/
+
+ #if 0
+static int composite_setup(FAR struct usbdev_s *dev,
+ FAR const struct usb_ctrlreq_s *ctrl)
+{
+ FAR struct composite_dev_s *priv;
+ FAR struct usbdev_req_s *ctrlreq;
+ uint16_t value;
+ uint16_t index;
+ uint16_t len;
+ int ret = -EOPNOTSUPP;
+
+#ifdef CONFIG_DEBUG
+ if (!dev || !dev->ep0 || !ctrl)
+ {
+ usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_SETUPINVALIDARGS), 0);
+ return -EIO;
+ }
+#endif
+
+ /* Extract reference to private data */
+
+ usbtrace(TRACE_CLASSSETUP, ctrl->req);
+ priv = (FAR struct composite_dev_s *)dev->ep0->priv;
+
+#ifdef CONFIG_DEBUG
+ if (!priv || !priv->ctrlreq)
+ {
+ usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EP0NOTBOUND2), 0);
+ return -ENODEV;
+ }
+#endif
+ ctrlreq = priv->ctrlreq;
+
+ /* Extract the little-endian 16-bit values to host order */
+
+ value = GETUINT16(ctrl->value);
+ index = GETUINT16(ctrl->index);
+ len = GETUINT16(ctrl->len);
+
+ uvdbg("type=%02x req=%02x value=%04x index=%04x len=%04x\n",
+ ctrl->type, ctrl->req, value, index, len);
+
+ if ((ctrl->type & USB_REQ_TYPE_MASK) == USB_REQ_TYPE_STANDARD)
+ {
+ /**********************************************************************
+ * Standard Requests
+ **********************************************************************/
+
+ switch (ctrl->req)
+ {
+ case USB_REQ_GETDESCRIPTOR:
+ {
+ /* The value field specifies the descriptor type in the MS byte and the
+ * descriptor index in the LS byte (order is little endian)
+ */
+
+ switch (ctrl->value[1])
+ {
+ case USB_DESC_TYPE_DEVICE:
+ {
+ ret = USB_SIZEOF_DEVDESC;
+ memcpy(ctrlreq->buf, composite_getdevdesc(), ret);
+ }
+ break;
+
+#ifdef CONFIG_USBDEV_DUALSPEED
+ case USB_DESC_TYPE_DEVICEQUALIFIER:
+ {
+ ret = USB_SIZEOF_QUALDESC;
+ memcpy(ctrlreq->buf, composite_getqualdesc(), ret);
+ }
+ break;
+
+ case USB_DESC_TYPE_OTHERSPEEDCONFIG:
+#endif /* CONFIG_USBDEV_DUALSPEED */
+
+ case USB_DESC_TYPE_CONFIG:
+ {
+#ifdef CONFIG_USBDEV_DUALSPEED
+ ret = composite_mkcfgdesc(ctrlreq->buf, dev->speed, ctrl->value[1]);
+#else
+ ret = composite_mkcfgdesc(ctrlreq->buf);
+#endif
+ }
+ break;
+
+ case USB_DESC_TYPE_STRING:
+ {
+ /* index == language code. */
+
+ ret = composite_mkstrdesc(ctrl->value[0], (struct usb_strdesc_s *)ctrlreq->buf);
+ }
+ break;
+
+ default:
+ {
+ usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_GETUNKNOWNDESC), value);
+ }
+ break;
+ }
+ }
+ break;
+
+ case USB_REQ_SETCONFIGURATION:
+ {
+ if (ctrl->type == 0)
+ {
+ /* Signal the worker thread to instantiate the new configuration */
+
+ priv->theventset |= USBSTRG_EVENT_CFGCHANGE;
+ priv->thvalue = value;
+ pthread_cond_signal(&priv->cond);
+
+ /* Return here... the response will be provided later by the
+ * worker thread.
+ */
+
+ return OK;
+ }
+ }
+ break;
+
+ case USB_REQ_GETCONFIGURATION:
+ {
+ if (ctrl->type == USB_DIR_IN)
+ {
+ ctrlreq->buf[0] = priv->config;
+ ret = 1;
+ }
+ }
+ break;
+
+ case USB_REQ_SETINTERFACE:
+ {
+ if (ctrl->type == USB_REQ_RECIPIENT_INTERFACE)
+ {
+ if (priv->config == USBSTRG_CONFIGID &&
+ index == USBSTRG_INTERFACEID &&
+ value == USBSTRG_ALTINTERFACEID)
+ {
+ /* Signal to instantiate the interface change */
+
+ priv->theventset |= USBSTRG_EVENT_IFCHANGE;
+ pthread_cond_signal(&priv->cond);
+
+ /* Return here... the response will be provided later by the
+ * worker thread.
+ */
+
+ return OK;
+ }
+ }
+ }
+ break;
+
+ case USB_REQ_GETINTERFACE:
+ {
+ if (ctrl->type == (USB_DIR_IN|USB_REQ_RECIPIENT_INTERFACE) &&
+ priv->config == USBSTRG_CONFIGIDNONE)
+ {
+ if (index != USBSTRG_INTERFACEID)
+ {
+ ret = -EDOM;
+ }
+ else
+ {
+ ctrlreq->buf[0] = USBSTRG_ALTINTERFACEID;
+ ret = 1;
+ }
+ }
+ }
+ break;
+
+ default:
+ usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_UNSUPPORTEDSTDREQ), ctrl->req);
+ break;
+ }
+
+ /* Respond to the setup command if data was returned. On an error return
+ * value (ret < 0), the USB driver will stall EP0.
+ */
+
+ if (ret >= 0)
+ {
+ ctrlreq->len = min(len, ret);
+ ctrlreq->flags = USBDEV_REQFLAGS_NULLPKT;
+ ret = EP_SUBMIT(dev->ep0, ctrlreq);
+ if (ret < 0)
+ {
+ usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EPRESPQ), (uint16_t)-ret);
+ ctrlreq->result = OK;
+ composite_ep0incomplete(dev->ep0, ctrlreq);
+ }
+ }
+ else
+ {
+ /**********************************************************************
+ * Non-Standard Class Requests
+ **********************************************************************/
+#warning "Missing Logic"
+ }
+
+ return ret;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#endif /* CONFIG_USBDEV_COMPOSITE */
diff --git a/nuttx/drivers/usbdev/usbdev_composite.h b/nuttx/drivers/usbdev/composite.h
index 472f523b2..ed3b48eac 100644
--- a/nuttx/drivers/usbdev/usbdev_composite.h
+++ b/nuttx/drivers/usbdev/composite.h
@@ -1,8 +1,8 @@
/****************************************************************************
- * drivers/usbdev/usbdev_composite.h
+ * drivers/usbdev/composite.h
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2011-2012 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
@@ -33,8 +33,8 @@
*
****************************************************************************/
-#ifndef __DRIVERS_USBDEV_USBDEV_COMPOSITE_H
-#define __DRIVERS_USBDEV_USBDEV_COMPOSITE_H 1
+#ifndef __DRIVERS_USBDEV_COMPOSITE_H
+#define __DRIVERS_USBDEV_COMPOSITE_H 1
/****************************************************************************
* Included Files
@@ -45,10 +45,13 @@
#include <sys/types.h>
#include <stdint.h>
+#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev_trace.h>
+#ifdef CONFIG_USBDEV_COMPOSITE
+
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
@@ -60,6 +63,55 @@
# define CONFIG_USBDEV_TRACE_INITIALIDSET 0
#endif
+/* Packet sizes */
+
+#ifndef CONFIG_COMPOSITE_EP0MAXPACKET
+# define CONFIG_COMPOSITE_EP0MAXPACKET 64
+#endif
+
+/* Vendor and product IDs and strings */
+
+#ifndef CONFIG_COMPOSITE_COMPOSITE
+# ifndef CONFIG_COMPOSITE_VENDORID
+# warning "CONFIG_COMPOSITE_VENDORID not defined"
+# define CONFIG_COMPOSITE_VENDORID 0x584e
+# endif
+
+# ifndef CONFIG_COMPOSITE_PRODUCTID
+# warning "CONFIG_COMPOSITE_PRODUCTID not defined"
+# define CONFIG_COMPOSITE_PRODUCTID 0x5342
+# endif
+
+# ifndef CONFIG_COMPOSITE_VERSIONNO
+# define CONFIG_COMPOSITE_VERSIONNO (0x0399)
+# endif
+
+# ifndef CONFIG_COMPOSITE_VENDORSTR
+# warning "No Vendor string specified"
+# define CONFIG_COMPOSITE_VENDORSTR "NuttX"
+# endif
+
+# ifndef CONFIG_COMPOSITE_PRODUCTSTR
+# warning "No Product string specified"
+# define CONFIG_COMPOSITE_PRODUCTSTR "Composite Device"
+# endif
+
+# undef CONFIG_COMPOSITE_SERIALSTR
+# define CONFIG_COMPOSITE_SERIALSTR "0101"
+#endif
+
+#undef CONFIG_COMPOSITE_CONFIGSTR
+#define CONFIG_COMPOSITE_CONFIGSTR "Composite"
+
+/* Descriptors **************************************************************/
+
+/* Descriptor strings */
+
+#define COMPOSITE_MANUFACTURERSTRID (1)
+#define COMPOSITE_PRODUCTSTRID (2)
+#define COMPOSITE_SERIALSTRID (3)
+#define COMPOSITE_CONFIGSTRID (4)
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -72,15 +124,53 @@
* Public Function Prototypes
****************************************************************************/
-/*******************************************************************************
- * Name:
+/****************************************************************************
+ * Name: usbstrg_mkstrdesc
*
* Description:
+ * Construct a string descriptor
*
- * Input Parameters:
+ ****************************************************************************/
+
+int composite_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc);
+
+/****************************************************************************
+ * Name: composite_getepdesc
*
- * Returned Value:
+ * Description:
+ * Return a pointer to the composite device descriptor
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_COMPOSITE_COMPOSITE
+FAR const struct usb_devdesc_s *composite_getdevdesc(void);
+#endif
+
+/****************************************************************************
+ * Name: composite_mkcfgdesc
+ *
+ * Description:
+ * Construct the composite configuration descriptor
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USBDEV_DUALSPEED
+int16_t composite_mkcfgdesc(uint8_t *buf, uint8_t speed, uint8_t type);
+#else
+int16_t composite_mkcfgdesc(uint8_t *buf);
+#endif
+
+/****************************************************************************
+ * Name: composite_getqualdesc
*
- *******************************************************************************/
+ * Description:
+ * Return a pointer to the composite qual descriptor
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USBDEV_DUALSPEED
+FAR const struct usb_qualdesc_s *composite_getqualdesc(void);
+#endif
-#endif /* __DRIVERS_USBDEV_USBDEV_COMPOSITE_H */
+#endif /* CONFIG_USBDEV_COMPOSITE */
+#endif /* __DRIVERS_USBDEV_COMPOSITE_H */
diff --git a/nuttx/drivers/usbdev/composite_descriptors.c b/nuttx/drivers/usbdev/composite_descriptors.c
new file mode 100644
index 000000000..5feed8e21
--- /dev/null
+++ b/nuttx/drivers/usbdev/composite_descriptors.c
@@ -0,0 +1,366 @@
+/****************************************************************************
+ * drivers/usbdev/composite_descriptors.c
+ *
+ * Copyright (C) 2011-2012 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 <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev_trace.h>
+
+#include "composite.h"
+
+#ifdef CONFIG_CDCSER_COMPOSITE
+# include "cdcacm.h"
+#endif
+
+#ifdef CONFIG_USBSTRG_COMPOSITE
+# include "msc.h"
+#endif
+
+#ifdef CONFIG_USBDEV_COMPOSITE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#undef DEV1_IS_CDCSERIAL
+#undef DEV1_IS_USBSTRG
+
+#undef DEV2_IS_CDCSERIAL
+#undef DEV2_IS_USBSTRG
+
+/* Pick the first device in the composite. At present, this may only be
+ * the CDC serial device or the mass storage device.
+ */
+
+#if defined(CONFIG_CDCSER_COMPOSITE)
+# define DEV1_IS_CDCSERIAL 1
+# define DEV1_MKCFGDESC cdcser_mkcfgdesc
+# define DEV1_NCONFIGS CDCSER_NCONFIGS
+# define DEV1_CONFIGID CDCSER_CONFIGID
+# define DEV1_NINTERFACES CDCSER_NINTERFACES
+# define DEV1_FIRSTSTRID CONFIG_CDCSER_STRBASE
+# define DEV1_NSTRIDS (CDCSER_LASTSTRID-CONFIG_CDCSER_STRBASE)
+# define DEV1_CFGDESCSIZE SIZEOF_CDCSER_CFGDESC
+#elif defined(CONFIG_CDCSER_COMPOSITE)
+# define DEV1_IS_USBSTRG 1
+# define DEV1_MKCFGDESC composite_mkcfgdesc
+# define DEV1_NCONFIGS USBSTRG_NCONFIGS
+# define DEV1_CONFIGID USBSTRG_CONFIGID
+# define DEV1_NINTERFACES USBSTRG_NINTERFACES
+# define DEV1_FIRSTSTRID CONFIG_CDCSER_STRBASE
+# define DEV1_NSTRIDS (USBSTRG_LASTSTRID-CONFIG_USBSTRG_STRBASE)
+# define DEV1_CFGDESCSIZE SIZEOF_USBSTRG_CFGDESC
+#else
+# error "No members of the composite defined"
+#endif
+
+/* Pick the second device in the composite. At present, this may only be
+ * the CDC serial device or the mass storage device.
+ */
+
+#if defined(CONFIG_CDCSER_COMPOSITE) && !defined(DEV1_IS_CDCSERIAL)
+# define DEV2_IS_CDCSERIAL 1
+# define DEV2_MKCFGDESC cdcser_mkcfgdesc
+# define DEV2_NCONFIGS CDCSER_NCONFIGS
+# define DEV2_CONFIGID CDCSER_CONFIGID
+# define DEV2_NINTERFACES CDCSER_NINTERFACES
+# define DEV2_FIRSTSTRID CONFIG_CDCSER_STRBASE
+# define DEV2_NSTRIDS (CDCSER_LASTSTRID-CONFIG_CDCSER_STRBASE)
+# define DEV2_CFGDESCSIZE SIZEOF_CDCSER_CFGDESC
+#elif defined(CONFIG_CDCSER_COMPOSITE) && !defined(DEV1_IS_USBSTRG)
+# define DEV2_IS_USBSTRG 1
+# define DEV2_MKCFGDESC composite_mkcfgdesc
+# define DEV2_NCONFIGS USBSTRG_NCONFIGS
+# define DEV2_CONFIGID USBSTRG_CONFIGID
+# define DEV2_NINTERFACES USBSTRG_NINTERFACES
+# define DEV2_FIRSTSTRID CONFIG_CDCSER_STRBASE
+# define DEV2_NSTRIDS (USBSTRG_LASTSTRID-CONFIG_USBSTRG_STRBASE)
+# define DEV2_CFGDESCSIZE SIZEOF_USBSTRG_CFGDESC
+#else
+# error "Insufficient members of the composite defined"
+#endif
+
+/* Total size of the configuration descriptor: */
+
+#define COMPOSITE_CFGDESCSIZE (USB_SIZEOF_CFGDESC + DEV1_CFGDESCSIZE + DEV2_CFGDESCSIZE)
+
+/* The total number of interfaces */
+
+#define COMPOSITE_NINTERFACES (DEV1_NINTERFACES + DEV2_NINTERFACES)
+
+/* Composite configuration ID value */
+
+#if DEV1_NCONFIGS != 1 || DEV1_CONFIGID != 1
+# error "DEV1: Only a single configuration is supported"
+#endif
+
+#if DEV2_NCONFIGS != 1 || DEV2_CONFIGID != 1
+# error "DEV2: Only a single configuration is supported"
+#endif
+
+#define COMPOSITE_NCONFIGS 1
+#define COMPOSITE_CONFIGID 1
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+#ifdef CONFIG_USBDEV_DUALSPEED
+typedef int16_t (*mkcfgdesc)(FAR uint8_t *buf, uint8_t speed, uint8_t type);
+#else
+typedef int16_t (*mkcfgdesc)(FAR uint8_t *buf);
+#endif
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Device Descriptor */
+
+static const struct usb_devdesc_s g_devdesc =
+{
+ USB_SIZEOF_DEVDESC, /* len */
+ USB_DESC_TYPE_DEVICE, /* type */
+ { /* usb */
+ LSBYTE(0x0200),
+ MSBYTE(0x0200)
+ },
+ USB_CLASS_PER_INTERFACE, /* class */
+ 0, /* subclass */
+ 0, /* protocol */
+ CONFIG_COMPOSITE_EP0MAXPACKET, /* maxpacketsize */
+ {
+ LSBYTE(CONFIG_COMPOSITE_VENDORID), /* vendor */
+ MSBYTE(CONFIG_COMPOSITE_VENDORID)
+ },
+ {
+ LSBYTE(CONFIG_COMPOSITE_PRODUCTID), /* product */
+ MSBYTE(CONFIG_COMPOSITE_PRODUCTID)
+ },
+ {
+ LSBYTE(CONFIG_COMPOSITE_VERSIONNO), /* device */
+ MSBYTE(CONFIG_COMPOSITE_VERSIONNO)
+ },
+ COMPOSITE_MANUFACTURERSTRID, /* imfgr */
+ COMPOSITE_PRODUCTSTRID, /* iproduct */
+ COMPOSITE_SERIALSTRID, /* serno */
+ COMPOSITE_NCONFIGS /* nconfigs */
+};
+
+/* Configuration descriptor for the composite device */
+
+static const struct usb_cfgdesc_s g_cfgdesc =
+{
+ USB_SIZEOF_CFGDESC, /* len */
+ USB_DESC_TYPE_CONFIG, /* type */
+ {
+ LSBYTE(COMPOSITE_CFGDESCSIZE), /* LS totallen */
+ MSBYTE(COMPOSITE_CFGDESCSIZE) /* MS totallen */
+ },
+ COMPOSITE_NINTERFACES, /* ninterfaces */
+ COMPOSITE_CONFIGID, /* cfgvalue */
+ COMPOSITE_CONFIGSTRID, /* icfg */
+ USB_CONFIG_ATTR_ONE|SELFPOWERED|REMOTEWAKEUP, /* attr */
+ (CONFIG_USBDEV_MAXPOWER + 1) / 2 /* mxpower */
+};
+
+#ifdef CONFIG_USBDEV_DUALSPEED
+static const struct usb_qualdesc_s g_qualdesc =
+{
+ USB_SIZEOF_QUALDESC, /* len */
+ USB_DESC_TYPE_DEVICEQUALIFIER, /* type */
+ { /* usb */
+ LSBYTE(0x0200),
+ MSBYTE(0x0200)
+ },
+ USB_CLASS_VENDOR_SPEC, /* class */
+ 0, /* subclass */
+ 0, /* protocol */
+ CONFIG_COMPOSITE_EP0MAXPACKET, /* mxpacketsize */
+ COMPOSITE_NCONFIGS, /* nconfigs */
+ 0, /* reserved */
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbstrg_mkstrdesc
+ *
+ * Description:
+ * Construct a string descriptor
+ *
+ ****************************************************************************/
+
+int composite_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
+{
+ const char *str;
+ int len;
+ int ndata;
+ int i;
+
+ switch (id)
+ {
+ case 0:
+ {
+ /* Descriptor 0 is the language id */
+
+ strdesc->len = 4;
+ strdesc->type = USB_DESC_TYPE_STRING;
+ strdesc->data[0] = LSBYTE(USBSTRG_STR_LANGUAGE);
+ strdesc->data[1] = MSBYTE(USBSTRG_STR_LANGUAGE);
+ return 4;
+ }
+
+ case COMPOSITE_MANUFACTURERSTRID:
+ str = g_vendorstr;
+ break;
+
+ case COMPOSITE_PRODUCTSTRID:
+ str = g_productstr;
+ break;
+
+ case COMPOSITE_SERIALSTRID:
+ str = g_serialstr;
+ break;
+
+ case COMPOSITE_CONFIGSTRID:
+ str = CONFIG_USBSTRG_CONFIGSTR;
+ break;
+
+ default:
+ return -EINVAL;
+ }
+
+ /* The string is utf16-le. The poor man's utf-8 to utf16-le
+ * conversion below will only handle 7-bit en-us ascii
+ */
+
+ len = strlen(str);
+ for (i = 0, ndata = 0; i < len; i++, ndata += 2)
+ {
+ strdesc->data[ndata] = str[i];
+ strdesc->data[ndata+1] = 0;
+ }
+
+ strdesc->len = ndata+2;
+ strdesc->type = USB_DESC_TYPE_STRING;
+ return strdesc->len;
+}
+
+/****************************************************************************
+ * Name: composite_getepdesc
+ *
+ * Description:
+ * Return a pointer to the raw device descriptor
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_USBSTRG_COMPOSITE
+FAR const struct usb_devdesc_s *composite_getdevdesc(void)
+{
+ return &g_devdesc;
+}
+#endif
+
+/****************************************************************************
+ * Name: composite_mkcfgdesc
+ *
+ * Description:
+ * Construct the configuration descriptor
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USBDEV_DUALSPEED
+int16_t composite_mkcfgdesc(uint8_t *buf, uint8_t speed, uint8_t type)
+#else
+int16_t composite_mkcfgdesc(uint8_t *buf)
+#endif
+{
+ FAR struct usb_cfgdesc_s *cfgdesc = (struct usb_cfgdesc_s*)buf;
+
+ /* Configuration descriptor -- Copy the canned configuration descriptor. */
+
+ memcpy(cfgdesc, &g_cfgdesc, USB_SIZEOF_CFGDESC);
+ buf += USB_SIZEOF_CFGDESC;
+
+ /* Copy DEV1/DEV2 configuration descriptors */
+
+#ifdef CONFIG_USBDEV_DUALSPEED
+ buf += DEV1_MKCFGDESC(buf, speed, type);
+ buf += DEV2_MKCFGDESC(buf, speed, type);
+#else
+ buf += DEV1_MKCFGDESC(buf);
+ buf += DEV2_MKCFGDESC(buf);
+#endif
+
+ return COMPOSITE_CFGDESCSIZE;
+}
+
+/****************************************************************************
+ * Name: composite_getqualdesc
+ *
+ * Description:
+ * Return a pointer to the raw qual descriptor
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USBDEV_DUALSPEED
+FAR const struct usb_qualdesc_s *composite_getqualdesc(void)
+{
+ return &g_qualdesc;
+}
+#endif
+
+#endif /* CONFIG_USBDEV_COMPOSITE */
diff --git a/nuttx/drivers/usbdev/usbdev_storage.c b/nuttx/drivers/usbdev/msc.c
index 360756b12..a29153b64 100644
--- a/nuttx/drivers/usbdev/usbdev_storage.c
+++ b/nuttx/drivers/usbdev/msc.c
@@ -1,8 +1,8 @@
/****************************************************************************
- * drivers/usbdev/usbdev_storage.c
+ * drivers/usbdev/msc.c
*
- * Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Mass storage class device. Bulk-only with SCSI subclass.
*
@@ -80,7 +80,7 @@
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
-#include "usbdev_storage.h"
+#include "msc.h"
/****************************************************************************
* Pre-processor Definitions
@@ -520,6 +520,14 @@ static int usbstrg_setup(FAR struct usbdev_s *dev,
* Standard Requests
**********************************************************************/
+ /* If the mass storage device is used in as part of a composite device,
+ * then the configuration descriptor is is handled by logic in the
+ * composite device logic.
+ */
+
+#ifdef CONFIG_USBSTRG_COMPOSITE
+ usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_UNSUPPORTEDSTDREQ), ctrl->req);
+#else
switch (ctrl->req)
{
case USB_REQ_GETDESCRIPTOR:
@@ -649,6 +657,7 @@ static int usbstrg_setup(FAR struct usbdev_s *dev,
usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_UNSUPPORTEDSTDREQ), ctrl->req);
break;
}
+#endif
}
else
{
diff --git a/nuttx/drivers/usbdev/usbdev_storage.h b/nuttx/drivers/usbdev/msc.h
index 77cc0e53c..f73d1af9c 100644
--- a/nuttx/drivers/usbdev/usbdev_storage.h
+++ b/nuttx/drivers/usbdev/msc.h
@@ -1,8 +1,8 @@
/****************************************************************************
- * drivers/usbdev/usbdev_storage.h
+ * drivers/usbdev/msc.h
*
- * Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Mass storage class device. Bulk-only with SCSI subclass.
*
@@ -35,8 +35,8 @@
*
****************************************************************************/
-#ifndef __DRIVERS_USBDEV_USBDEV_STORAGE_H
-#define __DRIVERS_USBDEV_USBDEV_STORAGE_H
+#ifndef __DRIVERS_USBDEV_MSC_H
+#define __DRIVERS_USBDEV_MSC_H
/****************************************************************************
* Included Files
@@ -55,9 +55,22 @@
#include <nuttx/usb/usbdev.h>
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
+/* If the USB mass storage device is configured as part of a composite device
+ * then both CONFIG_USBDEV_COMPOSITE and CONFIG_USBSTRG_COMPOSITE must be
+ * defined.
+ */
+
+#ifndef CONFIG_USBDEV_COMPOSITE
+# undef CONFIG_USBSTRG_COMPOSITE
+#endif
+
+#if defined(CONFIG_USBSTRG_COMPOSITE) && !defined(CONFIG_USBSTRG_STRBASE)
+# define CONFIG_USBSTRG_STRBASE (4)
+#endif
+
/* Number of requests in the write queue */
#ifndef CONFIG_USBSTRG_NWRREQS
@@ -84,8 +97,10 @@
/* Packet and request buffer sizes */
-#ifndef CONFIG_USBSTRG_EP0MAXPACKET
-# define CONFIG_USBSTRG_EP0MAXPACKET 64
+#ifndef CONFIG_CDCSER_COMPOSITE
+# ifndef CONFIG_USBSTRG_EP0MAXPACKET
+# define CONFIG_USBSTRG_EP0MAXPACKET 64
+# endif
#endif
#ifndef CONFIG_USBSTRG_BULKINREQLEN
@@ -134,32 +149,34 @@
/* Vendor and product IDs and strings */
-#ifndef CONFIG_USBSTRG_VENDORID
-# warning "CONFIG_USBSTRG_VENDORID not defined"
-# define CONFIG_USBSTRG_VENDORID 0x584e
-#endif
+#ifndef CONFIG_USBSTRG_COMPOSITE
+# ifndef CONFIG_USBSTRG_VENDORID
+# warning "CONFIG_USBSTRG_VENDORID not defined"
+# define CONFIG_USBSTRG_VENDORID 0x584e
+# endif
-#ifndef CONFIG_USBSTRG_PRODUCTID
-# warning "CONFIG_USBSTRG_PRODUCTID not defined"
-# define CONFIG_USBSTRG_PRODUCTID 0x5342
-#endif
+# ifndef CONFIG_USBSTRG_PRODUCTID
+# warning "CONFIG_USBSTRG_PRODUCTID not defined"
+# define CONFIG_USBSTRG_PRODUCTID 0x5342
+# endif
-#ifndef CONFIG_USBSTRG_VERSIONNO
-# define CONFIG_USBSTRG_VERSIONNO (0x0399)
-#endif
+# ifndef CONFIG_USBSTRG_VERSIONNO
+# define CONFIG_USBSTRG_VERSIONNO (0x0399)
+# endif
-#ifndef CONFIG_USBSTRG_VENDORSTR
-# warning "No Vendor string specified"
-# define CONFIG_USBSTRG_VENDORSTR "NuttX"
-#endif
+# ifndef CONFIG_USBSTRG_VENDORSTR
+# warning "No Vendor string specified"
+# define CONFIG_USBSTRG_VENDORSTR "NuttX"
+# endif
-#ifndef CONFIG_USBSTRG_PRODUCTSTR
-# warning "No Product string specified"
-# define CONFIG_USBSTRG_PRODUCTSTR "USBdev Storage"
-#endif
+# ifndef CONFIG_USBSTRG_PRODUCTSTR
+# warning "No Product string specified"
+# define CONFIG_USBSTRG_PRODUCTSTR "USBdev Storage"
+# endif
-#undef CONFIG_USBSTRG_SERIALSTR
-#define CONFIG_USBSTRG_SERIALSTR "0101"
+# undef CONFIG_USBSTRG_SERIALSTR
+# define CONFIG_USBSTRG_SERIALSTR "0101"
+#endif
#undef CONFIG_USBSTRG_CONFIGSTR
#define CONFIG_USBSTRG_CONFIGSTR "Bulk"
@@ -260,10 +277,20 @@
/* Descriptor strings */
-#define USBSTRG_MANUFACTURERSTRID (1)
-#define USBSTRG_PRODUCTSTRID (2)
-#define USBSTRG_SERIALSTRID (3)
-#define USBSTRG_CONFIGSTRID (4)
+#ifndef CONFIG_USBSTRG_COMPOSITE
+# define USBSTRG_MANUFACTURERSTRID (1)
+# define USBSTRG_PRODUCTSTRID (2)
+# define USBSTRG_SERIALSTRID (3)
+# define USBSTRG_CONFIGSTRID (4)
+# define USBSTRG_INTERFACESTRID USBSTRG_CONFIGSTRID
+
+# undef CONFIG_USBSTRG_STRBASE
+# define CONFIG_USBSTRG_STRBASE (4)
+#else
+# define USBSTRG_INTERFACESTRID (CONFIG_USBSTRG_STRBASE+1)
+#endif
+#define USBSTRG_LASTSTRID USBSTRG_INTERFACESTRID
+
#define USBSTRG_NCONFIGS (1) /* Number of configurations supported */
/* Configuration Descriptor */
@@ -274,12 +301,6 @@
#define USBSTRG_CONFIGIDNONE (0) /* Config ID means to return to address mode */
#define USBSTRG_CONFIGID (1) /* The only supported configuration ID */
-#define STRING_MANUFACTURER (1)
-#define STRING_PRODUCT (2)
-#define STRING_SERIAL (3)
-
-#define USBSTRG_CONFIGID (1) /* There is only one configuration. */
-
/* Interface description */
#define USBSTRG_NENDPOINTS (2) /* Number of endpoints in the interface */
@@ -320,6 +341,34 @@
# define USBSTRG_BULKMXPKTMASK(d) USBSTRG_FSBULKMXPKTMASK
#endif
+/* Configuration descriptor size */
+
+#ifndef CONFIG_USBSTRG_COMPOSITE
+
+/* Number of individual descriptors in the configuration descriptor:
+ * (1) Configuration descriptor + (1) interface descriptor + (2) interface
+ * descriptors.
+ */
+
+# define USBSTRG_CFGGROUP_SIZE (4)
+
+/* The size of the config descriptor: (9 + 9 + 2*7) = 32 */
+
+# define SIZEOF_USBSTRG_CFGDESC \
+ (USB_SIZEOF_CFGDESC + USB_SIZEOF_IFDESC + 2*USB_SIZEOF_EPDESC)
+#else
+
+/* Number of individual descriptors in the configuration descriptor:
+ * (1) interface descriptor + (2) interface descriptors.
+ */
+
+# define USBSTRG_CFGGROUP_SIZE (3)
+
+/* The size of the config descriptor: (9 + 2*7) = 23 */
+
+# define SIZEOF_USBSTRG_CFGDESC (USB_SIZEOF_IFDESC + 2*USB_SIZEOF_EPDESC)
+#endif
+
/* Block driver helpers *****************************************************/
#define USBSTRG_DRVR_READ(l,b,s,n) ((l)->inode->u.i_bops->read((l)->inode,b,s,n))
@@ -481,7 +530,9 @@ int usbstrg_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc);
*
************************************************************************************/
+#ifndef CONFIG_USBSTRG_COMPOSITE
FAR const struct usb_devdesc_s *usbstrg_getdevdesc(void);
+#endif
/************************************************************************************
* Name: usbstrg_getepdesc
@@ -516,7 +567,7 @@ int16_t usbstrg_mkcfgdesc(FAR uint8_t *buf);
*
************************************************************************************/
-#ifdef CONFIG_USBDEV_DUALSPEED
+#if !defined(CONFIG_USBSTRG_COMPOSITE) && defined(CONFIG_USBDEV_DUALSPEED)
FAR const struct usb_qualdesc_s *usbstrg_getqualdesc(void);
#endif
@@ -605,4 +656,4 @@ EXTERN void usbstrg_deferredresponse(FAR struct usbstrg_dev_s *priv, bool failed
}
#endif
-#endif /* #define __DRIVERS_USBDEV_USBDEV_STORAGE_H */
+#endif /* #define __DRIVERS_USBDEV_MSC_H */
diff --git a/nuttx/drivers/usbdev/usbdev_stordesc.c b/nuttx/drivers/usbdev/msc_descriptors.c
index 68dffa96c..7cb77d8a1 100644
--- a/nuttx/drivers/usbdev/usbdev_stordesc.c
+++ b/nuttx/drivers/usbdev/msc_descriptors.c
@@ -1,8 +1,8 @@
/****************************************************************************
- * drivers/usbdev/usbdev_stordesc.c
+ * drivers/usbdev/msc_descriptors.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2011-2012 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
@@ -48,10 +48,10 @@
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbdev_trace.h>
-#include "usbdev_storage.h"
+#include "msc.h"
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/****************************************************************************
@@ -66,8 +66,12 @@
* Private Data
****************************************************************************/
/* Descriptors **************************************************************/
-/* Device descriptor */
+/* Device descriptor. If the USB mass storage device is configured as part
+ * of a composite device, then the device descriptor will be provided by the
+ * composite device logic.
+ */
+#ifndef CONFIG_USBSTRG_COMPOSITE
static const struct usb_devdesc_s g_devdesc =
{
USB_SIZEOF_DEVDESC, /* len */
@@ -93,9 +97,14 @@ static const struct usb_devdesc_s g_devdesc =
USBSTRG_SERIALSTRID, /* serno */
USBSTRG_NCONFIGS /* nconfigs */
};
+#endif
-/* Configuration descriptor */
+/* Configuration descriptor If the USB mass storage device is configured as part
+ * of a composite device, then the configuration descriptor will be provided by the
+ * composite device logic.
+ */
+#ifndef CONFIG_USBSTRG_COMPOSITE
static const struct usb_cfgdesc_s g_cfgdesc =
{
USB_SIZEOF_CFGDESC, /* len */
@@ -107,6 +116,7 @@ static const struct usb_cfgdesc_s g_cfgdesc =
USB_CONFIG_ATTR_ONE|SELFPOWERED|REMOTEWAKEUP, /* attr */
(CONFIG_USBDEV_MAXPOWER + 1) / 2 /* mxpower */
};
+#endif
/* Single interface descriptor */
@@ -120,7 +130,7 @@ static const struct usb_ifdesc_s g_ifdesc =
USB_CLASS_MASS_STORAGE, /* class */
USBSTRG_SUBCLASS_SCSI, /* subclass */
USBSTRG_PROTO_BULKONLY, /* protocol */
- USBSTRG_CONFIGSTRID /* iif */
+ USBSTRG_INTERFACESTRID /* iif */
};
/* Endpoint descriptors */
@@ -151,7 +161,8 @@ static const struct usb_epdesc_s g_fsepbulkindesc =
0 /* interval */
};
-#ifdef CONFIG_USBDEV_DUALSPEED
+#ifdef CONFIG_USBDEV_DUALSPEED
+#ifndef CONFIG_USBSTRG_COMPOSITE
static const struct usb_qualdesc_s g_qualdesc =
{
USB_SIZEOF_QUALDESC, /* len */
@@ -167,6 +178,7 @@ static const struct usb_qualdesc_s g_qualdesc =
USBSTRG_NCONFIGS, /* nconfigs */
0, /* reserved */
};
+#endif
static const struct usb_epdesc_s g_hsepbulkoutdesc =
{
@@ -200,9 +212,11 @@ static const struct usb_epdesc_s g_hsepbulkindesc =
****************************************************************************/
/* Strings ******************************************************************/
+#ifndef CONFIG_USBSTRG_COMPOSITE
const char g_vendorstr[] = CONFIG_USBSTRG_VENDORSTR;
const char g_productstr[] = CONFIG_USBSTRG_PRODUCTSTR;
const char g_serialstr[] = CONFIG_USBSTRG_SERIALSTR;
+#endif
/****************************************************************************
* Private Functions
@@ -229,6 +243,7 @@ int usbstrg_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
switch (id)
{
+#ifndef CONFIG_USBSTRG_COMPOSITE
case 0:
{
/* Descriptor 0 is the language id */
@@ -240,7 +255,7 @@ int usbstrg_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
return 4;
}
- case USBSTRG_MANUFACTURERSTRID:
+ case USBSTRG_MANUFACTURERSTRID:
str = g_vendorstr;
break;
@@ -251,8 +266,10 @@ int usbstrg_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
case USBSTRG_SERIALSTRID:
str = g_serialstr;
break;
+#endif
- case USBSTRG_CONFIGSTRID:
+ /* case USBSTRG_CONFIGSTRID: */
+ case USBSTRG_INTERFACESTRID:
str = CONFIG_USBSTRG_CONFIGSTR;
break;
@@ -284,10 +301,12 @@ int usbstrg_mkstrdesc(uint8_t id, struct usb_strdesc_s *strdesc)
*
****************************************************************************/
+#ifndef CONFIG_USBSTRG_COMPOSITE
FAR const struct usb_devdesc_s *usbstrg_getdevdesc(void)
{
return &g_devdesc;
}
+#endif
/****************************************************************************
* Name: usbstrg_getepdesc
@@ -334,7 +353,9 @@ int16_t usbstrg_mkcfgdesc(uint8_t *buf, uint8_t speed, uint8_t type)
int16_t usbstrg_mkcfgdesc(uint8_t *buf)
#endif
{
+#ifndef CONFIG_USBSTRG_COMPOSITE
FAR struct usb_cfgdesc_s *cfgdesc = (struct usb_cfgdesc_s*)buf;
+#endif
#ifdef CONFIG_USBDEV_DUALSPEED
FAR const struct usb_epdesc_s *epdesc;
bool hispeed = (speed == USB_SPEED_HIGH);
@@ -349,13 +370,17 @@ int16_t usbstrg_mkcfgdesc(uint8_t *buf)
totallen = USB_SIZEOF_CFGDESC + USB_SIZEOF_IFDESC + USBSTRG_NENDPOINTS * USB_SIZEOF_EPDESC;
/* Configuration descriptor -- Copy the canned descriptor and fill in the
- * type (we'll also need to update the size below
+ * type (we'll also need to update the size below). If the USB mass storage
+ * device is configured as part of a composite device, then the configuration
+ * descriptor will be provided by the composite device logic.
*/
+#ifndef CONFIG_USBSTRG_COMPOSITE
memcpy(cfgdesc, &g_cfgdesc, USB_SIZEOF_CFGDESC);
buf += USB_SIZEOF_CFGDESC;
+#endif
- /* Copy the canned interface descriptor */
+ /* Copy the canned interface descriptor */
memcpy(buf, &g_ifdesc, USB_SIZEOF_IFDESC);
buf += USB_SIZEOF_IFDESC;
@@ -386,8 +411,10 @@ int16_t usbstrg_mkcfgdesc(uint8_t *buf)
/* Finally, fill in the total size of the configuration descriptor */
+#ifndef CONFIG_USBSTRG_COMPOSITE
cfgdesc->totallen[0] = LSBYTE(totallen);
cfgdesc->totallen[1] = MSBYTE(totallen);
+#endif
return totallen;
}
@@ -399,7 +426,7 @@ int16_t usbstrg_mkcfgdesc(uint8_t *buf)
*
****************************************************************************/
-#ifdef CONFIG_USBDEV_DUALSPEED
+#if !defined(CONFIG_USBSTRG_COMPOSITE) && defined(CONFIG_USBDEV_DUALSPEED)
FAR const struct usb_qualdesc_s *usbstrg_getqualdesc(void)
{
return &g_qualdesc;
diff --git a/nuttx/drivers/usbdev/usbdev_scsi.c b/nuttx/drivers/usbdev/msc_scsi.c
index a0bbf8c2a..d5b0162e0 100644
--- a/nuttx/drivers/usbdev/usbdev_scsi.c
+++ b/nuttx/drivers/usbdev/msc_scsi.c
@@ -1,8 +1,8 @@
/****************************************************************************
- * drivers/usbdev/usbdev_storage.c
+ * drivers/usbdev/msc_scsi.c
*
- * Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008-2010, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Mass storage class device. Bulk-only with SCSI subclass.
*
@@ -73,7 +73,7 @@
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
-#include "usbdev_storage.h"
+#include "msc.h"
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/drivers/usbdev/usbdev_serial.c b/nuttx/drivers/usbdev/pl2303.c
index bef02ed73..86e55fefb 100644
--- a/nuttx/drivers/usbdev/usbdev_serial.c
+++ b/nuttx/drivers/usbdev/pl2303.c
@@ -1,8 +1,8 @@
/****************************************************************************
- * drivers/usbdev/usbdev_serial.c
+ * drivers/usbdev/pl2303.c
*
- * Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* This logic emulates the Prolific PL2303 serial/USB converter
*
diff --git a/nuttx/drivers/usbdev/usbdev_composite.c b/nuttx/drivers/usbdev/usbdev_composite.c
deleted file mode 100644
index de531b8a4..000000000
--- a/nuttx/drivers/usbdev/usbdev_composite.c
+++ /dev/null
@@ -1,85 +0,0 @@
-/****************************************************************************
- * drivers/usbdev/usbdev_composite.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * 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 <nuttx/usb/usbdev_trace.h>
-
-#include "usbdev_composite.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/*******************************************************************************
- * Name:
- *
- * Description:
- *
- * Input Parameters:
- *
- * Returned Value:
- *
- *******************************************************************************/
-
diff --git a/nuttx/drivers/usbdev/usbdev_trace.c b/nuttx/drivers/usbdev/usbdev_trace.c
index 7b258b1cb..c8cc09292 100644
--- a/nuttx/drivers/usbdev/usbdev_trace.c
+++ b/nuttx/drivers/usbdev/usbdev_trace.c
@@ -1,8 +1,8 @@
/****************************************************************************
* drivers/usbdev/usbdev_trace.c
*
- * Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008-2010, 2012 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
diff --git a/nuttx/drivers/usbdev/usbdev_trprintf.c b/nuttx/drivers/usbdev/usbdev_trprintf.c
index 55c517b2e..2a9921f98 100644
--- a/nuttx/drivers/usbdev/usbdev_trprintf.c
+++ b/nuttx/drivers/usbdev/usbdev_trprintf.c
@@ -1,8 +1,8 @@
/****************************************************************************
* drivers/usbdev/usbdev_trprintf.c
*
- * Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008-2010, 2012 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