summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-08-11 17:11:32 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-08-11 17:11:32 -0600
commit861253baf26635b4bc6f8092bbddaaebbabc09dd (patch)
tree969b6f71c51570630ce385df30d5989adb284093 /nuttx/drivers
parent90d17e48b58e3fbffbe8b4d6b2476ba8bf23797d (diff)
downloadpx4-nuttx-861253baf26635b4bc6f8092bbddaaebbabc09dd.tar.gz
px4-nuttx-861253baf26635b4bc6f8092bbddaaebbabc09dd.tar.bz2
px4-nuttx-861253baf26635b4bc6f8092bbddaaebbabc09dd.zip
Add untested OHCI driver for the SAMA5; structure naming and header files for USB host initialization prototypes
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/usbhost/usbhost_hidkbd.c55
-rw-r--r--nuttx/drivers/usbhost/usbhost_storage.c52
2 files changed, 64 insertions, 43 deletions
diff --git a/nuttx/drivers/usbhost/usbhost_hidkbd.c b/nuttx/drivers/usbhost/usbhost_hidkbd.c
index 403befd49..1710a2bb8 100644
--- a/nuttx/drivers/usbhost/usbhost_hidkbd.c
+++ b/nuttx/drivers/usbhost/usbhost_hidkbd.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/usbhost/usbhost_hidkbd.c
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -120,7 +120,7 @@
/* The default is to support scancode mapping for the standard 104 key
* keyboard. Setting CONFIG_HIDKBD_RAWSCANCODES will disable all scancode
* mapping; Setting CONFIG_HIDKBD_ALLSCANCODES will enable mapping of all
- * scancodes;
+ * scancodes;
*/
#ifndef CONFIG_HIDKBD_RAWSCANCODES
@@ -201,7 +201,7 @@ struct usbhost_state_s
struct usbhost_driver_s *drvr;
/* The remainder of the fields are provide o the keyboard class driver */
-
+
char devchar; /* Character identifying the /dev/kbd[n] device */
volatile bool disconnected; /* TRUE: Device has been disconnected */
volatile bool polling; /* TRUE: Poll thread is running */
@@ -321,7 +321,7 @@ 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);
@@ -349,7 +349,7 @@ static int usbhost_poll(FAR struct file *filep, FAR struct pollfd *fds,
* Private Data
****************************************************************************/
-/* This structure provides the registry entry ID informatino that will be
+/* This structure provides the registry entry ID informatino that will be
* used to associate the USB host keyboard class driver to a connected USB
* device.
*/
@@ -763,7 +763,7 @@ static void usbhost_destroy(FAR void *arg)
DEBUGASSERT(priv != NULL);
uvdbg("crefs: %d\n", priv->crefs);
-
+
/* Unregister the driver */
uvdbg("Unregister driver\n");
@@ -1026,12 +1026,12 @@ static int usbhost_kbdpoll(int argc, char *argv[])
priv = g_priv;
DEBUGASSERT(priv != NULL);
-
+
priv->polling = true;
priv->crefs++;
usbhost_givesem(&g_syncsem);
sleep(1);
-
+
/* Loop here until the device is disconnected */
uvdbg("Entering poll loop\n");
@@ -1149,7 +1149,7 @@ static int usbhost_kbdpoll(int argc, char *argv[])
{
keycode &= 0x1f;
}
-
+
/* Copy the next keyboard character into the user
* buffer.
*/
@@ -1242,13 +1242,13 @@ static int usbhost_kbdpoll(int argc, char *argv[])
* we can destroy it now. Otherwise, we have to wait until the all
* of the file descriptors are closed.
*/
-
+
udbg("Keyboard removed, polling halted\n");
priv->polling = false;
if (--priv->crefs < 2)
{
/* Destroy the instance (while we hold the semaphore!) */
-
+
usbhost_destroy(priv);
}
else
@@ -1299,10 +1299,15 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
bool done = false;
int ret;
- DEBUGASSERT(priv != NULL &&
+ DEBUGASSERT(priv != NULL &&
configdesc != NULL &&
desclen >= sizeof(struct usb_cfgdesc_s));
-
+
+ /* Keep the compiler from complaining about uninitialized variables */
+
+ memset(&epindesc, 0, sizeof(struct usbhost_epdesc_s));
+ memset(&epoutdesc, 0, sizeof(struct usbhost_epdesc_s));
+
/* Verify that we were passed a configuration descriptor */
cfgdesc = (FAR struct usb_cfgdesc_s *)configdesc;
@@ -1338,7 +1343,7 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
case USB_DESC_TYPE_INTERFACE:
{
FAR struct usb_ifdesc_s *ifdesc = (FAR struct usb_ifdesc_s *)configdesc;
-
+
uvdbg("Interface descriptor\n");
DEBUGASSERT(remaining >= USB_SIZEOF_IFDESC);
@@ -1429,7 +1434,7 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
found |= USBHOST_EPINFOUND;
/* Save the interrupt IN endpoint information */
-
+
epindesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK;
epindesc.in = 1;
epindesc.funcaddr = funcaddr;
@@ -1460,13 +1465,13 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
}
/* Increment the address of the next descriptor */
-
+
configdesc += desc->len;
remaining -= desc->len;
}
/* Sanity checking... did we find all of things that we need? */
-
+
if ((found & USBHOST_RQDFOUND) != USBHOST_RQDFOUND)
{
ulldbg("ERROR: Found IF:%s EPIN:%s\n",
@@ -1752,7 +1757,7 @@ static inline int usbhost_tdfree(FAR struct usbhost_state_s *priv)
* Name: usbhost_create
*
* Description:
- * This function implements the create() method of struct usbhost_registry_s.
+ * 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
@@ -1812,7 +1817,7 @@ static FAR struct usbhost_class_s *usbhost_create(FAR struct usbhost_driver_s *d
priv->drvr = drvr;
/* Return the instance of the USB keyboard class driver */
-
+
return &priv->class;
}
}
@@ -1867,7 +1872,7 @@ static int usbhost_connect(FAR struct usbhost_class_s *class,
FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)class;
int ret;
- DEBUGASSERT(priv != NULL &&
+ DEBUGASSERT(priv != NULL &&
configdesc != NULL &&
desclen >= sizeof(struct usb_cfgdesc_s));
@@ -1888,7 +1893,7 @@ static int usbhost_connect(FAR struct usbhost_class_s *class,
udbg("usbhost_devinit() failed: %d\n", ret);
}
}
-
+
/* ERROR handling: Do nothing. If we return and error during connection,
* the driver is required to call the DISCONNECT method. Possibilities:
*
@@ -1958,7 +1963,7 @@ static int usbhost_disconnected(struct usbhost_class_s *class)
if (priv->polling)
{
- /* The polling task is still alive. Signal the keyboard polling task.
+ /* The polling task is still alive. Signal the keyboard polling task.
* When that task wakes up, it will decrement the reference count and,
* perhaps, destroy the class instance. Then it will exit.
*/
@@ -2064,7 +2069,7 @@ static int usbhost_close(FAR struct file *filep)
/* Is this the last reference (other than the one held by the USB host
* controller driver)
*/
-
+
if (priv->crefs <= 1)
{
irqstate_t flags;
@@ -2098,7 +2103,7 @@ static int usbhost_close(FAR struct file *filep)
}
irqrestore(flags);
}
-
+
usbhost_givesem(&priv->exclsem);
return OK;
}
@@ -2177,7 +2182,7 @@ static ssize_t usbhost_read(FAR struct file *filep, FAR char *buffer, size_t len
}
/* Read data from our internal buffer of received characters */
-
+
for (tail = priv->tailndx, nbytes = 0;
tail != priv->headndx && nbytes < len;
nbytes++)
diff --git a/nuttx/drivers/usbhost/usbhost_storage.c b/nuttx/drivers/usbhost/usbhost_storage.c
index cb6af46b8..89ec6238f 100644
--- a/nuttx/drivers/usbhost/usbhost_storage.c
+++ b/nuttx/drivers/usbhost/usbhost_storage.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/usbhost/usbhost_storage.c
*
- * Copyright (C) 2010-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -139,6 +139,13 @@ struct usbhost_state_s
usbhost_ep_t bulkout; /* Bulk OUT endpoint */
};
+/* This is how struct usbhost_state_s looks to the free list logic */
+
+struct usbhost_freestate_s
+{
+ FAR struct usbhost_freestate_s *flink;
+};
+
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
@@ -300,7 +307,7 @@ static struct usbhost_state_s g_prealloc[CONFIG_USBHOST_NPREALLOC];
/* This is a list of free, pre-allocated USB host storage class instances */
#if CONFIG_USBHOST_NPREALLOC > 0
-static struct usbhost_state_s *g_freelist;
+static FAR struct usbhost_freestate_s *g_freelist;
#endif
/* This is a bitmap that is used to allocate device names /dev/sda-z. */
@@ -356,7 +363,7 @@ static void usbhost_takesem(sem_t *sem)
#if CONFIG_USBHOST_NPREALLOC > 0
static inline FAR struct usbhost_state_s *usbhost_allocclass(void)
{
- struct usbhost_state_s *priv;
+ FAR struct usbhost_freestate_s *entry;
irqstate_t flags;
/* We may be executing from an interrupt handler so we need to take one of
@@ -364,15 +371,15 @@ static inline FAR struct usbhost_state_s *usbhost_allocclass(void)
*/
flags = irqsave();
- priv = g_freelist;
- if (priv)
+ entry = g_freelist;
+ if (entry)
{
- g_freelist = priv->class.flink;
- priv->class.flink = NULL;
+ g_freelist = entry->flink;
}
+
irqrestore(flags);
- ullvdbg("Allocated: %p\n", priv);;
- return priv;
+ ullvdbg("Allocated: %p\n", entry);;
+ return (FAR struct usbhost_state_s *)entry;
}
#else
static inline FAR struct usbhost_state_s *usbhost_allocclass(void)
@@ -407,16 +414,17 @@ static inline FAR struct usbhost_state_s *usbhost_allocclass(void)
#if CONFIG_USBHOST_NPREALLOC > 0
static inline void usbhost_freeclass(FAR struct usbhost_state_s *class)
{
+ FAR struct usbhost_freestate_s *entry = (FAR struct usbhost_freestate_s *)class;
irqstate_t flags;
- DEBUGASSERT(class != NULL);
+ DEBUGASSERT(entry != NULL);
- ullvdbg("Freeing: %p\n", class);;
+ ullvdbg("Freeing: %p\n", entry);
/* Just put the pre-allocated class structure back on the freelist */
flags = irqsave();
- class->class.flink = g_freelist;
- g_freelist = class;
+ entry->flink = g_freelist;
+ g_freelist = entry;
irqrestore(flags);
}
#else
@@ -821,7 +829,6 @@ static inline int usbhost_readcapacity(FAR struct usbhost_state_s *priv)
static inline int usbhost_inquiry(FAR struct usbhost_state_s *priv)
{
FAR struct usbmsc_cbw_s *cbw;
- FAR struct scsiresp_inquiry_s *resp;
int result;
/* Initialize a CBW (re-using the allocated transfer buffer) */
@@ -846,9 +853,12 @@ static inline int usbhost_inquiry(FAR struct usbhost_state_s *priv)
priv->tbuffer, SCSIRESP_INQUIRY_SIZEOF);
if (result == OK)
{
- /* TODO: If USB debug is enabled, dump the response data here */
+#if 0
+ FAR struct scsiresp_inquiry_s *resp;
+ /* TODO: If USB debug is enabled, dump the response data here */
resp = (FAR struct scsiresp_inquiry_s *)priv->tbuffer;
+#endif
/* Receive the CSW */
@@ -971,6 +981,11 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
configdesc != NULL &&
desclen >= sizeof(struct usb_cfgdesc_s));
+ /* Keep the compiler from complaining about uninitialized variables */
+
+ memset(&bindesc, 0, sizeof(struct usbhost_epdesc_s));
+ memset(&boutdesc, 0, sizeof(struct usbhost_epdesc_s));
+
/* Verify that we were passed a configuration descriptor */
cfgdesc = (FAR struct usb_cfgdesc_s *)configdesc;
@@ -2225,14 +2240,15 @@ int usbhost_storageinit(void)
*/
#if CONFIG_USBHOST_NPREALLOC > 0
+ FAR struct usbhost_freestate_s *entry;
int i;
g_freelist = NULL;
for (i = 0; i < CONFIG_USBHOST_NPREALLOC; i++)
{
- struct usbhost_state_s *class = &g_prealloc[i];
- class->class.flink = g_freelist;
- g_freelist = class;
+ entry = (FAR struct usbhost_freestate_s *)&g_prealloc[i];
+ entry->flink = g_freelist;
+ g_freelist = entry;
}
#endif