summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog7
-rw-r--r--nuttx/Documentation/NuttX.html10
-rw-r--r--nuttx/drivers/usbhost/Make.defs2
-rw-r--r--nuttx/drivers/usbhost/usbhost_hidkbd.c1039
-rw-r--r--nuttx/drivers/usbhost/usbhost_skeleton.c1038
-rwxr-xr-xnuttx/include/nuttx/usb/hid.h190
6 files changed, 2284 insertions, 2 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 1d781751f..f25764d6b 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -1419,3 +1419,10 @@
Mass Storage Class.
5.17 2011-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
+
+ * include/nuttx/usb -- rename usb_storage.h to storage.h.
+ * arch/arm/src/lpc17xx/lpc17_usbhost.c -- Add support for low-speed devices.
+ * drivers/usbhost/usbhost_skeleton.c -- Template for new class drivers
+ * include/nuttx/usb/hid.h and drivers/usbhost/usbhost_hidkbd.c -- Initial
+ files for HID keyboard support. These are mostly empty files on the
+ initial checkin.
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index d8e5fbab5..e98e4a2fc 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: January 10, 2011</p>
+ <p>Last Updated: January 11, 2011</p>
</td>
</tr>
</table>
@@ -2101,6 +2101,14 @@ buildroot-1.8 2009-12-21 &lt;spudmonkey@racsa.co.cr&gt;
<ul><pre>
nuttx-5.17 2011-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
+ * include/nuttx/usb -- rename usb_storage.h to storage.h.
+ * arch/arm/src/lpc17xx/lpc17_usbhost.c -- Add support for low-speed devices.
+ * drivers/usbhost/usbhost_skeleton.c -- Template for new class drivers
+ * include/nuttx/usb/hid.h and drivers/usbhost/usbhost_hidkbd.c -- Initial
+ files for HID keyboard support. These are mostly empty files on the
+ initial checkin.
+
+
pascal-2.1 2010-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
buildroot-1.9 2010-xx-xx <spudmonkey@racsa.co.cr>
diff --git a/nuttx/drivers/usbhost/Make.defs b/nuttx/drivers/usbhost/Make.defs
index d1a34a941..d93666bed 100644
--- a/nuttx/drivers/usbhost/Make.defs
+++ b/nuttx/drivers/usbhost/Make.defs
@@ -38,5 +38,5 @@ USBHOST_CSRCS =
ifeq ($(CONFIG_USBHOST),y)
USBHOST_CSRCS += usbhost_registry.c usbhost_registerclass.c usbhost_findclass.c
-USBHOST_CSRCS += usbhost_enumerate.c usbhost_storage.c
+USBHOST_CSRCS += usbhost_enumerate.c usbhost_storage.c usbhost_hidkbd.c
endif
diff --git a/nuttx/drivers/usbhost/usbhost_hidkbd.c b/nuttx/drivers/usbhost/usbhost_hidkbd.c
new file mode 100644
index 000000000..a5d11a66d
--- /dev/null
+++ b/nuttx/drivers/usbhost/usbhost_hidkbd.c
@@ -0,0 +1,1039 @@
+/****************************************************************************
+ * drivers/usbhost/usbhost_hidkbd.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 <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/fs.h>
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+
+#include <nuttx/usb/usb.h>
+#include <nuttx/usb/usbhost.h>
+#include <nuttx/usb/hid.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error "Worker thread support is required (CONFIG_SCHED_WORKQUEUE)"
+#endif
+
+/* Driver support ***********************************************************/
+/* This format is used to construct the /dev/sd[n] device driver path. It
+ * defined here so that it will be used consistently in all places.
+ */
+
+#define DEV_FORMAT "/dev/sd%c"
+#define DEV_NAMELEN 10
+
+/* Used in usbhost_connect() */
+
+#define USBHOST_IFFOUND 0x01
+#define USBHOST_BINFOUND 0x02
+#define USBHOST_BOUTFOUND 0x04
+#define USBHOST_ALLFOUND 0x07
+
+#define USBHOST_MAX_CREFS 0x7fff
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* This structure contains the internal, private state of the USB host mass
+ * storage class.
+ */
+
+struct usbhost_state_s
+{
+ /* This is the externally visible portion of the state */
+
+ struct usbhost_class_s class;
+
+ /* This is an instance of the USB host driver bound to this class instance */
+
+ struct usbhost_driver_s *drvr;
+
+ /* The remainder of the fields are provide o the mass storage class */
+
+ char sdchar; /* Character identifying the /dev/sd[n] device */
+ volatile bool disconnected; /* TRUE: Device has been disconnected */
+ int16_t crefs; /* Reference count on the driver instance */
+ sem_t exclsem; /* Used to maintain mutual exclusive access */
+ struct work_s work; /* For interacting with the worker thread */
+ FAR uint8_t *tdbuffer; /* The allocated transfer descriptor buffer */
+ size_t tdbuflen; /* Size of the allocated transfer buffer */
+ usbhost_ep_t epin; /* IN endpoint */
+ usbhost_ep_t epout; /* OUT endpoint */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* Semaphores */
+
+static void usbhost_takesem(sem_t *sem);
+#define usbhost_givesem(s) sem_post(s);
+
+/* Memory allocation services */
+
+static inline FAR struct usbhost_state_s *usbhost_allocclass(void);
+static inline void usbhost_freeclass(FAR struct usbhost_state_s *class);
+
+/* Device name management */
+
+static int usbhost_allocdevno(FAR struct usbhost_state_s *priv);
+static void usbhost_freedevno(FAR struct usbhost_state_s *priv);
+static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, char *devname);
+
+/* Worker thread actions */
+
+static void usbhost_destroy(FAR void *arg);
+static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
+ FAR const uint8_t *configdesc, int desclen,
+ uint8_t funcaddr);
+static inline int usbhost_devinit(FAR struct usbhost_state_s *priv);
+
+/* (Little Endian) Data helpers */
+
+static inline uint16_t usbhost_getle16(const uint8_t *val);
+static inline void usbhost_putle16(uint8_t *dest, uint16_t val);
+static inline uint32_t usbhost_getle32(const uint8_t *val);
+static void usbhost_putle32(uint8_t *dest, uint32_t val);
+
+/* Transfer descriptor memory management */
+
+static inline int usbhost_tdalloc(FAR struct usbhost_state_s *priv);
+static inline int usbhost_tdfree(FAR struct usbhost_state_s *priv);
+
+/* struct usbhost_registry_s methods */
+
+static struct usbhost_class_s *usbhost_create(FAR struct usbhost_driver_s *drvr,
+ FAR const struct usbhost_id_s *id);
+
+/* struct usbhost_class_s methods */
+
+static int usbhost_connect(FAR struct usbhost_class_s *class,
+ FAR const uint8_t *configdesc, int desclen,
+ uint8_t funcaddr);
+static int usbhost_disconnected(FAR struct usbhost_class_s *class);
+
+/* Driver methods -- depend upon the type of NuttX driver interface exported */
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* This structure provides the registry entry ID informatino that will be
+ * used to associate the USB host mass storage class to a connected USB
+ * device.
+ */
+
+static const const struct usbhost_id_s g_id =
+{
+ USB_CLASS_HID, /* base */
+ USBHID_SUBCLASS_BOOTIF, /* subclass */
+ USBHID_PROTOCOL_KEYBOARD, /* proto */
+ 0, /* vid */
+ 0 /* pid */
+};
+
+/* This is the USB host storage class's registry entry */
+
+static struct usbhost_registry_s g_skeleton =
+{
+ NULL, /* flink */
+ usbhost_create, /* create */
+ 1, /* nids */
+ &g_id /* id[] */
+};
+
+/* This is a bitmap that is used to allocate device names /dev/sda-z. */
+
+static uint32_t g_devinuse;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbhost_takesem
+ *
+ * Description:
+ * This is just a wrapper to handle the annoying behavior of semaphore
+ * waits that return due to the receipt of a signal.
+ *
+ ****************************************************************************/
+
+static void usbhost_takesem(sem_t *sem)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(sem) != 0)
+ {
+ /* The only case that an error should occr here is if the wait was
+ * awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
+/****************************************************************************
+ * Name: usbhost_allocclass
+ *
+ * Description:
+ * This is really part of the logic that implements the create() method
+ * of struct usbhost_registry_s. This function allocates memory for one
+ * new class instance.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Values:
+ * On success, this function will return a non-NULL instance of struct
+ * usbhost_class_s. NULL is returned on failure; this function will
+ * will fail only if there are insufficient resources to create another
+ * USB host class instance.
+ *
+ ****************************************************************************/
+
+static inline FAR struct usbhost_state_s *usbhost_allocclass(void)
+{
+ FAR struct usbhost_state_s *priv;
+
+ DEBUGASSERT(!up_interrupt_context());
+ priv = (FAR struct usbhost_state_s *)malloc(sizeof(struct usbhost_state_s));
+ uvdbg("Allocated: %p\n", priv);;
+ return priv;
+}
+
+/****************************************************************************
+ * Name: usbhost_freeclass
+ *
+ * Description:
+ * Free a class instance previously allocated by usbhost_allocclass().
+ *
+ * Input Parameters:
+ * class - A reference to the class instance to be freed.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static inline void usbhost_freeclass(FAR struct usbhost_state_s *class)
+{
+ DEBUGASSERT(class != NULL);
+
+ /* Free the class instance (calling sched_free() in case we are executing
+ * from an interrupt handler.
+ */
+
+ uvdbg("Freeing: %p\n", class);;
+ free(class);
+}
+
+/****************************************************************************
+ * Name: Device name management
+ *
+ * Description:
+ * Some tiny functions to coordinate management of device names.
+ *
+ ****************************************************************************/
+
+static int usbhost_allocdevno(FAR struct usbhost_state_s *priv)
+{
+ irqstate_t flags;
+ int devno;
+
+ flags = irqsave();
+ for (devno = 0; devno < 26; devno++)
+ {
+ uint32_t bitno = 1 << devno;
+ if ((g_devinuse & bitno) == 0)
+ {
+ g_devinuse |= bitno;
+ priv->sdchar = 'a' + devno;
+ irqrestore(flags);
+ return OK;
+ }
+ }
+
+ irqrestore(flags);
+ return -EMFILE;
+}
+
+static void usbhost_freedevno(FAR struct usbhost_state_s *priv)
+{
+ int devno = 'a' - priv->sdchar;
+
+ if (devno >= 0 && devno < 26)
+ {
+ irqstate_t flags = irqsave();
+ g_devinuse &= ~(1 << devno);
+ irqrestore(flags);
+ }
+}
+
+static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, char *devname)
+{
+ (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, priv->sdchar);
+}
+
+/****************************************************************************
+ * Name: usbhost_destroy
+ *
+ * Description:
+ * The USB device has been disconnected and the refernce count on the USB
+ * host class instance has gone to 1.. Time to destroy the USB host class
+ * instance.
+ *
+ * Input Parameters:
+ * arg - A reference to the class instance to be destroyed.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static void usbhost_destroy(FAR void *arg)
+{
+ FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)arg;
+
+ DEBUGASSERT(priv != NULL);
+ uvdbg("crefs: %d\n", priv->crefs);
+
+ /* Unregister the driver */
+
+ /* Release the device name used by this connection */
+
+ usbhost_freedevno(priv);
+
+ /* Free the endpoints */
+
+ /* Free any transfer buffers */
+
+ /* Destroy the semaphores */
+
+ /* Disconnect the USB host device */
+
+ DRVR_DISCONNECT(priv->drvr);
+
+ /* And free the class instance. Hmmm.. this may execute on the worker
+ * thread and the work structure is part of what is getting freed. That
+ * should be okay because once the work contained is removed from the
+ * queue, it should not longer be accessed by the worker thread.
+ */
+
+ usbhost_freeclass(priv);
+}
+
+/****************************************************************************
+ * Name: usbhost_cfgdesc
+ *
+ * Description:
+ * This function implements the connect() method of struct
+ * usbhost_class_s. This method is a callback into the class
+ * implementation. It is used to provide the device's configuration
+ * descriptor to the class so that the class may initialize properly
+ *
+ * Input Parameters:
+ * priv - The USB host class instance.
+ * configdesc - A pointer to a uint8_t buffer container the configuration descripor.
+ * desclen - The length in bytes of the configuration descriptor.
+ * funcaddr - The USB address of the function containing the endpoint that EP0
+ * controls
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ****************************************************************************/
+
+static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
+ FAR const uint8_t *configdesc, int desclen,
+ uint8_t funcaddr)
+{
+ FAR struct usb_cfgdesc_s *cfgdesc;
+ FAR struct usb_desc_s *desc;
+ FAR struct usbhost_epdesc_s bindesc;
+ FAR struct usbhost_epdesc_s boutdesc;
+ int remaining;
+ uint8_t found = 0;
+ int ret;
+
+ DEBUGASSERT(priv != NULL &&
+ configdesc != NULL &&
+ desclen >= sizeof(struct usb_cfgdesc_s));
+
+ /* Verify that we were passed a configuration descriptor */
+
+ cfgdesc = (FAR struct usb_cfgdesc_s *)configdesc;
+ if (cfgdesc->type != USB_DESC_TYPE_CONFIG)
+ {
+ return -EINVAL;
+ }
+
+ /* Get the total length of the configuration descriptor (little endian).
+ * It might be a good check to get the number of interfaces here too.
+ */
+
+ remaining = (int)usbhost_getle16(cfgdesc->totallen);
+
+ /* Skip to the next entry descriptor */
+
+ configdesc += cfgdesc->len;
+ remaining -= cfgdesc->len;
+
+ /* Loop where there are more dscriptors to examine */
+
+ while (remaining >= sizeof(struct usb_desc_s))
+ {
+ /* What is the next descriptor? */
+
+ desc = (FAR struct usb_desc_s *)configdesc;
+ switch (desc->type)
+ {
+ /* Interface descriptor. We really should get the number of endpoints
+ * from this descriptor too.
+ */
+
+ case USB_DESC_TYPE_INTERFACE:
+ {
+ DEBUGASSERT(remaining >= USB_SIZEOF_IFDESC);
+ if ((found & USBHOST_IFFOUND) != 0)
+ {
+ /* Oops.. more than one interface. We don't know what to do with this. */
+
+ return -ENOSYS;
+ }
+ found |= USBHOST_IFFOUND;
+ }
+ break;
+
+ /* Endpoint descriptor. We expect two bulk endpoints, an IN and an OUT */
+ case USB_DESC_TYPE_ENDPOINT:
+ {
+ FAR struct usb_epdesc_s *epdesc = (FAR struct usb_epdesc_s *)configdesc;
+ DEBUGASSERT(remaining >= USB_SIZEOF_EPDESC);
+
+ /* Check for a bulk endpoint. We only support the bulk-only
+ * protocol so I suppose anything else should really be an error.
+ */
+
+ if ((epdesc->attr & USB_EP_ATTR_XFERTYPE_MASK) == USB_EP_ATTR_XFER_BULK)
+ {
+ /* Yes.. it is a bulk endpoint. IN or OUT? */
+
+ if (USB_ISEPOUT(epdesc->addr))
+ {
+ /* It is an OUT bulk endpoint. There should be only one bulk OUT endpoint. */
+
+ if ((found & USBHOST_BOUTFOUND) != 0)
+ {
+ /* Oops.. more than one interface. We don't know what to do with this. */
+
+ return -EINVAL;
+ }
+ found |= USBHOST_BOUTFOUND;
+
+ /* Save the bulk OUT endpoint information */
+
+ boutdesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK;
+ boutdesc.in = false;
+ boutdesc.funcaddr = funcaddr;
+ boutdesc.mxpacketsize = usbhost_getle16(epdesc->mxpacketsize);
+ uvdbg("Bulk OUT EP addr:%d mxpacketsize:%d\n",
+ boutdesc.addr, boutdesc.mxpacketsize);
+ }
+ else
+ {
+ /* It is an IN bulk endpoint. There should be only one bulk IN endpoint. */
+
+ if ((found & USBHOST_BINFOUND) != 0)
+ {
+ /* Oops.. more than one interface. We don't know what to do with this. */
+
+ return -EINVAL;
+ }
+ found |= USBHOST_BINFOUND;
+
+ /* Save the bulk IN endpoint information */
+
+ bindesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK;
+ bindesc.in = 1;
+ bindesc.funcaddr = funcaddr;
+ bindesc.mxpacketsize = usbhost_getle16(epdesc->mxpacketsize);
+ uvdbg("Bulk IN EP addr:%d mxpacketsize:%d\n",
+ bindesc.addr, bindesc.mxpacketsize);
+ }
+ }
+ }
+ break;
+
+ /* Other descriptors are just ignored for now */
+
+ default:
+ break;
+ }
+
+ /* Increment the address of the next descriptor */
+
+ configdesc += desc->len;
+ remaining -= desc->len;
+ }
+
+ /* Sanity checking... did we find all of things that we need? Hmmm.. I wonder..
+ * can we work read-only or write-only if only one bulk endpoint found?
+ */
+
+ if (found != USBHOST_ALLFOUND)
+ {
+ ulldbg("ERROR: Found IF:%s BIN:%s BOUT:%s\n",
+ (found & USBHOST_IFFOUND) != 0 ? "YES" : "NO",
+ (found & USBHOST_BINFOUND) != 0 ? "YES" : "NO",
+ (found & USBHOST_BOUTFOUND) != 0 ? "YES" : "NO");
+ return -EINVAL;
+ }
+
+ /* We are good... Allocate the endpoints */
+
+ ret = DRVR_EPALLOC(priv->drvr, &boutdesc, &priv->epout);
+ if (ret != OK)
+ {
+ udbg("ERROR: Failed to allocate Bulk OUT endpoint\n");
+ return ret;
+ }
+
+ ret = DRVR_EPALLOC(priv->drvr, &bindesc, &priv->epin);
+ if (ret != OK)
+ {
+ udbg("ERROR: Failed to allocate Bulk IN endpoint\n");
+ (void)DRVR_EPFREE(priv->drvr, priv->epout);
+ return ret;
+ }
+
+ ullvdbg("Endpoints allocated\n");
+ return OK;
+}
+
+/****************************************************************************
+ * Name: usbhost_devinit
+ *
+ * Description:
+ * The USB device has been successfully connected. This completes the
+ * initialization operations. It is first called after the
+ * configuration descriptor has been received.
+ *
+ * This function is called from the connect() method. This function always
+ * executes on the thread of the caller of connect().
+ *
+ * Input Parameters:
+ * priv - A reference to the class instance.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static inline int usbhost_devinit(FAR struct usbhost_state_s *priv)
+{
+ int ret;
+
+ /* Set aside a transfer buffer for exclusive use by the class driver */
+
+ /* Increment the reference count. This will prevent usbhost_destroy() from
+ * being called asynchronously if the device is removed.
+ */
+
+ priv->crefs++;
+ DEBUGASSERT(priv->crefs == 2);
+
+ /* Configure the device */
+
+ /* Register the driver */
+
+ if (ret == OK)
+ {
+ char devname[DEV_NAMELEN];
+
+ uvdbg("Register block driver\n");
+ usbhost_mkdevname(priv, devname);
+ // ret = register_blockdriver(devname, &g_bops, 0, priv);
+ }
+
+ /* Check if we successfully initialized. We now have to be concerned
+ * about asynchronous modification of crefs because the block
+ * driver has been registerd.
+ */
+
+ if (ret == OK)
+ {
+ usbhost_takesem(&priv->exclsem);
+ DEBUGASSERT(priv->crefs >= 2);
+
+ /* Handle a corner case where (1) open() has been called so the
+ * reference count is > 2, but the device has been disconnected.
+ * In this case, the class instance needs to persist until close()
+ * is called.
+ */
+
+ if (priv->crefs <= 2 && priv->disconnected)
+ {
+ /* We don't have to give the semaphore because it will be
+ * destroyed when usb_destroy is called.
+ */
+
+ ret = -ENODEV;
+ }
+ else
+ {
+ /* Ready for normal operation as a block device driver */
+
+ uvdbg("Successfully initialized\n");
+ priv->crefs--;
+ usbhost_givesem(&priv->exclsem);
+ }
+ }
+
+ /* Disconnect on any errors detected during volume initialization */
+
+ if (ret != OK)
+ {
+ udbg("ERROR! Aborting: %d\n", ret);
+ usbhost_destroy(priv);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: usbhost_getle16
+ *
+ * Description:
+ * Get a (possibly unaligned) 16-bit little endian value.
+ *
+ * Input Parameters:
+ * val - A pointer to the first byte of the little endian value.
+ *
+ * Returned Values:
+ * A uint16_t representing the whole 16-bit integer value
+ *
+ ****************************************************************************/
+
+static inline uint16_t usbhost_getle16(const uint8_t *val)
+{
+ return (uint16_t)val[1] << 8 | (uint16_t)val[0];
+}
+
+/****************************************************************************
+ * Name: usbhost_putle16
+ *
+ * Description:
+ * Put a (possibly unaligned) 16-bit little endian value.
+ *
+ * Input Parameters:
+ * dest - A pointer to the first byte to save the little endian value.
+ * val - The 16-bit value to be saved.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static void usbhost_putle16(uint8_t *dest, uint16_t val)
+{
+ dest[0] = val & 0xff; /* Little endian means LS byte first in byte stream */
+ dest[1] = val >> 8;
+}
+
+/****************************************************************************
+ * Name: usbhost_getle32
+ *
+ * Description:
+ * Get a (possibly unaligned) 32-bit little endian value.
+ *
+ * Input Parameters:
+ * dest - A pointer to the first byte to save the big endian value.
+ * val - The 32-bit value to be saved.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static inline uint32_t usbhost_getle32(const uint8_t *val)
+{
+ /* Little endian means LS halfword first in byte stream */
+
+ return (uint32_t)usbhost_getle16(&val[2]) << 16 | (uint32_t)usbhost_getle16(val);
+}
+
+/****************************************************************************
+ * Name: usbhost_putle32
+ *
+ * Description:
+ * Put a (possibly unaligned) 32-bit little endian value.
+ *
+ * Input Parameters:
+ * dest - A pointer to the first byte to save the little endian value.
+ * val - The 32-bit value to be saved.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static void usbhost_putle32(uint8_t *dest, uint32_t val)
+{
+ /* Little endian means LS halfword first in byte stream */
+
+ usbhost_putle16(dest, (uint16_t)(val & 0xffff));
+ usbhost_putle16(dest+2, (uint16_t)(val >> 16));
+}
+
+/****************************************************************************
+ * Name: usbhost_tdalloc
+ *
+ * Description:
+ * Allocate transfer descriptor memory.
+ *
+ * Input Parameters:
+ * priv - A reference to the class instance.
+ *
+ * Returned Values:
+ * On sucess, zero (OK) is returned. On failure, an negated errno value
+ * is returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+static inline int usbhost_tdalloc(FAR struct usbhost_state_s *priv)
+{
+ DEBUGASSERT(priv && priv->tdbuffer == NULL);
+ return DRVR_ALLOC(priv->drvr, &priv->tdbuffer, &priv->tdbuflen);
+}
+
+/****************************************************************************
+ * Name: usbhost_tdfree
+ *
+ * Description:
+ * Free transfer descriptor memory.
+ *
+ * Input Parameters:
+ * priv - A reference to the class instance.
+ *
+ * Returned Values:
+ * On sucess, zero (OK) is returned. On failure, an negated errno value
+ * is returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+static inline int usbhost_tdfree(FAR struct usbhost_state_s *priv)
+{
+ int result = OK;
+ DEBUGASSERT(priv);
+
+ if (priv->tdbuffer)
+ {
+ DEBUGASSERT(priv->drvr);
+ result = DRVR_FREE(priv->drvr, priv->tdbuffer);
+ priv->tdbuffer = NULL;
+ priv->tdbuflen = 0;
+ }
+ return result;
+}
+
+/****************************************************************************
+ * struct usbhost_registry_s methods
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbhost_create
+ *
+ * Description:
+ * This function implements the create() method of struct usbhost_registry_s.
+ * The create() method is a callback into the class implementation. It is
+ * used to (1) create a new instance of the USB host class state and to (2)
+ * bind a USB host driver "session" to the class instance. Use of this
+ * create() method will support environments where there may be multiple
+ * USB ports and multiple USB devices simultaneously connected.
+ *
+ * Input Parameters:
+ * drvr - An instance of struct usbhost_driver_s that the class
+ * implementation will "bind" to its state structure and will
+ * subsequently use to communicate with the USB host driver.
+ * id - In the case where the device supports multiple base classes,
+ * subclasses, or protocols, this specifies which to configure for.
+ *
+ * Returned Values:
+ * On success, this function will return a non-NULL instance of struct
+ * usbhost_class_s that can be used by the USB host driver to communicate
+ * with the USB host class. NULL is returned on failure; this function
+ * will fail only if the drvr input parameter is NULL or if there are
+ * insufficient resources to create another USB host class instance.
+ *
+ ****************************************************************************/
+
+static FAR struct usbhost_class_s *usbhost_create(FAR struct usbhost_driver_s *drvr,
+ FAR const struct usbhost_id_s *id)
+{
+ FAR struct usbhost_state_s *priv;
+
+ /* Allocate a USB host class instance */
+
+ priv = usbhost_allocclass();
+ if (priv)
+ {
+ /* Initialize the allocated storage class instance */
+
+ memset(priv, 0, sizeof(struct usbhost_state_s));
+
+ /* Assign a device number to this class instance */
+
+ if (usbhost_allocdevno(priv) == OK)
+ {
+ /* Initialize class method function pointers */
+
+ priv->class.connect = usbhost_connect;
+ priv->class.disconnected = usbhost_disconnected;
+
+ /* The initial reference count is 1... One reference is held by the driver */
+
+ priv->crefs = 1;
+
+ /* Initialize semphores (this works okay in the interrupt context) */
+
+ sem_init(&priv->exclsem, 0, 1);
+
+ /* Bind the driver to the storage class instance */
+
+ priv->drvr = drvr;
+
+ /* NOTE: We do not yet know the geometry of the USB mass storage device */
+
+ /* Return the instance of the USB mass storage class */
+
+ return &priv->class;
+ }
+ }
+
+ /* An error occurred. Free the allocation and return NULL on all failures */
+
+ if (priv)
+ {
+ usbhost_freeclass(priv);
+ }
+ return NULL;
+}
+
+/****************************************************************************
+ * struct usbhost_class_s methods
+ ****************************************************************************/
+/****************************************************************************
+ * Name: usbhost_connect
+ *
+ * Description:
+ * This function implements the connect() method of struct
+ * usbhost_class_s. This method is a callback into the class
+ * implementation. It is used to provide the device's configuration
+ * descriptor to the class so that the class may initialize properly
+ *
+ * Input Parameters:
+ * class - The USB host class entry previously obtained from a call to create().
+ * configdesc - A pointer to a uint8_t buffer container the configuration descripor.
+ * desclen - The length in bytes of the configuration descriptor.
+ * funcaddr - The USB address of the function containing the endpoint that EP0
+ * controls
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ****************************************************************************/
+
+static int usbhost_connect(FAR struct usbhost_class_s *class,
+ FAR const uint8_t *configdesc, int desclen,
+ uint8_t funcaddr)
+{
+ FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)class;
+ int ret;
+
+ DEBUGASSERT(priv != NULL &&
+ configdesc != NULL &&
+ desclen >= sizeof(struct usb_cfgdesc_s));
+
+ /* Parse the configuration descriptor to get the endpoints */
+
+ ret = usbhost_cfgdesc(priv, configdesc, desclen, funcaddr);
+ if (ret != OK)
+ {
+ udbg("usbhost_cfgdesc() failed: %d\n", ret);
+ }
+ else
+ {
+ /* Now configure the device and register the NuttX driver */
+
+ ret = usbhost_devinit(priv);
+ if (ret != OK)
+ {
+ udbg("usbhost_devinit() failed: %d\n", ret);
+ }
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: usbhost_disconnected
+ *
+ * Description:
+ * This function implements the disconnected() method of struct
+ * usbhost_class_s. This method is a callback into the class
+ * implementation. It is used to inform the class that the USB device has
+ * been disconnected.
+ *
+ * Input Parameters:
+ * class - The USB host class entry previously obtained from a call to
+ * create().
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value
+ * is returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function may be called from an interrupt handler.
+ *
+ ****************************************************************************/
+
+static int usbhost_disconnected(struct usbhost_class_s *class)
+{
+ FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)class;
+ irqstate_t flags;
+
+ DEBUGASSERT(priv != NULL);
+
+ /* Set an indication to any users of the mass storage device that the device
+ * is no longer available.
+ */
+
+ flags = irqsave();
+ priv->disconnected = true;
+
+ /* Now check the number of references on the class instance. If it is one,
+ * then we can free the class instance now. Otherwise, we will have to
+ * wait until the holders of the references free them by closing the
+ * block driver.
+ */
+
+ ullvdbg("crefs: %d\n", priv->crefs);
+ if (priv->crefs == 1)
+ {
+ /* Destroy the class instance. If we are executing from an interrupt
+ * handler, then defer the destruction to the worker thread.
+ * Otherwise, destroy the instance now.
+ */
+
+ if (up_interrupt_context())
+ {
+ /* Destroy the instance on the worker thread. */
+
+ uvdbg("Queuing destruction: worker %p->%p\n", priv->work.worker, usbhost_destroy);
+ DEBUGASSERT(priv->work.worker == NULL);
+ (void)work_queue(&priv->work, usbhost_destroy, priv, 0);
+ }
+ else
+ {
+ /* Do the work now */
+
+ usbhost_destroy(priv);
+ }
+ }
+
+ irqrestore(flags);
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbhost_skelinit
+ *
+ * Description:
+ * Initialize the USB storage class. This function should be called
+ * be platform-specific code in order to initialize and register support
+ * for the USB host storage class.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Values:
+ * On success this function will return zero (OK); A negated errno value
+ * will be returned on failure.
+ *
+ ****************************************************************************/
+
+int usbhost_skelinit(void)
+{
+ /* Perform any one-time initialization of the class implementation */
+
+ /* Advertise our availability to support (certain) devices */
+
+ return usbhost_registerclass(&g_skeleton);
+}
+
diff --git a/nuttx/drivers/usbhost/usbhost_skeleton.c b/nuttx/drivers/usbhost/usbhost_skeleton.c
new file mode 100644
index 000000000..ee1d78e4a
--- /dev/null
+++ b/nuttx/drivers/usbhost/usbhost_skeleton.c
@@ -0,0 +1,1038 @@
+/****************************************************************************
+ * drivers/usbhost/usbhost_skeleton.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 <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/fs.h>
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+
+#include <nuttx/usb/usb.h>
+#include <nuttx/usb/usbhost.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error "Worker thread support is required (CONFIG_SCHED_WORKQUEUE)"
+#endif
+
+/* Driver support ***********************************************************/
+/* This format is used to construct the /dev/sd[n] device driver path. It
+ * defined here so that it will be used consistently in all places.
+ */
+
+#define DEV_FORMAT "/dev/sd%c"
+#define DEV_NAMELEN 10
+
+/* Used in usbhost_connect() */
+
+#define USBHOST_IFFOUND 0x01
+#define USBHOST_BINFOUND 0x02
+#define USBHOST_BOUTFOUND 0x04
+#define USBHOST_ALLFOUND 0x07
+
+#define USBHOST_MAX_CREFS 0x7fff
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* This structure contains the internal, private state of the USB host mass
+ * storage class.
+ */
+
+struct usbhost_state_s
+{
+ /* This is the externally visible portion of the state */
+
+ struct usbhost_class_s class;
+
+ /* This is an instance of the USB host driver bound to this class instance */
+
+ struct usbhost_driver_s *drvr;
+
+ /* The remainder of the fields are provide o the mass storage class */
+
+ char sdchar; /* Character identifying the /dev/sd[n] device */
+ volatile bool disconnected; /* TRUE: Device has been disconnected */
+ int16_t crefs; /* Reference count on the driver instance */
+ sem_t exclsem; /* Used to maintain mutual exclusive access */
+ struct work_s work; /* For interacting with the worker thread */
+ FAR uint8_t *tdbuffer; /* The allocated transfer descriptor buffer */
+ size_t tdbuflen; /* Size of the allocated transfer buffer */
+ usbhost_ep_t epin; /* IN endpoint */
+ usbhost_ep_t epout; /* OUT endpoint */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* Semaphores */
+
+static void usbhost_takesem(sem_t *sem);
+#define usbhost_givesem(s) sem_post(s);
+
+/* Memory allocation services */
+
+static inline FAR struct usbhost_state_s *usbhost_allocclass(void);
+static inline void usbhost_freeclass(FAR struct usbhost_state_s *class);
+
+/* Device name management */
+
+static int usbhost_allocdevno(FAR struct usbhost_state_s *priv);
+static void usbhost_freedevno(FAR struct usbhost_state_s *priv);
+static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, char *devname);
+
+/* Worker thread actions */
+
+static void usbhost_destroy(FAR void *arg);
+static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
+ FAR const uint8_t *configdesc, int desclen,
+ uint8_t funcaddr);
+static inline int usbhost_devinit(FAR struct usbhost_state_s *priv);
+
+/* (Little Endian) Data helpers */
+
+static inline uint16_t usbhost_getle16(const uint8_t *val);
+static inline void usbhost_putle16(uint8_t *dest, uint16_t val);
+static inline uint32_t usbhost_getle32(const uint8_t *val);
+static void usbhost_putle32(uint8_t *dest, uint32_t val);
+
+/* Transfer descriptor memory management */
+
+static inline int usbhost_tdalloc(FAR struct usbhost_state_s *priv);
+static inline int usbhost_tdfree(FAR struct usbhost_state_s *priv);
+
+/* struct usbhost_registry_s methods */
+
+static struct usbhost_class_s *usbhost_create(FAR struct usbhost_driver_s *drvr,
+ FAR const struct usbhost_id_s *id);
+
+/* struct usbhost_class_s methods */
+
+static int usbhost_connect(FAR struct usbhost_class_s *class,
+ FAR const uint8_t *configdesc, int desclen,
+ uint8_t funcaddr);
+static int usbhost_disconnected(FAR struct usbhost_class_s *class);
+
+/* Driver methods -- depend upon the type of NuttX driver interface exported */
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* This structure provides the registry entry ID informatino that will be
+ * used to associate the USB host mass storage class to a connected USB
+ * device.
+ */
+
+static const const struct usbhost_id_s g_id =
+{
+ 0, /* base -- Must be one of the USB_CLASS_* definitions in usb.h */
+ 0, /* subclass -- depends on the device */
+ 0, /* proto -- depends on the device */
+ 0, /* vid */
+ 0 /* pid */
+};
+
+/* This is the USB host storage class's registry entry */
+
+static struct usbhost_registry_s g_skeleton =
+{
+ NULL, /* flink */
+ usbhost_create, /* create */
+ 1, /* nids */
+ &g_id /* id[] */
+};
+
+/* This is a bitmap that is used to allocate device names /dev/sda-z. */
+
+static uint32_t g_devinuse;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbhost_takesem
+ *
+ * Description:
+ * This is just a wrapper to handle the annoying behavior of semaphore
+ * waits that return due to the receipt of a signal.
+ *
+ ****************************************************************************/
+
+static void usbhost_takesem(sem_t *sem)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(sem) != 0)
+ {
+ /* The only case that an error should occr here is if the wait was
+ * awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
+/****************************************************************************
+ * Name: usbhost_allocclass
+ *
+ * Description:
+ * This is really part of the logic that implements the create() method
+ * of struct usbhost_registry_s. This function allocates memory for one
+ * new class instance.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Values:
+ * On success, this function will return a non-NULL instance of struct
+ * usbhost_class_s. NULL is returned on failure; this function will
+ * will fail only if there are insufficient resources to create another
+ * USB host class instance.
+ *
+ ****************************************************************************/
+
+static inline FAR struct usbhost_state_s *usbhost_allocclass(void)
+{
+ FAR struct usbhost_state_s *priv;
+
+ DEBUGASSERT(!up_interrupt_context());
+ priv = (FAR struct usbhost_state_s *)malloc(sizeof(struct usbhost_state_s));
+ uvdbg("Allocated: %p\n", priv);;
+ return priv;
+}
+
+/****************************************************************************
+ * Name: usbhost_freeclass
+ *
+ * Description:
+ * Free a class instance previously allocated by usbhost_allocclass().
+ *
+ * Input Parameters:
+ * class - A reference to the class instance to be freed.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static inline void usbhost_freeclass(FAR struct usbhost_state_s *class)
+{
+ DEBUGASSERT(class != NULL);
+
+ /* Free the class instance (calling sched_free() in case we are executing
+ * from an interrupt handler.
+ */
+
+ uvdbg("Freeing: %p\n", class);;
+ free(class);
+}
+
+/****************************************************************************
+ * Name: Device name management
+ *
+ * Description:
+ * Some tiny functions to coordinate management of device names.
+ *
+ ****************************************************************************/
+
+static int usbhost_allocdevno(FAR struct usbhost_state_s *priv)
+{
+ irqstate_t flags;
+ int devno;
+
+ flags = irqsave();
+ for (devno = 0; devno < 26; devno++)
+ {
+ uint32_t bitno = 1 << devno;
+ if ((g_devinuse & bitno) == 0)
+ {
+ g_devinuse |= bitno;
+ priv->sdchar = 'a' + devno;
+ irqrestore(flags);
+ return OK;
+ }
+ }
+
+ irqrestore(flags);
+ return -EMFILE;
+}
+
+static void usbhost_freedevno(FAR struct usbhost_state_s *priv)
+{
+ int devno = 'a' - priv->sdchar;
+
+ if (devno >= 0 && devno < 26)
+ {
+ irqstate_t flags = irqsave();
+ g_devinuse &= ~(1 << devno);
+ irqrestore(flags);
+ }
+}
+
+static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, char *devname)
+{
+ (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, priv->sdchar);
+}
+
+/****************************************************************************
+ * Name: usbhost_destroy
+ *
+ * Description:
+ * The USB device has been disconnected and the refernce count on the USB
+ * host class instance has gone to 1.. Time to destroy the USB host class
+ * instance.
+ *
+ * Input Parameters:
+ * arg - A reference to the class instance to be destroyed.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static void usbhost_destroy(FAR void *arg)
+{
+ FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)arg;
+
+ DEBUGASSERT(priv != NULL);
+ uvdbg("crefs: %d\n", priv->crefs);
+
+ /* Unregister the driver */
+
+ /* Release the device name used by this connection */
+
+ usbhost_freedevno(priv);
+
+ /* Free the endpoints */
+
+ /* Free any transfer buffers */
+
+ /* Destroy the semaphores */
+
+ /* Disconnect the USB host device */
+
+ DRVR_DISCONNECT(priv->drvr);
+
+ /* And free the class instance. Hmmm.. this may execute on the worker
+ * thread and the work structure is part of what is getting freed. That
+ * should be okay because once the work contained is removed from the
+ * queue, it should not longer be accessed by the worker thread.
+ */
+
+ usbhost_freeclass(priv);
+}
+
+/****************************************************************************
+ * Name: usbhost_cfgdesc
+ *
+ * Description:
+ * This function implements the connect() method of struct
+ * usbhost_class_s. This method is a callback into the class
+ * implementation. It is used to provide the device's configuration
+ * descriptor to the class so that the class may initialize properly
+ *
+ * Input Parameters:
+ * priv - The USB host class instance.
+ * configdesc - A pointer to a uint8_t buffer container the configuration descripor.
+ * desclen - The length in bytes of the configuration descriptor.
+ * funcaddr - The USB address of the function containing the endpoint that EP0
+ * controls
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ****************************************************************************/
+
+static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
+ FAR const uint8_t *configdesc, int desclen,
+ uint8_t funcaddr)
+{
+ FAR struct usb_cfgdesc_s *cfgdesc;
+ FAR struct usb_desc_s *desc;
+ FAR struct usbhost_epdesc_s bindesc;
+ FAR struct usbhost_epdesc_s boutdesc;
+ int remaining;
+ uint8_t found = 0;
+ int ret;
+
+ DEBUGASSERT(priv != NULL &&
+ configdesc != NULL &&
+ desclen >= sizeof(struct usb_cfgdesc_s));
+
+ /* Verify that we were passed a configuration descriptor */
+
+ cfgdesc = (FAR struct usb_cfgdesc_s *)configdesc;
+ if (cfgdesc->type != USB_DESC_TYPE_CONFIG)
+ {
+ return -EINVAL;
+ }
+
+ /* Get the total length of the configuration descriptor (little endian).
+ * It might be a good check to get the number of interfaces here too.
+ */
+
+ remaining = (int)usbhost_getle16(cfgdesc->totallen);
+
+ /* Skip to the next entry descriptor */
+
+ configdesc += cfgdesc->len;
+ remaining -= cfgdesc->len;
+
+ /* Loop where there are more dscriptors to examine */
+
+ while (remaining >= sizeof(struct usb_desc_s))
+ {
+ /* What is the next descriptor? */
+
+ desc = (FAR struct usb_desc_s *)configdesc;
+ switch (desc->type)
+ {
+ /* Interface descriptor. We really should get the number of endpoints
+ * from this descriptor too.
+ */
+
+ case USB_DESC_TYPE_INTERFACE:
+ {
+ DEBUGASSERT(remaining >= USB_SIZEOF_IFDESC);
+ if ((found & USBHOST_IFFOUND) != 0)
+ {
+ /* Oops.. more than one interface. We don't know what to do with this. */
+
+ return -ENOSYS;
+ }
+ found |= USBHOST_IFFOUND;
+ }
+ break;
+
+ /* Endpoint descriptor. We expect two bulk endpoints, an IN and an OUT */
+ case USB_DESC_TYPE_ENDPOINT:
+ {
+ FAR struct usb_epdesc_s *epdesc = (FAR struct usb_epdesc_s *)configdesc;
+ DEBUGASSERT(remaining >= USB_SIZEOF_EPDESC);
+
+ /* Check for a bulk endpoint. We only support the bulk-only
+ * protocol so I suppose anything else should really be an error.
+ */
+
+ if ((epdesc->attr & USB_EP_ATTR_XFERTYPE_MASK) == USB_EP_ATTR_XFER_BULK)
+ {
+ /* Yes.. it is a bulk endpoint. IN or OUT? */
+
+ if (USB_ISEPOUT(epdesc->addr))
+ {
+ /* It is an OUT bulk endpoint. There should be only one bulk OUT endpoint. */
+
+ if ((found & USBHOST_BOUTFOUND) != 0)
+ {
+ /* Oops.. more than one interface. We don't know what to do with this. */
+
+ return -EINVAL;
+ }
+ found |= USBHOST_BOUTFOUND;
+
+ /* Save the bulk OUT endpoint information */
+
+ boutdesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK;
+ boutdesc.in = false;
+ boutdesc.funcaddr = funcaddr;
+ boutdesc.mxpacketsize = usbhost_getle16(epdesc->mxpacketsize);
+ uvdbg("Bulk OUT EP addr:%d mxpacketsize:%d\n",
+ boutdesc.addr, boutdesc.mxpacketsize);
+ }
+ else
+ {
+ /* It is an IN bulk endpoint. There should be only one bulk IN endpoint. */
+
+ if ((found & USBHOST_BINFOUND) != 0)
+ {
+ /* Oops.. more than one interface. We don't know what to do with this. */
+
+ return -EINVAL;
+ }
+ found |= USBHOST_BINFOUND;
+
+ /* Save the bulk IN endpoint information */
+
+ bindesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK;
+ bindesc.in = 1;
+ bindesc.funcaddr = funcaddr;
+ bindesc.mxpacketsize = usbhost_getle16(epdesc->mxpacketsize);
+ uvdbg("Bulk IN EP addr:%d mxpacketsize:%d\n",
+ bindesc.addr, bindesc.mxpacketsize);
+ }
+ }
+ }
+ break;
+
+ /* Other descriptors are just ignored for now */
+
+ default:
+ break;
+ }
+
+ /* Increment the address of the next descriptor */
+
+ configdesc += desc->len;
+ remaining -= desc->len;
+ }
+
+ /* Sanity checking... did we find all of things that we need? Hmmm.. I wonder..
+ * can we work read-only or write-only if only one bulk endpoint found?
+ */
+
+ if (found != USBHOST_ALLFOUND)
+ {
+ ulldbg("ERROR: Found IF:%s BIN:%s BOUT:%s\n",
+ (found & USBHOST_IFFOUND) != 0 ? "YES" : "NO",
+ (found & USBHOST_BINFOUND) != 0 ? "YES" : "NO",
+ (found & USBHOST_BOUTFOUND) != 0 ? "YES" : "NO");
+ return -EINVAL;
+ }
+
+ /* We are good... Allocate the endpoints */
+
+ ret = DRVR_EPALLOC(priv->drvr, &boutdesc, &priv->epout);
+ if (ret != OK)
+ {
+ udbg("ERROR: Failed to allocate Bulk OUT endpoint\n");
+ return ret;
+ }
+
+ ret = DRVR_EPALLOC(priv->drvr, &bindesc, &priv->epin);
+ if (ret != OK)
+ {
+ udbg("ERROR: Failed to allocate Bulk IN endpoint\n");
+ (void)DRVR_EPFREE(priv->drvr, priv->epout);
+ return ret;
+ }
+
+ ullvdbg("Endpoints allocated\n");
+ return OK;
+}
+
+/****************************************************************************
+ * Name: usbhost_devinit
+ *
+ * Description:
+ * The USB device has been successfully connected. This completes the
+ * initialization operations. It is first called after the
+ * configuration descriptor has been received.
+ *
+ * This function is called from the connect() method. This function always
+ * executes on the thread of the caller of connect().
+ *
+ * Input Parameters:
+ * priv - A reference to the class instance.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static inline int usbhost_devinit(FAR struct usbhost_state_s *priv)
+{
+ int ret;
+
+ /* Set aside a transfer buffer for exclusive use by the class driver */
+
+ /* Increment the reference count. This will prevent usbhost_destroy() from
+ * being called asynchronously if the device is removed.
+ */
+
+ priv->crefs++;
+ DEBUGASSERT(priv->crefs == 2);
+
+ /* Configure the device */
+
+ /* Register the driver */
+
+ if (ret == OK)
+ {
+ char devname[DEV_NAMELEN];
+
+ uvdbg("Register block driver\n");
+ usbhost_mkdevname(priv, devname);
+ // ret = register_blockdriver(devname, &g_bops, 0, priv);
+ }
+
+ /* Check if we successfully initialized. We now have to be concerned
+ * about asynchronous modification of crefs because the block
+ * driver has been registerd.
+ */
+
+ if (ret == OK)
+ {
+ usbhost_takesem(&priv->exclsem);
+ DEBUGASSERT(priv->crefs >= 2);
+
+ /* Handle a corner case where (1) open() has been called so the
+ * reference count is > 2, but the device has been disconnected.
+ * In this case, the class instance needs to persist until close()
+ * is called.
+ */
+
+ if (priv->crefs <= 2 && priv->disconnected)
+ {
+ /* We don't have to give the semaphore because it will be
+ * destroyed when usb_destroy is called.
+ */
+
+ ret = -ENODEV;
+ }
+ else
+ {
+ /* Ready for normal operation as a block device driver */
+
+ uvdbg("Successfully initialized\n");
+ priv->crefs--;
+ usbhost_givesem(&priv->exclsem);
+ }
+ }
+
+ /* Disconnect on any errors detected during volume initialization */
+
+ if (ret != OK)
+ {
+ udbg("ERROR! Aborting: %d\n", ret);
+ usbhost_destroy(priv);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: usbhost_getle16
+ *
+ * Description:
+ * Get a (possibly unaligned) 16-bit little endian value.
+ *
+ * Input Parameters:
+ * val - A pointer to the first byte of the little endian value.
+ *
+ * Returned Values:
+ * A uint16_t representing the whole 16-bit integer value
+ *
+ ****************************************************************************/
+
+static inline uint16_t usbhost_getle16(const uint8_t *val)
+{
+ return (uint16_t)val[1] << 8 | (uint16_t)val[0];
+}
+
+/****************************************************************************
+ * Name: usbhost_putle16
+ *
+ * Description:
+ * Put a (possibly unaligned) 16-bit little endian value.
+ *
+ * Input Parameters:
+ * dest - A pointer to the first byte to save the little endian value.
+ * val - The 16-bit value to be saved.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static void usbhost_putle16(uint8_t *dest, uint16_t val)
+{
+ dest[0] = val & 0xff; /* Little endian means LS byte first in byte stream */
+ dest[1] = val >> 8;
+}
+
+/****************************************************************************
+ * Name: usbhost_getle32
+ *
+ * Description:
+ * Get a (possibly unaligned) 32-bit little endian value.
+ *
+ * Input Parameters:
+ * dest - A pointer to the first byte to save the big endian value.
+ * val - The 32-bit value to be saved.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static inline uint32_t usbhost_getle32(const uint8_t *val)
+{
+ /* Little endian means LS halfword first in byte stream */
+
+ return (uint32_t)usbhost_getle16(&val[2]) << 16 | (uint32_t)usbhost_getle16(val);
+}
+
+/****************************************************************************
+ * Name: usbhost_putle32
+ *
+ * Description:
+ * Put a (possibly unaligned) 32-bit little endian value.
+ *
+ * Input Parameters:
+ * dest - A pointer to the first byte to save the little endian value.
+ * val - The 32-bit value to be saved.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static void usbhost_putle32(uint8_t *dest, uint32_t val)
+{
+ /* Little endian means LS halfword first in byte stream */
+
+ usbhost_putle16(dest, (uint16_t)(val & 0xffff));
+ usbhost_putle16(dest+2, (uint16_t)(val >> 16));
+}
+
+/****************************************************************************
+ * Name: usbhost_tdalloc
+ *
+ * Description:
+ * Allocate transfer descriptor memory.
+ *
+ * Input Parameters:
+ * priv - A reference to the class instance.
+ *
+ * Returned Values:
+ * On sucess, zero (OK) is returned. On failure, an negated errno value
+ * is returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+static inline int usbhost_tdalloc(FAR struct usbhost_state_s *priv)
+{
+ DEBUGASSERT(priv && priv->tdbuffer == NULL);
+ return DRVR_ALLOC(priv->drvr, &priv->tdbuffer, &priv->tdbuflen);
+}
+
+/****************************************************************************
+ * Name: usbhost_tdfree
+ *
+ * Description:
+ * Free transfer descriptor memory.
+ *
+ * Input Parameters:
+ * priv - A reference to the class instance.
+ *
+ * Returned Values:
+ * On sucess, zero (OK) is returned. On failure, an negated errno value
+ * is returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+static inline int usbhost_tdfree(FAR struct usbhost_state_s *priv)
+{
+ int result = OK;
+ DEBUGASSERT(priv);
+
+ if (priv->tdbuffer)
+ {
+ DEBUGASSERT(priv->drvr);
+ result = DRVR_FREE(priv->drvr, priv->tdbuffer);
+ priv->tdbuffer = NULL;
+ priv->tdbuflen = 0;
+ }
+ return result;
+}
+
+/****************************************************************************
+ * struct usbhost_registry_s methods
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbhost_create
+ *
+ * Description:
+ * This function implements the create() method of struct usbhost_registry_s.
+ * The create() method is a callback into the class implementation. It is
+ * used to (1) create a new instance of the USB host class state and to (2)
+ * bind a USB host driver "session" to the class instance. Use of this
+ * create() method will support environments where there may be multiple
+ * USB ports and multiple USB devices simultaneously connected.
+ *
+ * Input Parameters:
+ * drvr - An instance of struct usbhost_driver_s that the class
+ * implementation will "bind" to its state structure and will
+ * subsequently use to communicate with the USB host driver.
+ * id - In the case where the device supports multiple base classes,
+ * subclasses, or protocols, this specifies which to configure for.
+ *
+ * Returned Values:
+ * On success, this function will return a non-NULL instance of struct
+ * usbhost_class_s that can be used by the USB host driver to communicate
+ * with the USB host class. NULL is returned on failure; this function
+ * will fail only if the drvr input parameter is NULL or if there are
+ * insufficient resources to create another USB host class instance.
+ *
+ ****************************************************************************/
+
+static FAR struct usbhost_class_s *usbhost_create(FAR struct usbhost_driver_s *drvr,
+ FAR const struct usbhost_id_s *id)
+{
+ FAR struct usbhost_state_s *priv;
+
+ /* Allocate a USB host class instance */
+
+ priv = usbhost_allocclass();
+ if (priv)
+ {
+ /* Initialize the allocated storage class instance */
+
+ memset(priv, 0, sizeof(struct usbhost_state_s));
+
+ /* Assign a device number to this class instance */
+
+ if (usbhost_allocdevno(priv) == OK)
+ {
+ /* Initialize class method function pointers */
+
+ priv->class.connect = usbhost_connect;
+ priv->class.disconnected = usbhost_disconnected;
+
+ /* The initial reference count is 1... One reference is held by the driver */
+
+ priv->crefs = 1;
+
+ /* Initialize semphores (this works okay in the interrupt context) */
+
+ sem_init(&priv->exclsem, 0, 1);
+
+ /* Bind the driver to the storage class instance */
+
+ priv->drvr = drvr;
+
+ /* NOTE: We do not yet know the geometry of the USB mass storage device */
+
+ /* Return the instance of the USB mass storage class */
+
+ return &priv->class;
+ }
+ }
+
+ /* An error occurred. Free the allocation and return NULL on all failures */
+
+ if (priv)
+ {
+ usbhost_freeclass(priv);
+ }
+ return NULL;
+}
+
+/****************************************************************************
+ * struct usbhost_class_s methods
+ ****************************************************************************/
+/****************************************************************************
+ * Name: usbhost_connect
+ *
+ * Description:
+ * This function implements the connect() method of struct
+ * usbhost_class_s. This method is a callback into the class
+ * implementation. It is used to provide the device's configuration
+ * descriptor to the class so that the class may initialize properly
+ *
+ * Input Parameters:
+ * class - The USB host class entry previously obtained from a call to create().
+ * configdesc - A pointer to a uint8_t buffer container the configuration descripor.
+ * desclen - The length in bytes of the configuration descriptor.
+ * funcaddr - The USB address of the function containing the endpoint that EP0
+ * controls
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ****************************************************************************/
+
+static int usbhost_connect(FAR struct usbhost_class_s *class,
+ FAR const uint8_t *configdesc, int desclen,
+ uint8_t funcaddr)
+{
+ FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)class;
+ int ret;
+
+ DEBUGASSERT(priv != NULL &&
+ configdesc != NULL &&
+ desclen >= sizeof(struct usb_cfgdesc_s));
+
+ /* Parse the configuration descriptor to get the endpoints */
+
+ ret = usbhost_cfgdesc(priv, configdesc, desclen, funcaddr);
+ if (ret != OK)
+ {
+ udbg("usbhost_cfgdesc() failed: %d\n", ret);
+ }
+ else
+ {
+ /* Now configure the device and register the NuttX driver */
+
+ ret = usbhost_devinit(priv);
+ if (ret != OK)
+ {
+ udbg("usbhost_devinit() failed: %d\n", ret);
+ }
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: usbhost_disconnected
+ *
+ * Description:
+ * This function implements the disconnected() method of struct
+ * usbhost_class_s. This method is a callback into the class
+ * implementation. It is used to inform the class that the USB device has
+ * been disconnected.
+ *
+ * Input Parameters:
+ * class - The USB host class entry previously obtained from a call to
+ * create().
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value
+ * is returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function may be called from an interrupt handler.
+ *
+ ****************************************************************************/
+
+static int usbhost_disconnected(struct usbhost_class_s *class)
+{
+ FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)class;
+ irqstate_t flags;
+
+ DEBUGASSERT(priv != NULL);
+
+ /* Set an indication to any users of the mass storage device that the device
+ * is no longer available.
+ */
+
+ flags = irqsave();
+ priv->disconnected = true;
+
+ /* Now check the number of references on the class instance. If it is one,
+ * then we can free the class instance now. Otherwise, we will have to
+ * wait until the holders of the references free them by closing the
+ * block driver.
+ */
+
+ ullvdbg("crefs: %d\n", priv->crefs);
+ if (priv->crefs == 1)
+ {
+ /* Destroy the class instance. If we are executing from an interrupt
+ * handler, then defer the destruction to the worker thread.
+ * Otherwise, destroy the instance now.
+ */
+
+ if (up_interrupt_context())
+ {
+ /* Destroy the instance on the worker thread. */
+
+ uvdbg("Queuing destruction: worker %p->%p\n", priv->work.worker, usbhost_destroy);
+ DEBUGASSERT(priv->work.worker == NULL);
+ (void)work_queue(&priv->work, usbhost_destroy, priv, 0);
+ }
+ else
+ {
+ /* Do the work now */
+
+ usbhost_destroy(priv);
+ }
+ }
+
+ irqrestore(flags);
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbhost_skelinit
+ *
+ * Description:
+ * Initialize the USB storage class. This function should be called
+ * be platform-specific code in order to initialize and register support
+ * for the USB host storage class.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Values:
+ * On success this function will return zero (OK); A negated errno value
+ * will be returned on failure.
+ *
+ ****************************************************************************/
+
+int usbhost_skelinit(void)
+{
+ /* Perform any one-time initialization of the class implementation */
+
+ /* Advertise our availability to support (certain) devices */
+
+ return usbhost_registerclass(&g_skeleton);
+}
+
diff --git a/nuttx/include/nuttx/usb/hid.h b/nuttx/include/nuttx/usb/hid.h
new file mode 100755
index 000000000..9fcf2b3ee
--- /dev/null
+++ b/nuttx/include/nuttx/usb/hid.h
@@ -0,0 +1,190 @@
+/****************************************************************************
+ * include/nuttx/usb/hid.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * References:
+ * Universal Serial Bus (USB), Device Class Definition for Human Interface
+ * Devices (HID), Firmware Specification—6/27/01, Version 1.11.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_NUTTX_USB_HID_H
+#define __INCLUDE_NUTTX_USB_HID_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Preprocessor definitions
+ ****************************************************************************/
+
+/* Subclass and Protocol ****************************************************/
+/* Subclass codes (4.2) */
+
+#define USBHID_SUBCLASS_NONE 0 /* No subclass */
+#define USBHID_SUBCLASS_BOOTIF 1 /* Boot Interface Subclass */
+
+/* A variety of protocols are supported HID devices. The protocol member of
+ * an Interface descriptor only has meaning if the subclass member declares
+ * that the device supports a boot interface, otherwise it is 0. (4.3)
+ */
+
+#define USBHID_PROTOCOL_NONE 0
+#define USBHID_PROTOCOL_KEYBOARD 1
+#define USBHID_PROTOCOL_MOUSE 2
+
+/* HID Descriptor ***********************************************************/
+
+#define USBHID_COUNTRY_NONE 0x00 /* Not Supported */
+#define USBHID_COUNTRY_ARABIC 0x01 /* Arabic */
+#define USBHID_COUNTRY_BELGIAN 0x02 /* Belgian */
+#define USBHID_COUNTRY_CANADA 0x03 /* Canadian-Bilingual */
+#define USBHID_COUNTRY_CANADRFR 0x04 /* Canadian-French */
+#define USBHID_COUNTRY_CZECH 0x05 /* Czech Republic */
+#define USBHID_COUNTRY_DANISH 0x06 /* Danish */
+#define USBHID_COUNTRY_FINNISH 0x07 /* Finnish */
+#define USBHID_COUNTRY_FRENCH 0x08 /* French */
+#define USBHID_COUNTRY_GERMAN 0x09 /* German */
+#define USBHID_COUNTRY_GREEK 0x10 /* Greek */
+#define USBHID_COUNTRY_HEBREW 0x11 /* Hebrew */
+#define USBHID_COUNTRY_HUNGARY 0x12 /* Hungary */
+#define USBHID_COUNTRY_ISO 0x13 /* International (ISO) */
+#define USBHID_COUNTRY_ITALIAN 0x14 /* Italian */
+#define USBHID_COUNTRY_JAPAN 0x15 /* Japan (Katakana) */
+#define USBHID_COUNTRY_KOREAN 0x16 /* Korean */
+#define USBHID_COUNTRY_LATINAM 0x17 /* Latin American */
+#define USBHID_COUNTRY_DUTCH 0x18 /* Netherlands/Dutch */
+#define USBHID_COUNTRY_NORWEGIAN 0x19 /* Norwegian */
+#define USBHID_COUNTRY_PERSIAN 0x20 /* Persian (Farsi) */
+#define USBHID_COUNTRY_POLAND 0x21 /* Poland */
+#define USBHID_COUNTRY_PORTUGUESE 0x22 /* Portuguese */
+#define USBHID_COUNTRY_RUSSIA 0x23 /* Russia */
+#define USBHID_COUNTRY_SLOVAKIA 0x24 /* Slovakia */
+#define USBHID_COUNTRY_SPANISH 0x25 /* Spanish */
+#define USBHID_COUNTRY_SWEDISH 0x26 /* Swedish */
+#define USBHID_COUNTRY_SWISSFR 0x27 /* Swiss/French */
+#define USBHID_COUNTRY_SWISSGR 0x28 /* Swiss/German */
+#define USBHID_COUNTRY_SWITZERLAND 0x29 /* Switzerland */
+#define USBHID_COUNTRY_TAIWAN 0x30 /* Taiwan */
+#define USBHID_COUNTRY_TURKISHQ 0x31 /* Turkish-Q */
+#define USBHID_COUNTRY_UK 0x32 /* UK */
+#define USBHID_COUNTRY_US 0x33 /* US */
+#define USBHID_COUNTRY_YUGOSLAVIA 0x34 /* Yugoslavia */
+#define USBHID_COUNTRY_TURKISHF 0x35 /* Turkish-F */
+
+/* Main Items (6.2.2.4) */
+
+#define USBHID_MAIN_SIZE(pfx) ((pfx) & 3)
+#define USBHID_MAIN_INPUT_PREFIX 0x80
+#define USBHID_MAIN_INPUT_CONSTANT (1 << 0) /* Constant(1) vs Data(0) */
+#define USBHID_MAIN_INPUT_VARIABLE (1 << 1) /* Variable(1) vs Array(0) */
+#define USBHID_MAIN_INPUT_RELATIVE (1 << 2) /* Relative(1) vs Absolute(0) */
+#define USBHID_MAIN_INPUT_WRAP (1 << 3) /* Wrap(1) vs No Wrap(0) */
+#define USBHID_MAIN_INPUT_NONLINEAR (1 << 4) /* Non Linear(1) vs Linear(0) */
+#define USBHID_MAIN_INPUT_NOPREFERRED (1 << 5) /* No Preferred (1) vs Preferred State(0) */
+#define USBHID_MAIN_INPUT_NULLSTATE (1 << 6) /* Null state(1) vs No Null position(0) */
+#define USBHID_MAIN_INPUT_BUFFEREDBYTES (1 << 8) /* Buffered Bytes(1) vs Bit Field(0) */
+
+#define USBHID_MAIN_OUTPUT_PREFIX 0x90
+#define USBHID_MAIN_OUTPUT_CONSTANT (1 << 0) /* Constant(1) vs Data(0) */
+#define USBHID_MAIN_OUTPUT_VARIABLE (1 << 1) /* Variable(1) vs Array(0) */
+#define USBHID_MAIN_OUTPUT_RELATIVE (1 << 2) /* Relative(1) vs Absolute(0) */
+#define USBHID_MAIN_OUTPUT_WRAP (1 << 3) /* Wrap(1) vs No Wrap(0) */
+#define USBHID_MAIN_OUTPUT_NONLINEAR (1 << 4) /* Non Linear(1) vs Linear(0) */
+#define USBHID_MAIN_OUTPUT_NOPREFERRED (1 << 5) /* No Preferred (1) vs Preferred State(0) */
+#define USBHID_MAIN_OUTPUT_NULLSTATE (1 << 6) /* Null state(1) vs No Null position(0) */
+#define USBHID_MAIN_OUTPUT_VOLATILE (1 << 7) /* Volatile(1) vs Non volatile(0) */
+#define USBHID_MAIN_OUTPUT_BUFFEREDBYTES (1 << 8) /* Buffered Bytes(1) vs Bit Field(0) */
+
+#define USBHID_MAIN_FEATURE_PREFIX 0xb0
+#define USBHID_MAIN_FEATURE_CONSTANT (1 << 0) /* Constant(1) vs Data(0) */
+#define USBHID_MAIN_FEATURE_VARIABLE (1 << 1) /* Variable(1) vs Array(0) */
+#define USBHID_MAIN_FEATURE_RELATIVE (1 << 2) /* Relative(1) vs Absolute(0) */
+#define USBHID_MAIN_FEATURE_WRAP (1 << 3) /* Wrap(1) vs No Wrap(0) */
+#define USBHID_MAIN_FEATURE_NONLINEAR (1 << 4) /* Non Linear(1) vs Linear(0) */
+#define USBHID_MAIN_FEATURE_NOPREFERRED (1 << 5) /* No Preferred (1) vs Preferred State(0) */
+#define USBHID_MAIN_FEATURE_NULLSTATE (1 << 6) /* Null state(1) vs No Null position(0) */
+#define USBHID_MAIN_FEATURE_VOLATILE (1 << 7) /* Volatile(1) vs Non volatile(0) */
+#define USBHID_MAIN_FEATURE_BUFFEREDBYTES (1 << 8) /* Buffered Bytes(1) vs Bit Field(0) */
+
+#define USBHID_MAIN_COLLECTION_PREFIX 0xa0
+#define USBHID_MAIN_COLLECTION_PHYSICAL 0x00 /* Physical (group of axes) */
+#define USBHID_MAIN_COLLECTION_APPL 0x01 /* Application (mouse, keyboard) */
+#define USBHID_MAIN_COLLECTION_LOGICAL 0x02 /* Logical (interrelated data) */
+#define USBHID_MAIN_COLLECTION_REPORT 0x03 /* Report */
+#define USBHID_MAIN_COLLECTION_ARRAY 0x04 /* Named Array */
+#define USBHID_MAIN_COLLECTION_SWITCH 0x05 /* Usage Switch */
+#define USBHID_MAIN_COLLECTION_MODIFIER 0x06 /* Usage Modifier */
+
+#define USBHID_MAIN_ENDCOLLECTION_PREFIX 0xc0
+
+/* Global Items (6.2.2.7) */
+
+#define USBHID_GLOBAL_SIZE(pfx) ((pfx) & 3)
+#define USBHID_GLOBAL_USAGEPAGE_PREFIX 0x04 /* Usage Page */
+#define USBHID_GLOBAL_LOGMINIMUM_PREFIX 0x14 /* Logical Minimum */
+#define USBHID_GLOBAL_LOGMAXIMUM_PREFIX 0x24 /* Logical Maximum */
+#define USBHID_GLOBAL_PHYSMINIMUM_PREFIX 0x34 /* Physical Minimum */
+#define USBHID_GLOBAL_PHYSMAXIMUM_PREFIX 0x44 /* Physical Maximum */
+#define USBHID_GLOBAL_UNITEXP_PREFIX 0x54 /* Unit Exponent */
+#define USBHID_GLOBAL_UNIT_PREFIX 0x64 /* Unit */
+#define USBHID_GLOBAL_REPORTSIZE_PREFIX 0x74 /* Report Size */
+#define USBHID_GLOBAL_REPORTID_PREFIX 0x84 /*Report ID */
+#define USBHID_GLOBAL_REPORTCOUNT_PREFIX 0x94 /* Report Count */
+#define USBHID_GLOBAL_PUSH_PREFIX 0xa4 /* Push */
+#define USBHID_GLOBAL_Pop_PREFIX 0xb4 /* Pop */
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+# define EXTERN extern "C"
+extern "C" {
+#else
+# define EXTERN extern
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_USB_HID_H */