summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c17
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/up_nsh.c155
-rw-r--r--nuttx/include/nuttx/usb/usbhost.h12
3 files changed, 167 insertions, 17 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
index c8be22fad..2f162556d 100755
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
@@ -250,7 +250,7 @@ static int lpc17_usbinterrupt(int irq, FAR void *context);
/* USB host controller operations **********************************************/
-static int lpc17_wait(FAR struct usbhost_driver_s *drvr);
+static int lpc17_wait(FAR struct usbhost_driver_s *drvr, bool connected);
static int lpc17_enumerate(FAR struct usbhost_driver_s *drvr);
static int lpc17_alloc(FAR struct usbhost_driver_s *drvr,
FAR uint8_t **buffer, FAR size_t *maxlen);
@@ -892,6 +892,7 @@ static int lpc17_usbinterrupt(int irq, FAR void *context)
CLASS_DISCONNECTED(priv->class);
}
+ lpc17_givesem(&priv->rhssem);
}
else
{
@@ -944,11 +945,13 @@ static int lpc17_usbinterrupt(int irq, FAR void *context)
* Name: lpc17_wait
*
* Description:
- * Wait for a device to be connected.
+ * Wait for a device to be connected or disconneced.
*
* Input Parameters:
* drvr - The USB host driver instance obtained as a parameter from the call to
* the class create() method.
+ * connected - TRUE: Wait for device to be connected; FALSE: wait for device
+ * to be disconnected
*
* Returned Values:
* Zero (OK) is returned when a device in connected. This function will not
@@ -962,15 +965,15 @@ static int lpc17_usbinterrupt(int irq, FAR void *context)
*
*******************************************************************************/
-static int lpc17_wait(FAR struct usbhost_driver_s *drvr)
+static int lpc17_wait(FAR struct usbhost_driver_s *drvr, bool connected)
{
struct lpc17_usbhost_s *priv = (struct lpc17_usbhost_s *)drvr;
/* Are we already connected? */
- while (!priv->connected)
+ while (priv->connected == connected)
{
- /* No, wait for the connection */
+ /* No, wait for the connection/disconnection */
lpc17_takesem(&priv->rhssem);
}
@@ -1534,7 +1537,7 @@ static void lpc17_hccainit(volatile struct lpc17_hcca_s *hcca)
*******************************************************************************/
/*******************************************************************************
- * Name: up_usbhostinitialize
+ * Name: usbhost_initialize
*
* Description:
* Initialize USB host device controller hardware.
@@ -1558,7 +1561,7 @@ static void lpc17_hccainit(volatile struct lpc17_hcca_s *hcca)
*
*******************************************************************************/
-FAR struct usbhost_driver_s *up_usbhostinitialize(int controller)
+FAR struct usbhost_driver_s *usbhost_initialize(int controller)
{
struct lpc17_usbhost_s *priv = &g_usbhost;
uint32_t regval;
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
index 26eb3158d..2d7e2753e 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
@@ -46,6 +46,7 @@
#include <nuttx/spi.h>
#include <nuttx/mmcsd.h>
+#include <nuttx/usb/usbhost.h>
#include "lpc17_internal.h"
#include "lpc1766stk_internal.h"
@@ -60,6 +61,7 @@
#ifdef CONFIG_ARCH_BOARD_LPC1766STK
# define CONFIG_EXAMPLES_NSH_HAVEMMCSD 1
+# define CONFIG_EXAMPLES_NSH_HAVEUSBHOST 1
# if !defined(CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO) || CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO != 1
# error "The LPC1766-STK MMC/SD is on SSP1"
# undef CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO
@@ -72,10 +74,12 @@
# endif
# ifndef CONFIG_LPC17_SSP1
# warning "CONFIG_LPC17_SSP1 is not enabled"
+# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
# endif
#else
# error "Unrecognized board"
# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
+# undef CONFIG_EXAMPLES_NSH_HAVEUSBHOST
#endif
/* Can't support MMC/SD features if mountpoints are disabled */
@@ -88,6 +92,33 @@
# define CONFIG_EXAMPLES_NSH_MMCSDMINOR 0
#endif
+/* USB Host */
+
+#ifdef CONFIG_USBHOST
+# ifndef CONFIG_LPC17_USBHOST
+# error "CONFIG_LPC17_USBHOST is not selected"
+# endif
+#endif
+
+#ifdef CONFIG_LPC17_USBHOST
+# ifndef CONFIG_USBHOST
+# warning "CONFIG_USBHOST is not selected"
+# endif
+#endif
+
+#if !defined(CONFIG_USBHOST) || !defined(CONFIG_LPC17_USBHOST)
+# undef CONFIG_EXAMPLES_NSH_HAVEUSBHOST
+#endif
+
+#ifdef CONFIG_EXAMPLES_NSH_HAVEUSBHOST
+# ifndef CONFIG_USBHOST_DEFPRIO
+# define CONFIG_USBHOST_DEFPRIO 50
+# endif
+# ifndef CONFIG_USBHOST_STACKSIZE
+# define CONFIG_USBHOST_STACKSIZE 1024
+# endif
+#endif
+
/* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
@@ -105,18 +136,65 @@
#endif
/****************************************************************************
- * Public Functions
+ * Private Data
****************************************************************************/
+#ifdef CONFIG_EXAMPLES_NSH_HAVEUSBHOST
+static struct usbhost_driver_s *g_drvr;
+#endif
+
/****************************************************************************
- * Name: nsh_archinitialize
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_waiter
*
* Description:
- * Perform architecture specific initialization
+ * Wait for USB devices to be connected.
*
****************************************************************************/
-int nsh_archinitialize(void)
+#ifdef CONFIG_EXAMPLES_NSH_HAVEUSBHOST
+static int nsh_waiter(int argc, char *argv[])
+{
+ bool connected = false;
+ int ret;
+
+ for (;;)
+ {
+ /* Wait for the device to change state */
+
+ ret = DRVR_WAIT(g_drvr, connected);
+ DEBUGASSERT(ret == OK);
+ connected = !connected;
+
+ /* Did we just become connected? */
+
+ if (connected)
+ {
+ /* Yes.. enumerate the newly connected device */
+
+ (void)DRVR_ENUMERATE(g_drvr);
+ }
+ }
+
+ /* Keep the compiler from complaining */
+
+ return 0;
+}
+#endif
+
+/****************************************************************************
+ * Name: nsh_sdinitialize
+ *
+ * Description:
+ * Initialize SPI-based microSD.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_EXAMPLES_NSH_HAVEMMCSD
+static int nsh_sdinitialize(void)
{
FAR struct spi_dev_s *ssp;
int ret;
@@ -145,7 +223,7 @@ int nsh_archinitialize(void)
CONFIG_EXAMPLES_NSH_MMCSDSLOTNO, ssp);
if (ret < 0)
{
- message("nsh_archinitialize: "
+ message("nsh_sdinitialize: "
"Failed to bind SSP port %d to MMC/SD slot %d: %d\n",
CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO,
CONFIG_EXAMPLES_NSH_MMCSDSLOTNO, ret);
@@ -163,3 +241,70 @@ errout:
lpc17_gpiowrite(LPC1766STK_MMC_PWR, true);
return ret;
}
+#else
+# define nsh_sdinitialize() (OK)
+#endif
+
+/****************************************************************************
+ * Name: nsh_usbhostinitialize
+ *
+ * Description:
+ * Initialize SPI-based microSD.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_EXAMPLES_NSH_HAVEUSBHOST
+static int nsh_usbhostinitialize(void)
+{
+ int pid;
+
+ /* First, get an instance of the USB host interface */
+
+ g_drvr = usbhost_initialize(0);
+ if (g_drvr)
+ {
+ /* Start a thread to handle device connection. */
+
+#ifndef CONFIG_CUSTOM_STACK
+ pid = task_create("usbhost", CONFIG_USBHOST_DEFPRIO,
+ CONFIG_USBHOST_STACKSIZE,
+ (main_t)nsh_waiter, (const char **)NULL);
+#else
+ pid = task_create("usbhost", CONFIG_USBHOST_DEFPRIO,
+ (main_t)nsh_waiter, (const char **)NULL);
+#endif
+ return pid < 0 ? -ENOEXEC : OK;
+ }
+ return -ENODEV;
+}
+#else
+# define nsh_usbhostinitialize() (OK)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int nsh_archinitialize(void)
+{
+ int ret;
+
+ /* Initialize SPI-based microSD */
+
+ ret = nsh_sdinitialize();
+ if (ret == OK)
+ {
+ /* Initialize USB host */
+
+ ret = nsh_usbhostinitialize();
+ }
+ return ret;
+}
diff --git a/nuttx/include/nuttx/usb/usbhost.h b/nuttx/include/nuttx/usb/usbhost.h
index abb0a7c02..2139df5e2 100644
--- a/nuttx/include/nuttx/usb/usbhost.h
+++ b/nuttx/include/nuttx/usb/usbhost.h
@@ -144,11 +144,13 @@
* Name: DRVR_WAIT
*
* Description:
- * Wait for a device to be connected.
+ * Wait for a device to be connected or disconneced.
*
* Input Parameters:
* drvr - The USB host driver instance obtained as a parameter from the call to
* the class create() method.
+ * connected - TRUE: Wait for device to be connected; FALSE: wait for device to
+ * be disconnected
*
* Returned Values:
* Zero (OK) is returned when a device in connected. This function will not
@@ -161,7 +163,7 @@
*
*******************************************************************************/
-#define DRVR_WAIT(drvr) ((drvr)->wait(drvr))
+#define DRVR_WAIT(drvr, connected) ((drvr)->wait(drvr,connected))
/************************************************************************************
* Name: DRVR_ENUMERATE
@@ -411,9 +413,9 @@ struct usbhost_class_s
struct usbhost_epdesc_s;
struct usbhost_driver_s
{
- /* Wait for a device to connect. */
+ /* Wait for a device to connect or disconnect. */
- int (*wait)(FAR struct usbhost_driver_s *drvr);
+ int (*wait)(FAR struct usbhost_driver_s *drvr, bool connected);
/* Enumerate the connected device. As part of this enumeration process,
* the driver will (1) get the device's configuration descriptor, (2)
@@ -565,7 +567,7 @@ EXTERN const struct usbhost_registry_s *usbhost_findclass(const struct usbhost_i
EXTERN int usbhost_storageinit(void);
/*******************************************************************************
- * Name: up_usbhostinitialize
+ * Name: usbhost_initialize
*
* Description:
* Initialize USB host device controller hardware.