summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-10-01 23:34:27 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-10-01 23:34:27 +0000
commit27e2ca4bed22eb0c1ae277770c1d08a7771baf35 (patch)
treeea6111e6fa379e69233127d31b7e7ae83d6d1e0b /nuttx
parentad1c3b799584ba5f51434fc43796235747da3866 (diff)
downloadpx4-nuttx-27e2ca4bed22eb0c1ae277770c1d08a7771baf35.tar.gz
px4-nuttx-27e2ca4bed22eb0c1ae277770c1d08a7771baf35.tar.bz2
px4-nuttx-27e2ca4bed22eb0c1ae277770c1d08a7771baf35.zip
Integrating LPC214x USB driver
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@970 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/lpc214x/chip.h25
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_apb.h72
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_head.S183
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_pll.h105
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c7
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c248
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.h28
-rw-r--r--nuttx/configs/mcu123-lpc214x/include/board.h12
-rw-r--r--nuttx/configs/mcu123-lpc214x/nsh/defconfig8
-rw-r--r--nuttx/configs/mcu123-lpc214x/ostest/defconfig8
-rw-r--r--nuttx/include/nuttx/usbdev_trace.h6
11 files changed, 549 insertions, 153 deletions
diff --git a/nuttx/arch/arm/src/lpc214x/chip.h b/nuttx/arch/arm/src/lpc214x/chip.h
index 597ee8702..74e976dfb 100644
--- a/nuttx/arch/arm/src/lpc214x/chip.h
+++ b/nuttx/arch/arm/src/lpc214x/chip.h
@@ -80,7 +80,7 @@
#define LPC214X_MEMMAP 0xe01fc040 /* Memory Mapping Control */
#define LPC214X_PLL_BASE 0xe01fc080 /* Phase Locked Loop (PLL) base address */
#define LPC214X_PCON_BASE 0xe01fc0c0 /* Power Control (PCON) base address */
-#define LPC214X_VPBDIV 0xe01fc100 /* VPBDIV Address */
+#define LPC214X_APBDIV 0xe01fc100 /* APBDIV Address */
#define LPC214X_EXT_BASE 0xe01fc140 /* External Interrupt base address */
#define LPC214X_EMC_BASE 0xffe00000 /* External Memory Controller (EMC) base address */
@@ -248,29 +248,6 @@
#define LPC214X_PLL_STAT_OFFSET 0x08 /* PLL Status Offset */
#define LPC214X_PLL_FEED_OFFSET 0x0c /* PLL Feed Offset */
-/* PLL Control Register Bit Settings */
-
-#define LPC214X_PLL_CON_PLLE (1 << 0) /* PLL Enable */
-#define LPC214X_PLL_CON_PLLC (1 << 1) /* PLL Connect */
-
-/* PLL Configuration Register Bit Settings */
-
-#define LPC214X_PLL_CFG_MSEL (0x1f << 0) /* PLL Multiplier */
-#define LPC214X_PLL_CFG_PSEL (0x03 << 5) /* PLL Divider */
-
-/* PLL Status Register Bit Settings */
-
-#define LPC214X_PLL_STAT_MSEL (0x1f << 0) /* PLL Multiplier Readback */
-#define LPC214X_PLL_STAT_PSEL (0x03 << 5) /* PLL Divider Readback */
-#define LPC214X_PLL_STAT_PLLE (1 << 8) /* PLL Enable Readback */
-#define LPC214X_PLL_STAT_PLLC (1 << 9) /* PLL Connect Readback */
-#define LPC214X_PLL_STAT_PLOCK (1 << 10) /* PLL Lock Status */
-
-/* PLL Feed Register values */
-
-#define LPC214X_PLL_FEED1 0xaa
-#define LPC214X_PLL_FEED2 0x55
-
/* Power Control register offsets */
#define LPC214X_PCON_OFFSET 0x00 /* Control Register */
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_apb.h b/nuttx/arch/arm/src/lpc214x/lpc214x_apb.h
new file mode 100644
index 000000000..996983778
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_apb.h
@@ -0,0 +1,72 @@
+/************************************************************************************
+ * arch/arm/src/lpc214x/lpc214x_apb.h
+ *
+ * Copyright (C) 2008 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.
+ *
+ ************************************************************************************/
+
+#ifndef _ARCH_ARM_SRC_LPC214X_APB_H
+#define _ARCH_ARM_SRC_LPC214X_APB_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Register address definitions *****************************************************/
+
+#define LPC214X_APB_APBDIV (0xe01fc100) /* 8-bit R/W APB divider register */
+
+/* Register bit definitions *********************************************************/
+
+/* APB divider register */
+
+#define LPC214X_APBDIV_MASK (0x03) /* Bit 0:1: APB divider value */
+#define LPC214X_APBDIV_DIV4 (0x00) /* Bit 0:1=00: APB=PCLK/4 */
+#define LPC214X_APBDIV_DIV1 (0x01) /* Bit 0:1=01: APB=PCLK */
+#define LPC214X_APBDIV_DIV2 (0x02) /* Bit 0:1=10: APB=PCLK/2 */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+#endif /* _ARCH_ARM_SRC_LPC214X_APB_H */
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_head.S b/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
index 6b5c24e17..d9ade6782 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
@@ -39,7 +39,10 @@
#include <nuttx/config.h>
+#include <arch/board/board.h>
#include "chip.h"
+#include "lpc214x_pll.h"
+#include "lpc214x_apb.h"
#include "up_internal.h"
#include "up_arch.h"
@@ -82,33 +85,77 @@
/* Phase Locked Loop (PLL) initialization values
*
- * BIT 0:4 MSEL: PLL Multiplier "M" Value
+ * Bit 0:4 MSEL: PLL Multiplier "M" Value
* CCLK = M * Fosc
- * BIT 5:6 PSEL: PLL Divider "P" Value
+ * Bit 5:6 PSEL: PLL Divider "P" Value
* Fcco = CCLK * 2 * P
* 156MHz <= Fcco <= 320MHz
*/
+/* PLL0 provides CCLK and must always be configured */
-#ifndef CONFIG_PLLCFG_VALUE /* Can be selected from config file */
-# define CONFIG_PLLCFG_VALUE 0x00000024
+#ifndef CONFIG_PLLCFG_VALUE /* board.h values can be supeceded config file */
+# ifdef LPC214X_PLL_M
+# define CONFIG_PLLCFG_MSEL (LPC214X_PLL_M-1)
+# else
+# warning "PLL_M not specified"
+# define CONFIG_PLLCFG_MSEL (5-1)
+# endif
+# ifdef LPC214X_PLL_P
+# if LPC214X_PLL_P == 1
+# define CONFIG_PLLCFG_PSEL LPC214X_PLL_CFG_PSEL1
+# elif LPC214X_PLL_P == 2
+# define CONFIG_PLLCFG_PSEL LPC214X_PLL_CFG_PSEL2
+# elif LPC214X_PLL_P == 4
+# define CONFIG_PLLCFG_PSEL LPC214X_PLL_CFG_PSEL4
+# elif LPC214X_PLL_P == 8
+# define CONFIG_PLLCFG_PSEL LPC214X_PLL_CFG_PSEL8
+# else
+# error "Unrecognized value for PLL_P"
+# endif
+# else
+# warning "PLL_P not specified"
+# define CONFIG_PLLCFG_PSEL LPC214X_PLL_CFG_PSEL2
+# endif
+# define CONFIG_PLLCFG_VALUE (CONFIG_PLLCFG_PSEL|CONFIG_PLLCFG_MSEL)
#endif
-/* PLL Control register */
-
-#ifndef CONFIG_PLLCON_VALUE /* Can be selected from config file */
-# define CONFIG_PLLCON_VALUE LPC214X_PLL_CON_PLLE
+/* If USB is enabled, PLL1 must be configured for 48MHz to provide USB clocking */
+
+#ifdef CONFIG_USBDEV
+# ifndef CONFIG_USBPLLCFG_VALUE /* board.h values can be supeceded config file */
+# ifdef LPC214X_USBPLL_M
+# define LPC214X_USBPLLCFG_MSEL (LPC214X_USBPLL_M-1)
+# else
+# warning "PLL_M not specified"
+# define LPC214X_USBPLLCFG_MSEL 0x00000004
+# endif
+# ifdef LPC214X_USBPLL_P
+# if LPC214X_USBPLL_P == 1
+# define LPC214X_USBPLLCFG_PSEL 0x00000000
+# elif LPC214X_USBPLL_P == 2
+# define LPC214X_USBPLLCFG_PSEL 0x00000020
+# elif LPC214X_USBPLL_P == 4
+# define LPC214X_USBPLLCFG_PSEL 0x00000040
+# elif LPC214X_USBPLL_P == 8
+# define LPC214X_USBPLLCFG_PSEL 0x00000060
+# else
+# error "Unrecognized value for PLL_P"
+# endif
+# endif
+# define CONFIG_USBPLLCFG_VALUE (LPC214X_USBPLLCFG_PSEL|LPC214X_USBPLLCFG_MSEL)
+# endif
#endif
/* Memory Accelerator Module (MAM) initialization values
*
* MAM Control Register
- * BIT 0:1 Mode
+ * Bit 0:1 Mode
* 0 = Disabled
* 1 = Partially Enabled
* 2 = Fully Enabled
* MAM Timing Register
- * BIT 0:2 Fetch Cycles
+ * Bit 0:2 Fetch Cycles
* 0 = Reserved
* 1 = 1
* 2 = 2
@@ -127,32 +174,40 @@
# define CONFIG_MAMTIM_VALUE 0x00000004
#endif
-/* VPBDIV initialization values
+/* APBDIV initialization values
*
- * BITS 0:1 VPB Peripheral Bus Clock Rate
- * 0 = VPB Clock = CPU Clock / 4
- * 1 = VPB Clock = CPU Clock
- * 2 = VPB Clock = CPU Clock / 2
- * BITS 4:5 XCLKDIV: XCLK Pin
- * 0 = XCLK Pin = CPU Clock / 4
- * 1 = XCLK Pin = CPU Clock
- * 2 = XCLK Pin = CPU Clock / 2
+ * Bits 0:1 APB Peripheral Bus Clock Rate
+ * 0 = APB Clock = CPU Clock / 4
+ * 1 = APB Clock = CPU Clock
+ * 2 = APB Clock = CPU Clock / 2
*/
-#ifndef CONFIG_VPBDIV_VALUE /* Can be selected from config file */
-# define CONFIG_VPBDIV_VALUE 0x00000001
+#ifndef CONFIG_APBDIV_VALUE /* Can be selected from config file */
+# ifdef LPC214X_APB_DIV
+# if LPC214X_APB_DIV == 1
+# define CONFIG_APBDIV_VALUE LPC214X_APBDIV_DIV1
+# elif LPC214X_APB_DIV == 2
+# define CONFIG_APBDIV_VALUE LPC214X_APBDIV_DIV2
+# elif LPC214X_APB_DIV == 4
+# define CONFIG_APBDIV_VALUE LPC214X_APBDIV_DIV4
+# else
+# error "Unrecognized value for APBDIV"
+# endif
+# else
+# define CONFIG_APBDIV_VALUE LPC214X_APBDIV_DIV1
+# endif
#endif
/* External Memory Controller (EMC) initialization values
*
* Bank Configuration n (BCFG0..3)
- * BIT 0:3 IDCY: Idle Cycles (0-15)
- * BIT 5:9 WST1: Wait States 1 (0-31)
- * BIT 11:15 WST2: Wait States 2 (0-31)
- * BIT 10 RBLE: Read Byte Lane Enable
- * BIT 26 WP: Write Protect
- * BIT 27 BM: Burst ROM
- * BIT 28:29 MW: Memory Width (0=8-bit 1=16-bit 2=32-bit 3=Reserved)
+ * Bit 0:3 IDCY: Idle Cycles (0-15)
+ * Bit 5:9 WST1: Wait States 1 (0-31)
+ * Bit 11:15 WST2: Wait States 2 (0-31)
+ * Bit 10 RBLE: Read Byte Lane Enable
+ * Bit 26 WP: Write Protect
+ * Bit 27 BM: Burst ROM
+ * Bit 28:29 MW: Memory Width (0=8-bit 1=16-bit 2=32-bit 3=Reserved)
*/
#ifndef CONFIG_BCFG0_VALUE /* Can be selected from config file */
@@ -189,17 +244,23 @@
#ifndef CONFIG_PINSEL1_VALUE /* Can be selected from the config file */
# ifdef CONFIG_ADC_SETUP
-# define CONFIG_PINSEL1_VALUE 0x01000000; /* Enable DAC */
+# define CONFIG_PINSEL1_ADC 0x01000000 /* Enable DAC */
+# else
+# define CONFIG_PINSEL1_ADC 0x00000000 /* Reset value */
+# endif
+# ifdef CONFIG_USBDEV
+# define CONFIG_PINSEL1_USBDEV 0x80004000 /* Enable Vbus and Connect LED */
# else
-# define CONFIG_PINSEL1_VALUE 0x00000000; /* Reset value */
+# define CONFIG_PINSEL1_USBDEV 0x00000000 /* Reset value */
# endif
+# define CONFIG_PINSEL1_VALUE (CONFIG_PINSEL1_ADC|CONFIG_PINSEL1_USBDEV)
#endif
/* External Memory Pins definitions
- * BIT 0:1 Reserved
- * BIT 2 GPIO/DEBUG
- * BIT 3 GPIO/TRACE
- * BIT 31:4 Reserved
+ * Bit 0:1 Reserved
+ * Bit 2 GPIO/DEBUG
+ * Bit 3 GPIO/TRACE
+ * Bit 31:4 Reserved
* CS0..3, OE, WE, BLS0..3, D0..31, A2..23, JTAG Pins
*/
@@ -260,13 +321,13 @@
#endif
.endm
-/* Configure VPBDIV */
+/* Configure APBDIV */
- .macro configvpbdiv, base, val
-#ifdef CONFIG_VPBDIV_SETUP
- ldr \base, =LPC214X_VPBDIV
- ldr \val, =CONFIG_VPBDIV_VALUE
- str \val, [\base]
+ .macro configapbdiv, base, val
+#ifdef CONFIG_APBDIV_SETUP
+ ldr \base, =LPC214X_APBDIV
+ ldr \val, =CONFIG_APBDIV_VALUE
+ strb \val, [\base]
#endif
.endm
@@ -274,7 +335,7 @@
.macro configpll, base, val1, val2, val3
#ifdef CONFIG_PLL_SETUP
- ldr \base, =LPC214X_PLL_BASE
+ ldr \base, =LPC214X_PLL0_BASE
mov \val1, #LPC214X_PLL_FEED1
mov \val2, #LPC214X_PLL_FEED2
@@ -282,7 +343,7 @@
mov \val3, #CONFIG_PLLCFG_VALUE
str \val3, [\base, #LPC214X_PLL_CFG_OFFSET]
- mov \val3, #CONFIG_PLLCON_VALUE
+ mov \val3, #LPC214X_PLL_CON_PLLE
str \val3, [\base, #LPC214X_PLL_CON_OFFSET]
str \val1, [\base, #LPC214X_PLL_FEED_OFFSET]
str \val2, [\base, #LPC214X_PLL_FEED_OFFSET]
@@ -302,6 +363,37 @@
#endif
.endm
+ .macro configusbpll, base, val1, val2, val3
+#ifdef CONFIG_USBDEV
+ ldr \base, =LPC214X_PLL1_BASE
+ mov \val1, #LPC214X_PLL_FEED1
+ mov \val2, #LPC214X_PLL_FEED2
+
+ /* Configure and Enable PLL */
+
+ mov \val3, #CONFIG_USBPLLCFG_VALUE
+ str \val3, [\base, #LPC214X_PLL_CFG_OFFSET]
+ mov \val3, #LPC214X_PLL_CON_PLLE
+ str \val3, [\base, #LPC214X_PLL_CON_OFFSET]
+ str \val1, [\base, #LPC214X_PLL_FEED_OFFSET]
+ str \val2, [\base, #LPC214X_PLL_FEED_OFFSET]
+
+ /* Wait until PLL Locked */
+1:
+ ldr \val3, [\base, #LPC214X_PLL_STAT_OFFSET]
+ ands \val3, \val3, #LPC214X_PLL_STAT_PLOCK
+ beq 1b
+
+ /* Switch to PLL Clock */
+
+ mov \val3, #(LPC214X_PLL_CON_PLLE | LPC214X_PLL_CON_PLLC)
+ str \val3, [\base, #LPC214X_PLL_CON_OFFSET]
+ str \val1, [\base, #LPC214X_PLL_FEED_OFFSET]
+ str \val2, [\base, #LPC214X_PLL_FEED_OFFSET]
+#endif
+ .endm
+
+
/* Configure the Memory Accelerator Module (MAM) */
.macro configmam, base, val
@@ -420,13 +512,14 @@ __start:
configemc r0, r1
- /* Configure VPBDIV */
+ /* Configure APBDIV */
- configvpbdiv r0, r1
+ configapbdiv r0, r1
- /* Configure the PLL */
+ /* Configure the PLL(s) */
configpll r0, r1, r2, r3
+ configusbpll r0, r1, r2, r3
/* Configure the Memory Accelerator Module (MAM) */
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_pll.h b/nuttx/arch/arm/src/lpc214x/lpc214x_pll.h
new file mode 100644
index 000000000..386f3a765
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_pll.h
@@ -0,0 +1,105 @@
+/****************************************************************************************************
+ * arch/arm/src/lpc214x/lpc214x_pll.h
+ *
+ * Copyright (C) 2008 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.
+ *
+ ****************************************************************************************************/
+
+#ifndef _ARCH_ARM_SRC_LPC214X_PLL_H
+#define _ARCH_ARM_SRC_LPC214X_PLL_H
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <chip.h>
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+
+/* PLL bass addresses *******************************************************************************/
+
+/* There are two PLLs: PLL0 generates CCLK and PLL1 is configured to provide the 48MHx USB clock */
+
+#define LPC214X_PLL0_BASE (LPC214X_PLL_BASE)
+#define LPC214X_PLL1_BASE (LPC214X_PLL_BASE + 0x00000020)
+
+/* PLL registers ************************************************************************************/
+
+#define LPC214x_PLL0_CON (LPC214X_PLL0_BASE+LPC214X_PLL_CON_OFFSET)
+#define LPC214x_PLL0_CFG (LPC214X_PLL0_BASE+LPC214X_PLL_CFG_OFFSET)
+#define LPC214x_PLL0_STAT (LPC214X_PLL0_BASE+LPC214X_PLL_STAT_OFFSET)
+#define LPC214x_PLL0_FEED (LPC214X_PLL0_BASE+LPC214X_PLL_FEED_OFFSET)
+
+#define LPC214x_PLL1_CON (LPC214X_PLL1_BASE+LPC214X_PLL_CON_OFFSET)
+#define LPC214x_PLL1_CFG (LPC214X_PLL1_BASE+LPC214X_PLL_CFG_OFFSET)
+#define LPC214x_PLL1_STAT (LPC214X_PLL1_BASE+LPC214X_PLL_STAT_OFFSET)
+#define LPC214x_PLL1_FEED (LPC214X_PLL1_BASE+LPC214X_PLL_FEED_OFFSET)
+
+/* Register bit settings ****************************************************************************/
+
+/* PLL Control Register Bit Settings */
+
+#define LPC214X_PLL_CON_PLLE (1 << 0) /* PLL Enable */
+#define LPC214X_PLL_CON_PLLC (1 << 1) /* PLL Connect */
+
+/* PLL Configuration Register Bit Settings */
+
+#define LPC214X_PLL_CFG_MSEL (0x1f << 0) /* PLL Multiplier (minus 1) */
+#define LPC214X_PLL_CFG_PSEL (0x03 << 5) /* PLL Divider (encoded) */
+#define LPC214X_PLL_CFG_PSEL1 (0x00 << 5)
+#define LPC214X_PLL_CFG_PSEL2 (0x01 << 5)
+#define LPC214X_PLL_CFG_PSEL4 (0x02 << 5)
+#define LPC214X_PLL_CFG_PSEL8 (0x03 << 5)
+
+/* PLL Status Register Bit Settings */
+
+#define LPC214X_PLL_STAT_MSEL (0x1f << 0) /* PLL Multiplier Readback */
+#define LPC214X_PLL_STAT_PSEL (0x03 << 5) /* PLL Divider Readback */
+#define LPC214X_PLL_STAT_PLLE (1 << 8) /* PLL Enable Readback */
+#define LPC214X_PLL_STAT_PLLC (1 << 9) /* PLL Connect Readback */
+#define LPC214X_PLL_STAT_PLOCK (1 << 10) /* PLL Lock Status */
+
+/* PLL Feed Register values */
+
+#define LPC214X_PLL_FEED1 0xaa
+#define LPC214X_PLL_FEED2 0x55
+
+/****************************************************************************************************
+ * Inline Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************************************/
+
+#endif /* _ARCH_ARM_SRC_LPC214X_PLL_H */
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c b/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c
index 3ed87a2bc..4a7bbb6c4 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_timerisr.c
@@ -54,7 +54,12 @@
* Definitions
****************************************************************************/
-#define PCLKFREQ (LPC214X_FOSC/4) /* PCLK must be FOSC/4 */
+/* The timers count at the rate of PCLK which is determined by PLL_M and
+ * and APBDIV:
+ */
+
+#define LPC214X_CCLKFREQ (LPC214X_FOSC*LPC214X_PLL_M)
+#define LPC214X_PCLKFREQ (LPC214X_CCLKFREQ/LPC214X_APBDIV)
#define tmr_getreg8(o) getreg8(LPC214X_TMR0_BASE+(o))
#define tmr_getreg16(o) getreg16(LPC214X_TMR0_BASE+(o))
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c
index d85c97d2e..d86b0e3a4 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c
@@ -57,6 +57,7 @@
#include "up_arch.h"
#include "up_internal.h"
#include "lpc214x_usbdev.h"
+#include "lpc214x_pll.h"
#include "lpc214x_power.h"
/*******************************************************************************
@@ -134,14 +135,15 @@
#define LPC214X_TRACEERR_DRIVER 0x0007
#define LPC214X_TRACEERR_DRIVERREGISTERED 0x0008
#define LPC214X_TRACEERR_EPREAD 0x0009
-#define LPC214X_TRACEERR_INVALIDPARMS 0x000a
-#define LPC214X_TRACEERR_IRQREGISTRATION 0x000b
-#define LPC214X_TRACEERR_NODMADESC 0x000c
-#define LPC214X_TRACEERR_NOEP 0x000d
-#define LPC214X_TRACEERR_NOTCONFIGURED 0x000e
-#define LPC214X_TRACEERR_NULLPACKET 0x000f
-#define LPC214X_TRACEERR_NULLREQUEST 0x0010
-#define LPC214X_TRACEERR_STALLED 0x0011
+#define LPC214X_TRACEERR_INVALIDCMD 0x000a
+#define LPC214X_TRACEERR_INVALIDPARMS 0x000b
+#define LPC214X_TRACEERR_IRQREGISTRATION 0x000c
+#define LPC214X_TRACEERR_NODMADESC 0x000d
+#define LPC214X_TRACEERR_NOEP 0x000e
+#define LPC214X_TRACEERR_NOTCONFIGURED 0x000f
+#define LPC214X_TRACEERR_NULLPACKET 0x0010
+#define LPC214X_TRACEERR_NULLREQUEST 0x0011
+#define LPC214X_TRACEERR_STALLED 0x0012
/* Trace interrupt codes */
@@ -218,6 +220,11 @@
#define LPC214X_NLOGENDPOINTS (16) /* ep0-15 */
#define LPC214X_NPHYSENDPOINTS (32) /* x2 for IN and OUT */
+/* Odd physical endpoint numbers are IN; even are out */
+
+#define LPC214X_EPPHYIN(epphy) (((epphy)&1)!=0)
+#define LPC214X_EPPHYOUT(epphy) (((epphy)&1)==0)
+
/* Mapping to more traditional endpoint numbers */
#define LPC214X_EP_LOG2PHYOUT(ep) ((ep)&0x0f)<<1))
@@ -233,10 +240,12 @@
#define LPC214X_EPINTRSET (0x0c30c30c) /* Interrupt endpoints */
#define LPC214X_EPBULKSET (0xf0c30c30) /* Bulk endpoints */
#define LPC214X_EPISOCSET (0x030c30c0) /* Isochronous endpoints */
+#define LPC214X_EPDBLBUFFER (0xf3cf3cf0) /* Double buffered endpoints */
-#define LPC214X_EP0MAXPACKET (64) /* EP0 max packet size */
-#define LPC214X_BULKMAXPACKET (64) /* Bulk endpoint max packet */
-#define LPC214X_INTRMAXPACKET (64) /* Interrupt endpoint max packet */
+#define LPC214X_EP0MAXPACKET (64) /* EP0 max packet size (1-64) */
+#define LPC214X_BULKMAXPACKET (64) /* Bulk endpoint max packet (8/16/32/64) */
+#define LPC214X_INTRMAXPACKET (64) /* Interrupt endpoint max packet (1 to 64) */
+#define LPC214X_ISOCMAXPACKET (512) /* Acutally 1..1023 */
/* EP0 status */
@@ -277,8 +286,7 @@ struct lpc214x_ep_s
ubyte eplog; /* Logical EP address from descriptor */
ubyte epphy; /* Physical EP address */
ubyte stalled:1; /* Endpoint is halted */
- ubyte in:1; /* Endpoint is IN only */
- ubyte halted:1; /* Endport feature halted */
+ ubyte halted:1; /* Endpoint feature halted */
};
/* This represents a DMA descriptor */
@@ -473,8 +481,53 @@ static const struct usbdev_ops_s g_devops =
#if defined(CONFIG_LPC214X_USBDEV_REGDEBUG) && defined(CONFIG_DEBUG)
static uint32 lpc214x_getreg(uint32 addr)
{
+ static uint32 prevaddr = 0;
+ static uint32 preval = 0;
+ static uint32 count = 0;
+
+ /* Read the value from the register */
+
uint32 val = getreg32(addr);
- lldbg("%04x->%04x\n", addr, val);
+
+ /* Is this the same value that we read from the same registe last time? Are
+ * we polling the register? If so, suppress some of the output.
+ */
+
+ if (addr == prevaddr || val == preval)
+ {
+ if (count == 0xffffffff || ++count > 3)
+ {
+ if (count == 4)
+ {
+ lldbg("...\n");
+ }
+ return val;
+ }
+ }
+
+ /* No this is a new address or value */
+
+ else
+ {
+ /* Did we print "..." for the previous value? */
+
+ if (count > 3)
+ {
+ /* Yes.. then show how many times the value repeated */
+
+ lldbg("[repeats %d more times]\n", count-3);
+ }
+
+ /* Save the new address, value, and count */
+
+ prevaddr = addr;
+ preval = val;
+ count = 1;
+ }
+
+ /* Show the register value read */
+
+ lldbg("%08x->%08x\n", addr, val);
return val;
}
#endif
@@ -490,7 +543,12 @@ static uint32 lpc214x_getreg(uint32 addr)
#if defined(CONFIG_LPC214X_USBDEV_REGDEBUG) && defined(CONFIG_DEBUG)
static void lpc214x_putreg(uint32 val, uint32 addr)
{
- lldbg("%04x<-%04x\n", addr, val);
+ /* Show the register value being written */
+
+ lldbg("%08x<-%08x\n", addr, val);
+
+ /* Write the value */
+
putreg32(val, addr);
}
#endif
@@ -513,11 +571,11 @@ static uint32 lpc214x_usbcmd(uint16 cmd, ubyte data)
flags = irqsave();
lpc214x_putreg(USBDEV_DEVINT_CDFULL|USBDEV_DEVINT_CCEMTY, LPC214X_USBDEV_DEVINTCLR);
- /* Load commonad in USB engine */
+ /* Load command + WR in command code register */
lpc214x_putreg(((cmd & 0xff) << 16) + CMD_USB_CMDWR, LPC214X_USBDEV_CMDCODE);
- /* Wait until command is accepted */
+ /* Wait until the command register is empty (CCEMPTY != 0, command is accepted) */
while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CCEMTY) == 0);
@@ -525,36 +583,66 @@ static uint32 lpc214x_usbcmd(uint16 cmd, ubyte data)
lpc214x_putreg(USBDEV_DEVINT_CCEMTY, LPC214X_USBDEV_DEVINTCLR);
- /* determinate next phase of the command */
+ /* Determine next phase of the command */
switch (cmd)
{
+ /* Write operations */
+
case CMD_USB_DEV_SETADDRESS:
case CMD_USB_DEV_CONFIG:
case CMD_USB_DEV_SETMODE:
case CMD_USB_DEV_SETSTATUS:
- lpc214x_putreg((data << 16) + CMD_USB_DATAWR, LPC214X_USBDEV_CMDCODE);
- while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CCEMTY) == 0);
+ {
+ /* Send data + WR and wait for CCEMPTY */
+
+ lpc214x_putreg((data << 16) + CMD_USB_DATAWR, LPC214X_USBDEV_CMDCODE);
+ while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CCEMTY) == 0);
+ }
break;
+ /* 16 bit read operations */
+
case CMD_USB_DEV_READFRAMENO:
case CMD_USB_DEV_READTESTREG:
- lpc214x_putreg((cmd << 16) + CMD_USB_DATARD, LPC214X_USBDEV_CMDCODE);
- while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CDFULL) == 0);
- lpc214x_putreg(USBDEV_DEVINT_CDFULL, LPC214X_USBDEV_DEVINTCLR);
- tmp = lpc214x_getreg(LPC214X_USBDEV_CMDDATA);
- lpc214x_putreg((cmd << 16) + CMD_USB_DATARD, LPC214X_USBDEV_CMDCODE);
- while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CDFULL) == 0);
- tmp |= lpc214x_getreg(LPC214X_USBDEV_CMDDATA) << 8;
+ {
+ /* Send command code + RD and wait for CDFULL */
+
+ lpc214x_putreg((cmd << 16) + CMD_USB_DATARD, LPC214X_USBDEV_CMDCODE);
+ while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CDFULL) == 0);
+
+ /* Clear CDFULL and read LS data */
+
+ lpc214x_putreg(USBDEV_DEVINT_CDFULL, LPC214X_USBDEV_DEVINTCLR);
+ tmp = lpc214x_getreg(LPC214X_USBDEV_CMDDATA);
+
+ /* Send command code + RD and wait for CDFULL */
+
+ lpc214x_putreg((cmd << 16) + CMD_USB_DATARD, LPC214X_USBDEV_CMDCODE);
+ while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CDFULL) == 0);
+
+ /* Read MS data */
+
+ tmp |= lpc214x_getreg(LPC214X_USBDEV_CMDDATA) << 8;
+ }
break;
+ /* 8-bit read operations */
+
case CMD_USB_DEV_GETSTATUS:
case CMD_USB_DEV_GETERRORCODE:
case CMD_USB_DEV_READERRORSTATUS:
case CMD_USB_EP_CLRBUFFER:
- lpc214x_putreg((cmd << 16) + CMD_USB_DATARD, LPC214X_USBDEV_CMDCODE);
- while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CDFULL) == 0);
- tmp = lpc214x_getreg(LPC214X_USBDEV_CMDDATA);
+ {
+ /* Send command code + RD and wait for CDFULL */
+
+ lpc214x_putreg((cmd << 16) + CMD_USB_DATARD, LPC214X_USBDEV_CMDCODE);
+ while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CDFULL) == 0);
+
+ /* Read data */
+
+ tmp = lpc214x_getreg(LPC214X_USBDEV_CMDDATA);
+ }
break;
default:
@@ -562,14 +650,28 @@ static uint32 lpc214x_usbcmd(uint16 cmd, ubyte data)
{
case CMD_USB_EP_SELECT:
case CMD_USB_EP_SELECTCLEAR:
- lpc214x_putreg((cmd << 16) + CMD_USB_DATARD, LPC214X_USBDEV_CMDCODE);
- while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CDFULL) == 0);
- tmp = lpc214x_getreg(LPC214X_USBDEV_CMDDATA);
+ {
+ /* Send command code + RD and wait for CDFULL */
+
+ lpc214x_putreg((cmd << 16) + CMD_USB_DATARD, LPC214X_USBDEV_CMDCODE);
+ while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CDFULL) == 0);
+
+ /* Read data */
+
+ tmp = lpc214x_getreg(LPC214X_USBDEV_CMDDATA);
+ }
break;
case CMD_USB_EP_SETSTATUS:
- lpc214x_putreg((data << 16) + CMD_USB_DATAWR, LPC214X_USBDEV_CMDCODE);
- while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CCEMTY) == 0);
+ {
+ /* Send data + RD and wait for CCEMPTY */
+
+ lpc214x_putreg((data << 16) + CMD_USB_DATAWR, LPC214X_USBDEV_CMDCODE);
+ while ((lpc214x_getreg(LPC214X_USBDEV_DEVINTST) & USBDEV_DEVINT_CCEMTY) == 0);
+ }
+ break;
+ default:
+ usbtrace(TRACE_DEVERROR(LPC214X_TRACEERR_INVALIDCMD), 0);
break;
}
break;
@@ -1173,7 +1275,6 @@ static inline void lpc214x_ep0setup(struct lpc214x_usbdev_s *priv)
/* Dispatch any non-standard requests */
- ep0->in = (ctrl.type & USB_DIR_IN) != 0;
if ((ctrl.type & USB_REQ_TYPE_MASK) != USB_REQ_TYPE_STANDARD)
{
lpc214x_dispatchrequest(priv, &ctrl);
@@ -1593,7 +1694,7 @@ static int lpc214x_usbinterrupt(int irq, FAR void *context)
/* Get device status */
- g_usbdev.devstatus = lpc214x_usbcmd(CMD_USB_DEV_GETSTATUS, 0);
+ g_usbdev.devstatus = (ubyte)lpc214x_usbcmd(CMD_USB_DEV_GETSTATUS, 0);
usbtrace(TRACE_INTDECODE(LPC214X_TRACEINTID_DEVSTAT), (uint16)g_usbdev.devstatus);
/* Device connection status */
@@ -1907,8 +2008,8 @@ static int lpc214x_dmasetup(struct lpc214x_usbdev_s *priv, ubyte epphy,
reg = lpc214x_usbcmd(CMD_USB_EP_SELECT | epphy, 0);
- if (((epphy & 1) != 0 && (reg & 0x60) == 0) ||
- ((epphy & 1) == 0 && (reg & 0x60) == 0x60))
+ if ((LPC214X_EPPHYIN(epphy) && (reg & 0x60) == 0) ||
+ (LPC214X_EPPHYOUT(epphy) && (reg & 0x60) == 0x60))
{
/* DMA should be "being serviced" */
@@ -1948,8 +2049,8 @@ static void lpc214x_dmarestart(ubyte epphy, uint32 descndx)
/* Check the state of IN/OUT EP buffer */
uint32 reg = lpc214x_usbcmd(CMD_USB_EP_SELECT | epphy, 0);
- if (((epphy & 1) != 0 && (reg & 0x60) == 0) ||
- ((epphy & 1) == 0 && (reg & 0x60) == 0x60))
+ if ((LPC214X_EPPHYIN(epphy) && (reg & 0x60) == 0) ||
+ (LPC214X_EPPHYIN(epphy) && (reg & 0x60) == 0x60))
{
/* Re-trigger the DMA Transfer */
@@ -2213,7 +2314,7 @@ static int lpc214x_epsubmit(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s
/* Check for NULL packet */
flags = irqsave();
- if (req->len == 0 && (privep->in || privep->epphy == 3))
+ if (req->len == 0 && (LPC214X_EPPHYIN(privep->epphy)))
{
usbtrace(TRACE_DEVERROR(LPC214X_TRACEERR_NULLPACKET), 0);
sq_addlast(&privreq->sqe, &privep->reqlist);
@@ -2237,7 +2338,7 @@ static int lpc214x_epsubmit(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s
/* Handle IN requests */
- if ((privep->in) || privep->epphy == 3)
+ if (LPC214X_EPPHYIN(privep->epphy))
{
ret = lpc214x_wrrequest(privep);
}
@@ -2543,16 +2644,11 @@ static int lpc214x_pullup(struct usbdev_s *dev, boolean enable)
{
usbtrace(TRACE_DEVPULLUP, (uint16)enable);
- /* Prohibit interruption during connection command */
-
- irqstate_t flags = irqsave();
-
/* The USBDEV_DEVSTATUS_CONNECT bit in the CMD_USB_DEV_SETSTATUS command
* controls the LPC214x SoftConnect_N output pin that is used for SoftConnect.
*/
lpc214x_usbcmd(CMD_USB_DEV_SETSTATUS, (enable ? USBDEV_DEVSTATUS_CONNECT : 0));
- irqrestore(flags);
return OK;
}
@@ -2568,9 +2664,10 @@ static int lpc214x_pullup(struct usbdev_s *dev, boolean enable)
*
* Assumptions:
* - This function is called very early in the initialization sequence
- * - PLL initialization is not performed here but should been in the low-level
- * boot logic. For the USB engine, FUSB=FOSC*PLL_M. The USB device controller
- * clock is a 48MHz clock.
+ * - PLL and GIO pin initialization is not performed here but should been in
+ * the low-level boot logic: PLL1 must be configured for operation at 48MHz
+ * and P0.23 and PO.31 in PINSEL1 must be configured for Vbus and USB connect
+ * LED.
*
*******************************************************************************/
@@ -2578,27 +2675,62 @@ void up_usbinitialize(void)
{
struct lpc214x_usbdev_s *priv = &g_usbdev;
uint32 reg;
+ int i;
usbtrace(TRACE_DEVINIT, 0);
+ /* Disable USB inerrupts */
+
+ lpc214x_putreg(0, LPC214X_USBDEV_INTST);
+
/* Initialize the device state structure */
memset(priv, 0, sizeof(struct lpc214x_usbdev_s));
priv->usbdev.ops = &g_devops;
+ priv->usbdev.ep0 = &priv->eplist[LPC214X_EP0_IN].ep;
priv->wravail = LPC214X_EPALLSET;
+ /* Initialize the endpoint list */
+
+ for (i = 0; i < LPC214X_NPHYSENDPOINTS; i++)
+ {
+ uint32 bit = 1 << i;
+
+ /* Set endpoint operations, reference to driver structure (not
+ * really necessary because there is only one controller), and
+ * the physical endpoint number (which is just the index to the
+ * endpoint).
+ */
+ priv->eplist[i].ep.ops = &g_epops;
+ priv->eplist[i].dev = priv;
+ priv->eplist[i].epphy = i;
+
+ /* The maximum packet size may depend on the type of endpoint */
+
+ if ((LPC214X_EPCTRLSET & bit) != 0)
+ {
+ priv->eplist[i].ep.maxpacket = LPC214X_EP0MAXPACKET;
+ }
+ else if ((LPC214X_EPINTRSET & bit) != 0)
+ {
+ priv->eplist[i].ep.maxpacket = LPC214X_INTRMAXPACKET;
+ }
+ else if ((LPC214X_EPBULKSET & bit) != 0)
+ {
+ priv->eplist[i].ep.maxpacket = LPC214X_BULKMAXPACKET;
+ }
+ else /* if ((LPC214X_EPISOCSET & bit) != 0) */
+ {
+ priv->eplist[i].ep.maxpacket = LPC214X_ISOCMAXPACKET;
+ }
+ }
+
/* Turn on USB power and clocking */
reg = lpc214x_getreg(LPC214X_PCON_PCONP);
reg |= LPC214X_PCONP_PCUSB;
lpc214x_putreg(reg, LPC214X_PCON_PCONP);
- /* Enable Vbus sense and Connect */
-
- reg = lpc214x_getreg(LPC214X_PINSEL1);
- reg = (reg & LPC214X_USBDEV_PINMASK) | LPC214X_USBDEV_PINSEL;
- lpc214x_putreg(reg, LPC214X_PINSEL1);
-
/* Attach USB controller interrupt handler */
if (irq_attach(LPC214X_USB_IRQ, lpc214x_usbinterrupt) != 0)
@@ -2609,6 +2741,7 @@ void up_usbinitialize(void)
/* Enable USB inerrupts */
+ lpc214x_putreg(USBDEV_INTST_ENUSBINTS, LPC214X_USBDEV_INTST);
up_enable_irq(LPC214X_USB_IRQ);
/* Disconnect device */
@@ -2644,6 +2777,7 @@ void up_usbuninitialize(void)
irqstate_t flags;
usbtrace(TRACE_DEVUNINIT, 0);
+
if (priv->driver)
{
usbtrace(TRACE_DEVERROR(LPC214X_TRACEERR_DRIVERREGISTERED), 0);
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.h b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.h
index 97ceea9e9..55438799e 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.h
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.h
@@ -177,12 +177,6 @@
/* Device Status Bits */
-#define USBDEV_DEVSTATUS_CONNECT (0x00000001) /* Bit 0: Connected */
-#define USBDEV_DEVSTATUS_CONNCHG (0x00000002) /* Bit 1: Connect change */
-#define USBDEV_DEVSTATUS_SUSPEND (0x00000004) /* Bit 2: Suspend */
-#define USBDEV_DEVSTATUS_SUSPCHG (0x00000008) /* Bit 3: Suspend change */
-#define USBDEV_DEVSTATUS_RESET (0x00000002) /* Bit 4: Bus reset bit */
-
#define USBDEV_EPSTALL (0x00000001)
#define USBDEV_EPSTALLSTATUS (0x00000002)
#define USBDEV_EPSETUPPACKET (0x00000004)
@@ -269,15 +263,23 @@
/* Command Responses ***********************************************************/
+/* Device Status Bits (8-bits) */
+
+#define USBDEV_DEVSTATUS_CONNECT (0x01) /* Bit 0: Connected */
+#define USBDEV_DEVSTATUS_CONNCHG (0x02) /* Bit 1: Connect change */
+#define USBDEV_DEVSTATUS_SUSPEND (0x04) /* Bit 2: Suspend */
+#define USBDEV_DEVSTATUS_SUSPCHG (0x08) /* Bit 3: Suspend change */
+#define USBDEV_DEVSTATUS_RESET (0x10) /* Bit 4: Bus reset bit */
+
/* EP Select response */
-#define CMD_USB_EPSELECT_FE (0x01) /* Bit 0=1: IN empty or OUT full */
-#define CMD_USB_EPSELECT_ST (0x02) /* Bit 1=1: Endpoint is stalled */
-#define CMD_USB_EPSELECT_STP (0x04) /* Bit 2=1: Last packet was setup */
-#define CMD_USB_EPSELECT_PO (0x05) /* Bit 3=1: Previous packet was overwritten */
-#define CMD_USB_EPSELECT_EPN (0x10) /* Bit 4=1: NAK sent */
-#define CMD_USB_EPSELECT_B1FULL (0x20) /* Bit 5=1: Buffer 1 full */
-#define CMD_USB_EPSELECT_B2FULL (0x40) /* Bit 6=1: Buffer 2 full */
+#define CMD_USB_EPSELECT_FE (0x01) /* Bit 0=1: IN empty or OUT full */
+#define CMD_USB_EPSELECT_ST (0x02) /* Bit 1=1: Endpoint is stalled */
+#define CMD_USB_EPSELECT_STP (0x04) /* Bit 2=1: Last packet was setup */
+#define CMD_USB_EPSELECT_PO (0x05) /* Bit 3=1: Previous packet was overwritten */
+#define CMD_USB_EPSELECT_EPN (0x10) /* Bit 4=1: NAK sent */
+#define CMD_USB_EPSELECT_B1FULL (0x20) /* Bit 5=1: Buffer 1 full */
+#define CMD_USB_EPSELECT_B2FULL (0x40) /* Bit 6=1: Buffer 2 full */
/* EP CLRBUFFER response */
diff --git a/nuttx/configs/mcu123-lpc214x/include/board.h b/nuttx/configs/mcu123-lpc214x/include/board.h
index 080b06abe..e860cbb5e 100644
--- a/nuttx/configs/mcu123-lpc214x/include/board.h
+++ b/nuttx/configs/mcu123-lpc214x/include/board.h
@@ -50,12 +50,20 @@
/* Clocking *****************************************************************/
+/* Oscillator frequency */
+
#define LPC214X_FOSC 12000000
+
+/* PLL0 settings CCLK = PLL_M * FOSC PCLK = CCLK/APBDIV */
+
#define LPC214X_PLL_M 5
-#define LPC214X_MSEL (PLL_M-1)
#define LPC214X_PLL_P 2
+#define LPC214X_APB_DIV 1
+
+/* USB Pll settings -- 48 MHz needed. FUSB = PLL_M FOSC */
-#define LPC214X_PCLKFREQ (LPC214X_FOSC/4) /* PCLK must be FOSC/4 */
+#define LPC214X_USBPLL_M 4
+#define LPC214X_USBPLL_P 2
/* LED definitions **********************************************************/
diff --git a/nuttx/configs/mcu123-lpc214x/nsh/defconfig b/nuttx/configs/mcu123-lpc214x/nsh/defconfig
index 8c0cb137e..3dec91a3a 100644
--- a/nuttx/configs/mcu123-lpc214x/nsh/defconfig
+++ b/nuttx/configs/mcu123-lpc214x/nsh/defconfig
@@ -57,7 +57,7 @@ CONFIG_ARCH_CHIP=lpc214x
CONFIG_ARCH_LPC2148=y
CONFIG_ARCH_BOARD=mcu123-lpc214x
CONFIG_ARCH_BOARD_MCU123=y
-CONFIG_BOARD_LOOPSPERMSEC=4327
+CONFIG_BOARD_LOOPSPERMSEC=3270
CONFIG_ARCH_LEDS=y
CONFIG_DRAM_SIZE=0x00008000
CONFIG_DRAM_START=0x40000000
@@ -72,7 +72,7 @@ CONFIG_RAM_MODE=n
CONFIG_CODE_BASE=0x00000000
CONFIG_PLL_SETUP=y
CONFIG_MAM_SETUP=y
-CONFIG_VPBDIV_SETUP=y
+CONFIG_APBDIV_SETUP=y
CONFIG_EMC_SETUP=n
CONFIG_BCFG0_SETUP=n
CONFIG_BCFG1_SETUP=n
@@ -170,8 +170,8 @@ CONFIG_RR_INTERVAL=0
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
CONFIG_START_YEAR=2008
-CONFIG_START_MONTH=9
-CONFIG_START_DAY=17
+CONFIG_START_MONTH=10
+CONFIG_START_DAY=1
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
CONFIG_DEV_LOWCONSOLE=n
diff --git a/nuttx/configs/mcu123-lpc214x/ostest/defconfig b/nuttx/configs/mcu123-lpc214x/ostest/defconfig
index 1d284076b..4a1e38193 100644
--- a/nuttx/configs/mcu123-lpc214x/ostest/defconfig
+++ b/nuttx/configs/mcu123-lpc214x/ostest/defconfig
@@ -57,7 +57,7 @@ CONFIG_ARCH_CHIP=lpc214x
CONFIG_ARCH_LPC2148=y
CONFIG_ARCH_BOARD=mcu123-lpc214x
CONFIG_ARCH_BOARD_MCU123=y
-CONFIG_BOARD_LOOPSPERMSEC=4327
+CONFIG_BOARD_LOOPSPERMSEC=3270
CONFIG_ARCH_LEDS=y
CONFIG_DRAM_SIZE=0x00008000
CONFIG_DRAM_START=0x40000000
@@ -72,7 +72,7 @@ CONFIG_RAM_MODE=n
CONFIG_CODE_BASE=0x00000000
CONFIG_PLL_SETUP=y
CONFIG_MAM_SETUP=y
-CONFIG_VPBDIV_SETUP=y
+CONFIG_APBDIV_SETUP=y
CONFIG_EMC_SETUP=n
CONFIG_BCFG0_SETUP=n
CONFIG_BCFG1_SETUP=n
@@ -170,8 +170,8 @@ CONFIG_RR_INTERVAL=0
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
CONFIG_START_YEAR=2008
-CONFIG_START_MONTH=9
-CONFIG_START_DAY=17
+CONFIG_START_MONTH=10
+CONFIG_START_DAY=1
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
CONFIG_DEV_LOWCONSOLE=y
diff --git a/nuttx/include/nuttx/usbdev_trace.h b/nuttx/include/nuttx/usbdev_trace.h
index 9e57a2fe1..8a15b5c1b 100644
--- a/nuttx/include/nuttx/usbdev_trace.h
+++ b/nuttx/include/nuttx/usbdev_trace.h
@@ -47,9 +47,9 @@
* Preprocessor definitions
****************************************************************************/
-#define TRACE_EVENT(id,num) ((uint16)(id)|(num))
-#define TRACE_CLASS_ID(event) ((event)&0xff00)
-#define TRACE_INSTANCE(event) ((event)0x00ff)
+#define TRACE_EVENT(id,data) ((uint16)(id)|(data))
+#define TRACE_ID(event) ((event)&0xff00)
+#define TRACE_DATA(event) ((event)0x00ff)
/* Event class IDs */