summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c14
-rwxr-xr-xnuttx/include/nuttx/usb/ohci.h10
-rw-r--r--nuttx/include/nuttx/usb/usbhost.h8
3 files changed, 19 insertions, 13 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
index 26bbb0758..c65415ca1 100755
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
@@ -50,8 +50,8 @@
#include <nuttx/arch.h>
#include <nuttx/usb/usb.h>
-#include <nuttx/usb/usbhost.h>
#include <nuttx/usb/ohci.h>
+#include <nuttx/usb/usbhost.h>
#include <nuttx/usb/usbhost_trace.h>
#include <arch/irq.h>
@@ -86,7 +86,7 @@
# define usbhost_dumpgpio() \
do { \
lpc17_dumpgpio(GPIO_USB_DP, "D+ P0.29; D- P0.30"); \
- lpc17_dumpgpio(GPIO_USB_UPLED, "LED P1:18; PPWR P1:19 PWRD P1:22 PVRCR P1:27); \
+ lpc17_dumpgpio(GPIO_USB_UPLED, "LED P1:18; PPWR P1:19 PWRD P1:22 PVRCR P1:27"); \
} while (0);
#else
# define usbhost_dumpgpio()
@@ -188,6 +188,12 @@ static int lpc17_usbinterrupt(int irq, FAR void *context);
/* USB host controller operations **********************************************/
+/* Initializaion ***************************************************************/
+
+static void usbhost_tdinit(volatile struct usbhost_hctd_s *td);
+static void usbhost_edinit(volatile struct usbhost_hced_s *);
+static void usbhost_hccainit(volatile struct usbhost_hcca_s *hcca);
+
/*******************************************************************************
* Private Data
*******************************************************************************/
@@ -421,7 +427,7 @@ void up_usbhostinitialize(void)
usbhost_edinit(EDBulkOut);
usbhost_tdinit(TDHead);
usbhost_tdinit(TDTail);
- usbhost_hccanit(Hcca);
+ usbhost_hccainit(Hcca);
/* Wait 50MS then perform hardware reset */
@@ -457,7 +463,7 @@ void up_usbhostinitialize(void)
/* Clear pending interrupts */
regval = lpc17_getreg(LPC17_USBHOST_INTST);
- lpc17_putreg(revgval, LPC17_USBHOST_INTST);
+ lpc17_putreg(regval, LPC17_USBHOST_INTST);
/* Enable OHCI interrupts */
diff --git a/nuttx/include/nuttx/usb/ohci.h b/nuttx/include/nuttx/usb/ohci.h
index dd714c7c1..d23e1aa67 100755
--- a/nuttx/include/nuttx/usb/ohci.h
+++ b/nuttx/include/nuttx/usb/ohci.h
@@ -118,11 +118,11 @@
#define OHCI_CTRL_CLE (1 << 4) /* Bit 3: Control list enable */
#define OHCI_CTRL_BLE (1 << 5) /* Bit 4: Bulk list enable */
#define OHCI_CTRL_HCFS_SHIFT (6) /* Bits 6-7: Host controller functional state */
-#define OHCI_CTRL_HCFS_MASK (3 << OHCI_CTRL_HCFS_MASK)
-# define OHCI_CTRL_HCFS_RESET (0 << OHCI_CTRL_HCFS_MASK)
-# define OHCI_CTRL_HCFS_RESUME (1 << OHCI_CTRL_HCFS_MASK)
-# define OHCI_CTRL_HCFS_OPER (2 << OHCI_CTRL_HCFS_MASK)
-# define OHCI_CTRL_HCFS_SUSPEND (3 << OHCI_CTRL_HCFS_MASK)
+#define OHCI_CTRL_HCFS_MASK (3 << OHCI_CTRL_HCFS_SHIFT)
+# define OHCI_CTRL_HCFS_RESET (0 << OHCI_CTRL_HCFS_SHIFT)
+# define OHCI_CTRL_HCFS_RESUME (1 << OHCI_CTRL_HCFS_SHIFT)
+# define OHCI_CTRL_HCFS_OPER (2 << OHCI_CTRL_HCFS_SHIFT)
+# define OHCI_CTRL_HCFS_SUSPEND (3 << OHCI_CTRL_HCFS_SHIFT)
#define OHCI_CTRL_IR (1 << 8) /* Bit 8: Interrupt routing */
#define OHCI_CTRL_RWC (1 << 9) /* Bit 9: Remote wakeup connected */
#define OHCI_CTRL_RWE (1 << 10) /* Bit 10: Remote wakeup enable */
diff --git a/nuttx/include/nuttx/usb/usbhost.h b/nuttx/include/nuttx/usb/usbhost.h
index a3a356df5..7043c65e7 100644
--- a/nuttx/include/nuttx/usb/usbhost.h
+++ b/nuttx/include/nuttx/usb/usbhost.h
@@ -105,7 +105,7 @@
*
************************************************************************************/
-#definei CLASS_CONFIGDESC(class, configdesc, desclen) ((class)->configdesc(class, configdesc, desclen))
+#define CLASS_CONFIGDESC(class, configdesc, desclen) ((class)->configdesc(class, configdesc, desclen))
/************************************************************************************
* Name: CLASS_DISCONNECTED
@@ -124,7 +124,7 @@
*
************************************************************************************/
-#definei CLASS_DISCONNECTED(class) ((class)->disconnected(class))
+#define CLASS_DISCONNECTED(class) ((class)->disconnected(class))
/************************************************************************************
* Public Types
@@ -158,7 +158,7 @@ struct usbhost_registry_s
* provide those instances in write-able memory (RAM).
*/
- struct usbhost_registry_s flink;
+ struct usbhost_registry_s *flink;
/* This 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
@@ -168,7 +168,7 @@ struct usbhost_registry_s
*/
FAR struct usbhost_class_s *(*create)(FAR struct usbhost_driver_s *drvr,
- FAR const struct usbhost_id_s *id)
+ FAR const struct usbhost_id_s *id);
/* This information uniquely identifies the USB host class implementation that
* goes with a specific USB device.