summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h2
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h8
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h46
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h5
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_memorymap.h2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c8
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c127
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c15
-rw-r--r--nuttx/arch/arm/src/nuc1xx/Make.defs2
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_adc.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_clk.h283
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_cmp.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_ebi.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_gcr.h373
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h554
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_i2c.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_i2s.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_pdma.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_ps2d.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_pwm.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_rtc.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_spi.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_tmr.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_uart.h280
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_usbd.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_wdt.h71
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_config.h126
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_gpio.h64
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_start.c140
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_start.c14
-rw-r--r--nuttx/configs/lincoln60/include/board.h4
-rw-r--r--nuttx/configs/lpcxpresso-lpc1768/include/board.h4
-rw-r--r--nuttx/configs/mbed/include/board.h4
-rw-r--r--nuttx/configs/nucleus2g/include/board.h4
-rw-r--r--nuttx/configs/nutiny-nuc120/include/Makefile0
-rw-r--r--nuttx/configs/nutiny-nuc120/include/board.h40
-rw-r--r--nuttx/configs/nutiny-nuc120/src/Makefile116
-rw-r--r--nuttx/configs/nutiny-nuc120/src/nuc_boardinitialize.c102
-rw-r--r--nuttx/configs/nutiny-nuc120/src/nuc_led.c132
-rw-r--r--nuttx/configs/nutiny-nuc120/src/nutiny-nuc120.h116
-rw-r--r--nuttx/configs/olimex-lpc1766stk/include/board.h4
-rw-r--r--nuttx/configs/open1788/include/board.h69
-rwxr-xr-xnuttx/configs/open1788/scripts/ld.script137
44 files changed, 3490 insertions, 216 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h
index fb0c7c700..50f262237 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/lpc17xx/chip/lp176x_pinconfig.h
+ * arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h
*
* Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h
index ca4ab6b1d..11a94240c 100755
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_iocon.h
@@ -88,13 +88,13 @@
/* Register addresses ***************************************************************/
-#define LPC17_IOCON_P_BASE(b) (LPC17_IOCON_BASE + (unsigned int(b) << 7))
+#define LPC17_IOCON_P_BASE(b) (LPC17_IOCON_BASE + ((unsigned int)(b) << 7))
#define LPC17_IOCON_P0_BASE (LPC17_IOCON_BASE + 0x0000)
#define LPC17_IOCON_P1_BASE (LPC17_IOCON_BASE + 0x0080)
#define LPC17_IOCON_P2_BASE (LPC17_IOCON_BASE + 0x0100)
#define LPC17_IOCON_P3_BASE (LPC17_IOCON_BASE + 0x0180)
#define LPC17_IOCON_P4_BASE (LPC17_IOCON_BASE + 0x0200)
-#define LPC17_IOCON_P4_BASE (LPC17_IOCON_BASE + 0x0280)
+#define LPC17_IOCON_P5_BASE (LPC17_IOCON_BASE + 0x0280)
#define LPC17_IOCON_P(b,p) (LPC17_IOCON_P_BASE(b) + LPC17_IOCON_PP_OFFSET(p))
@@ -308,9 +308,9 @@
#define IOCON_FUNC_ALT6 (6)
#define IOCON_FUNC_ALT7 (7)
-#define IOCON_FUNC_SHIFT (0) /* Bits 0-2: All types */
+#define IOCON_FUNC_SHIFT (0) /* Bits 0-2: All types */
#define IOCON_FUNC_MASK (7 << IOCON_FUNC_SHIFT)
-#define IOCON_MODE_SHIFT (3) /* Bits 3-4: Type D,A,W */
+#define IOCON_MODE_SHIFT (3) /* Bits 3-4: Type D,A,W */
#define IOCON_MODE_MASK (3 << IOCON_MODE_SHIFT )
#define IOCON_HYS_SHIFT (5) /* Bit 5: Type D,W */
#define IOCON_HYS_MASK (1 << IOCON_HYS_SHIFT)
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
index 887aa0a9f..8afb1eedc 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/lpc17xx/chip/lp178x_pinconfig.h
+ * arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Authors: Rommel Marcelo
@@ -144,21 +144,21 @@
#define GPIO_SPIFI_IO0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
#define GPIO_UART1_DSR_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN19)
-#define GPIO_SD_CLK (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN19)
+#define GPIO_SD_CLK_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN19)
#define GPIO_I2C1_SDA_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN19)
#define GPIO_UART1_DTR_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN20)
-#define GPIO_SD_CMD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN20)
+#define GPIO_SD_CMD_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN20)
#define GPIO_I2C1_SCL_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN20)
#define GPIO_UART1_RI_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
-#define GPIO_SD_PWR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
+#define GPIO_SD_PWR_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
#define GPIO_UART4_OE_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
#define GPIO_CAN1_RD_2 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
#define GPIO_UART4_SCLK (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
#define GPIO_UART1_RTS_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
-#define GPIO_SD_DAT0 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
+#define GPIO_SD_DAT0_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
#define GPIO_UART4_TXD_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
#define GPIO_CAN1_TD_2 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
#define GPIO_SPIFI_SCLK (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
@@ -186,10 +186,10 @@
#define GPIO_USB_SCL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN28)
#define GPIO_USB1DP (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN29)
-#define GPIO_EINT0 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN29)
+#define GPIO_EINT0_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN29)
#define GPIO_USB1DM (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN30)
-#define GPIO_EINT1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN30)
+#define GPIO_EINT1_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN30)
#define GPIO_USB2_DP (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN31)
@@ -202,11 +202,11 @@
#define GPIO_SSP2_MOSI (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN1)
#define GPIO_ENET_TXD2 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN2)
-#define GPIO_SD_CLK (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN2)
+#define GPIO_SD_CLK_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN2)
#define GPIO_PWM0p1_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN2)
#define GPIO_ENET_TXD3 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN3)
-#define GPIO_SD_CMD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN3)
+#define GPIO_SD_CMD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN3)
#define GPIO_PWM0p2_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN3)
#define GPIO_ENET_TXEN (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN4)
@@ -214,15 +214,15 @@
#define GPIO_SSP2_MISO (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN4)
#define GPIO_ENET_TX_ER (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN5)
-#define GPIO_SD_PWR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN5)
+#define GPIO_SD_PWR_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN5)
#define GPIO_PWM0p3_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN5)
#define GPIO_ENET_TX_CLK (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN6)
-#define GPIO_SD_DAT0 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN6)
+#define GPIO_SD_DAT0_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN6)
#define GPIO_PWM0p4_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN6)
#define GPIO_ENET_COL (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN7)
-#define GPIO_SD_DAT1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN7)
+#define GPIO_SD_DAT1_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN7)
#define GPIO_PWM0p5_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN7)
#define GPIO_ENET_CRSDV (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN8)
@@ -236,11 +236,11 @@
#define GPIO_CAP3p0_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN10)
#define GPIO_ENET_RXD2 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN11)
-#define GPIO_SD_DAT2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN11)
+#define GPIO_SD_DAT2_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN11)
#define GPIO_PWM0p6_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN11)
#define GPIO_ENET_RXD3 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN12)
-#define GPIO_SD_DAT3 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN12)
+#define GPIO_SD_DAT3_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN12)
#define GPIO_PWM0CAPp0_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN12)
#define GPIO_ENET_RX_DV (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN13)
@@ -335,7 +335,7 @@
#define GPIO_PCAP1p0_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
#define GPIO_MAT0p0_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
#define GPIO_MCPWM_MC2A (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
-#define GPIO_SSP0_SSEL_2 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
+#define GPIO_SSP0_SSEL_3 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
#define GPIO_LCD_VD14 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
#define GPIO_LCD_VD22 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
@@ -399,7 +399,7 @@
#define GPIO_LCD_VD4_1 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN6)
#define GPIO_CAN2_RD_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
-#define GPIO_UART1_RTS_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
+#define GPIO_UART1_RTS_3 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
#define GPIO_SPIFI_CS (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
#define GPIO_LCD_VD1_2 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
#define GPIO_LCD_VD5_1 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
@@ -418,16 +418,16 @@
#define GPIO_LCD_VD3_1 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
#define GPIO_LCD_VD7 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
-#define GPIO_EINT0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN10)
+#define GPIO_EINT0_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN10)
#define GPIO_NMI (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN10)
-#define GPIO_EINT1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
-#define GPIO_SD_DAT1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
+#define GPIO_EINT1_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
+#define GPIO_SD_DAT1_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
#define GPIO_I2S_TXCLK_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
#define GPIO_LCD_CLKIN (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
#define GPIO_EINT2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
-#define GPIO_SD_DAT2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define GPIO_SD_DAT2_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
#define GPIO_I2S_TXWS_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
#define GPIO_LCD_VD4_2 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
#define GPIO_LCD_VD3_2 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
@@ -435,7 +435,7 @@
#define GPIO_LCD_VD18 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
#define GPIO_EINT3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
-#define GPIO_SD_DAT3 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+#define GPIO_SD_DAT3_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
#define GPIO_I2S_TXSDA_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
#define GPIO_LCD_VD5_2 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
#define GPIO_LCD_VD9_3 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
@@ -462,7 +462,7 @@
#define GPIO_CAP3p0_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN22)
#define GPIO_EMC_DYCS3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN23)
-#define GPIO_SSP0_SSEL_3 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN23)
+#define GPIO_SSP0_SSEL_4 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN23)
#define GPIO_CAP3p1_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN23)
#define GPIO_EMC_CKE0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN24)
@@ -562,7 +562,7 @@
#define GPIO_MAT1p0_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN29)
#define GPIO_EMC_D30 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN30)
-#define GPIO_UART1_RTS_3 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN30)
+#define GPIO_UART1_RTS_4 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN30)
#define GPIO_MAT1p1_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN30)
#define GPIO_EMC_D31 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN31)
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h
index 7a30794d6..54530bdfa 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h
@@ -324,7 +324,7 @@
#define SYSCON_PCLKSEL_PCLKDIV_SHIFT (0) /* Bits 0-4: Clock divide value for all APB peripherals */
#define SYSCON_PCLKSEL_PCLKDIV_MASK (0x1f << SYSCON_PCLKSEL_PCLKDIV_SHIFT)
-# define SYSCON_PCLKSEL_PCLKDIV(n) ((n-1) << SYSCON_PCLKSEL_PCLKDIV_SHIFT) /* n = 2 - 31 */
+# define SYSCON_PCLKSEL_PCLKDIV(n) ((n) & SYSCON_PCLKSEL_PCLKDIV_MASK) /* n = 1 - 31 */
/* Bits 5-31: Reserved */
/* Power Boost Control Register */
@@ -589,6 +589,9 @@
#define SYSCON_PLL0STAT_PLLE SYSCON_PLLSTAT_PLLE /* PLL enable readback */
#define SYSCON_PLL0STAT_PLLC SYSCON_PLLSTAT_PLLC /* PLL connect readback */
#define SYSCON_PLL0STAT_PLOCK SYSCON_PLLSTAT_PLOCK /* PLL lock status */
+#define SYSCON_PLL1STAT_PLLE SYSCON_PLLSTAT_PLLE /* PLL enable readback */
+#define SYSCON_PLL1STAT_PLLC SYSCON_PLLSTAT_PLLC /* PLL connect readback */
+#define SYSCON_PLL1STAT_PLOCK SYSCON_PLLSTAT_PLOCK /* PLL lock status */
/****************************************************************************************************
* Public Types
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_memorymap.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_memorymap.h
index d3bdf79ab..ef720ae59 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_memorymap.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_memorymap.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/lpc17xx/chip/lp17_memorymap.h
+ * arch/arm/src/lpc17xx/chip/lpc17_memorymap.h
*
* Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h
index fb4a487c2..e90b425a9 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/lpc17xx/chip/lp17_pinconfig.h
+ * arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h
*
* Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c b/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c
index aba2079e4..6e46d3241 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c
@@ -2,7 +2,7 @@
* arch/arm/src/lpc17xx/lpc17_clockconfig.c
* arch/arm/src/chip/lpc17_clockconfig.c
*
- * Copyright (C) 2010 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
@@ -186,8 +186,12 @@ void lpc17_clockconfig(void)
* when the device driver is initialized.
*/
+# if defined(LPC176x)
putreg32(0, LPC17_SYSCON_PCLKSEL0);
putreg32(0, LPC17_SYSCON_PCLKSEL1);
+# elif defined(LPC178x)
+ putreg32(0, LPC17_SYSCON_PCLKSEL);
+# endif
/* Disable power to all peripherals (execpt GPIO). Peripherals must be re-powered
* one at a time by each device driver when the driver is initialized.
@@ -201,7 +205,7 @@ void lpc17_clockconfig(void)
/* Configure FLASH */
-#ifdef CONFIG_LP17_FLASH
+#ifdef CONFIG_LPC17_FLASH
putreg32(BOARD_FLASHCFG_VALUE, LPC17_SYSCON_FLASHCFG);
#endif
}
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
index 8ae8fe6e7..a94eaf999 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
@@ -115,6 +115,7 @@ const uint32_t g_intbase[GPIO_NPORTS] =
#endif
};
+#ifdef LPC176x
const uint32_t g_lopinsel[GPIO_NPORTS] =
{
LPC17_PINCONN_PINSEL0,
@@ -174,6 +175,7 @@ const uint32_t g_odmode[GPIO_NPORTS] =
, 0
#endif
};
+#endif /* LPC176x */
/****************************************************************************
* Private Functions
@@ -199,41 +201,85 @@ static int lpc17_configiocon(unsigned int port, unsigned int pin,
{
uint32_t regaddr;
uint32_t regval;
- uint32_t typemask
-
- /* Select the mask based on pin usage */
-
- if (port == 0 && (pin==7 || pin==8 || pin==9))
- {
- typemask = GPIO_IOCON_TYPE_W_MASK;
- }
- else if ((port == 0 && (pin==27 || pin==28)) ||
- (port == 5 && (pin==2 || pin==3)))
- {
- typemask = GPIO_IOCON_TYPE_I_MASK;
- }
- else if (port == 0 && (pin==29 || pin==30 || pin==31))
- {
- typemask = GPIO_IOCON_TYPE_U_MASK;
- }
- else if ((port == 0 && (pin==12 || pin==13 || pin==23 ||
- pin==24 || pin==25 || pin==26)) ||
- (port == 1 && (pin==30 || pin==31)))
- {
- typemask = GPIO_IOCON_TYPE_A_MASK;
- }
- else
- {
- typemask = GPIO_IOCON_TYPE_D_MASK;
- }
+ uint32_t typemask = GPIO_IOCON_TYPE_D_MASK;
+
+ /* Select the mask based on pin usage */
+
+ switch (port)
+ {
+ case 0:
+ switch (pin)
+ {
+ case 7:
+ case 8:
+ case 9:
+ typemask = GPIO_IOCON_TYPE_W_MASK;
+ break;
+
+ case 12:
+ case 13:
+ case 23:
+ case 24:
+ case 25:
+ case 26:
+ typemask = GPIO_IOCON_TYPE_A_MASK;
+ break;
+
+ case 27:
+ case 28:
+ typemask = GPIO_IOCON_TYPE_I_MASK;
+ break;
+
+ case 29:
+ case 30:
+ case 31:
+ typemask = GPIO_IOCON_TYPE_U_MASK;
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case 1:
+ switch (pin)
+ {
+ case 30:
+ case 31:
+ typemask = GPIO_IOCON_TYPE_A_MASK;
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case 5:
+ switch (pin)
+ {
+ case 2:
+ case 3:
+ typemask = GPIO_IOCON_TYPE_I_MASK;
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ default:
+ break;
+ }
regaddr = LPC17_IOCON_P(port, pin);
regval = getreg32(regaddr);
regval &= value;
regval &= ~typemask;
putreg32(regval, regaddr);
+
+ return OK;
}
-#endif
+#endif /* LPC178x */
/****************************************************************************
* Name: lpc17_pinsel
@@ -244,6 +290,7 @@ static int lpc17_configiocon(unsigned int port, unsigned int pin,
*
****************************************************************************/
+#ifdef LPC176x
static int lpc17_pinsel(unsigned int port, unsigned int pin, unsigned int value)
{
const uint32_t *table;
@@ -290,7 +337,8 @@ static int lpc17_pinsel(unsigned int port, unsigned int pin, unsigned int value)
*
****************************************************************************/
-static int lpc17_pullup(lpc17_pinset_t cfgset, unsigned int port, unsigned int pin)
+static int lpc17_pullup(lpc17_pinset_t cfgset, unsigned int port,
+ unsigned int pin)
{
const uint32_t *table;
uint32_t regaddr;
@@ -347,6 +395,7 @@ static int lpc17_pullup(lpc17_pinset_t cfgset, unsigned int port, unsigned int p
return -EINVAL;
}
+#endif /* LPC176x */
/****************************************************************************
* Name: lpc17_setintedge
@@ -385,7 +434,7 @@ static void lpc17_setintedge(unsigned int port, unsigned int pin,
*intedge &= ~((uint64_t)3 << shift);
*intedge |= ((uint64_t)value << shift);
}
-#endif
+#endif /* CONFIG_GPIO_IRQ */
/****************************************************************************
* Name: lpc17_setopendrain
@@ -395,6 +444,7 @@ static void lpc17_setintedge(unsigned int port, unsigned int pin,
*
****************************************************************************/
+#ifdef LPC176x
static void lpc17_setopendrain(unsigned int port, unsigned int pin)
{
uint32_t regaddr;
@@ -424,6 +474,7 @@ static void lpc17_clropendrain(unsigned int port, unsigned int pin)
regval &= ~(1 << pin);
putreg32(regval, regaddr);
}
+#endif /* LPC176x */
/****************************************************************************
* Name: lpc17_configinput
@@ -726,6 +777,8 @@ int lpc17_configgpio(lpc17_pinset_t cfgset)
ret = lpc17_configoutput(cfgset, port, pin);
break;
+#if defined(LPC176x)
+
case GPIO_ALT1: /* Alternate function 1 */
ret = lpc17_configalternate(cfgset, port, pin, PINCONN_PINSEL_ALT1);
break;
@@ -738,7 +791,19 @@ int lpc17_configgpio(lpc17_pinset_t cfgset)
ret = lpc17_configalternate(cfgset, port, pin, PINCONN_PINSEL_ALT3);
break;
-#ifdef LPC178x
+#elif defined(LPC178x)
+
+ case GPIO_ALT1: /* Alternate function 1 */
+ ret = lpc17_configalternate(cfgset, port, pin, IOCON_FUNC_ALT1);
+ break;
+
+ case GPIO_ALT2: /* Alternate function 2 */
+ ret = lpc17_configalternate(cfgset, port, pin, IOCON_FUNC_ALT2);
+ break;
+
+ case GPIO_ALT3: /* Alternate function 3 */
+ ret = lpc17_configalternate(cfgset, port, pin, IOCON_FUNC_ALT3);
+ break;
case GPIO_ALT4: /* Alternate function 4 */
ret = lpc17_configalternate(cfgset, port, pin, IOCON_FUNC_ALT4);
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c b/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c
index 5c34bda1b..b41cbe0bd 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c
@@ -1,7 +1,7 @@
/**************************************************************************
* arch/arm/src/lpc17xx/lpc17_lowputc.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
@@ -57,7 +57,7 @@
/**************************************************************************
* Private Definitions
**************************************************************************/
-
+
/* Select UART parameters for the selected console */
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
@@ -189,7 +189,7 @@
* And
*
* 4 * CCLK / BAUD / 16 >= MinDL, or
- * BAUD <= CCLK / 4 / MinDL
+ * BAUD <= CCLK / 4 / MinDL
*/
#elif CONSOLE_BAUD < (LPC17_CCLK / 4 / UART_MINDL)
@@ -204,7 +204,7 @@
* And
*
* 8 * CCLK / BAUD / 16 >= MinDL, or
- * BAUD <= CCLK / 2 / MinDL
+ * BAUD <= CCLK / 2 / MinDL
*/
#else /* if CONSOLE_BAUD < (LPC17_CCLK / 2 / UART_MINDL) */
@@ -277,7 +277,7 @@ void up_lowputc(char ch)
* PCLK_UART1; in the PCLKSEL1 register, select PCLK_UART2 and PCLK_UART3.
* 3. Baud rate: In the LCR register, set bit DLAB = 1. This enables access
* to registers DLL and DLM for setting the baud rate. Also, if needed,
- * set the fractional baud rate in the fractional divider
+ * set the fractional baud rate in the fractional divider.
* 4. UART FIFO: Use bit FIFO enable (bit 0) in FCR register to
* enable FIFO.
* 5. Pins: Select UART pins through the PINSEL registers and pin modes
@@ -318,6 +318,7 @@ void lpc17_lowsetup(void)
* clocking for all other UARTs
*/
+#if defined(LPC176x)
regval = getreg32(LPC17_SYSCON_PCLKSEL0);
regval &= ~(SYSCON_PCLKSEL0_UART0_MASK|SYSCON_PCLKSEL0_UART1_MASK);
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
@@ -336,6 +337,10 @@ void lpc17_lowsetup(void)
#endif
putreg32(regval, LPC17_SYSCON_PCLKSEL1);
+#elif defined(LPC178x)
+ putreg32(LPC17_PCLKDIV, LPC17_SYSCON_PCLKSEL);
+#endif
+
/* Configure UART pins for the selected CONSOLE */
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
diff --git a/nuttx/arch/arm/src/nuc1xx/Make.defs b/nuttx/arch/arm/src/nuc1xx/Make.defs
index 37387b857..38f5b3f6a 100644
--- a/nuttx/arch/arm/src/nuc1xx/Make.defs
+++ b/nuttx/arch/arm/src/nuc1xx/Make.defs
@@ -56,4 +56,4 @@ CMN_CSRCS += up_elf.c
endif
CHIP_ASRCS =
-CHIP_CSRCS =
+CHIP_CSRCS = nuc_start.c
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_adc.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_adc.h
new file mode 100644
index 000000000..cea74a0fd
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_adc.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_adc.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_ADC_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_ADC_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_ADC_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_clk.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_clk.h
new file mode 100644
index 000000000..17814a467
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_clk.h
@@ -0,0 +1,283 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_clk.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_CLK_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_CLK_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+#define NUC_CLK_PWRCON_OFFSET 0x0000 /* System power down control register */
+#define NUC_CLK_AHBCLK_OFFSET 0x0004 /* AHB devices clock enable control register */
+#define NUC_CLK_APBCLK_OFFSET 0x0008 /* APB devices clock enable control register */
+#define NUC_CLK_CLKSTATUS_OFFSET 0x000c /* Clock status monitor register */
+#define NUC_CLK_CLKSEL0_OFFSET 0x0010 /* Clock source select control register 0 */
+#define NUC_CLK_CLKSEL1_OFFSET 0x0014 /* Clock source select control register 1 */
+#define NUC_CLK_CLKSEL2_OFFSET 0x001c /* Clock source select control register 2 */
+#define NUC_CLK_CLKDIV_OFFSET 0x0018 /* Clock divider number register */
+#define NUC_CLK_PLLCON_OFFSET 0x0020 /* PLL control register */
+#define NUC_CLK_FRQDIV_OFFSET 0x0024 /* Frequency divider control register */
+
+/* Register addresses ***********************************************************************/
+
+#define NUC_CLK_PWRCON (NUC_CLK_BASE+NUC_CLK_PWRCON_OFFSET)
+#define NUC_CLK_AHBCLK (NUC_CLK_BASE+NUC_CLK_AHBCLK_OFFSET)
+#define NUC_CLK_APBCLK (NUC_CLK_BASE+NUC_CLK_APBCLK_OFFSET)
+#define NUC_CLK_CLKSTATUS (NUC_CLK_BASE+NUC_CLK_CLKSTATUS_OFFSET)
+#define NUC_CLK_CLKSEL0 (NUC_CLK_BASE+NUC_CLK_CLKSEL0_OFFSET)
+#define NUC_CLK_CLKSEL1 (NUC_CLK_BASE+NUC_CLK_CLKSEL1_OFFSET)
+#define NUC_CLK_CLKSEL2 (NUC_CLK_BASE+NUC_CLK_CLKSEL2_OFFSET)
+#define NUC_CLK_CLKDIV (NUC_CLK_BASE+NUC_CLK_CLKDIV_OFFSET)
+#define NUC_CLK_PLLCON (NUC_CLK_BASE+NUC_CLK_PLLCON_OFFSET)
+#define NUC_CLK_FRQDIV (NUC_CLK_BASE+NUC_CLK_FRQDIV_OFFSET)
+
+/* Register bit-field definitions ***********************************************************/
+
+/* System power down control register */
+
+#define CLK_PWRCON_XTL12M_EN (1 << 0) /* Bit 0: External 4~24 mhz high speed crystal enable */
+#define CLK_PWRCON_XTL32K_EN (1 << 1) /* Bit 1: External 32.768 khz low speed crystal enable */
+#define CLK_PWRCON_OSC22M_EN (1 << 2) /* Bit 2: Internal 22.1184 MHz high speed oscillator enable */
+#define CLK_PWRCON_OSC10K_EN (1 << 3) /* Bit 3: Internal 10KHz low speed oscillator enable */
+#define CLK_PWRCON_PD_WU_DLY (1 << 4) /* Bit 4: Enable the wake-up delay counter */
+#define CLK_PWRCON_PD_WU_INT_EN (1 << 5) /* Bit 5: Power down mode wake-up interrupt status */
+#define CLK_PWRCON_PD_WU_STS (1 << 6) /* Bit 6: Power down mode wake-up interupt status */
+#define CLK_PWRCON_PWR_DOWN_EN (1 << 7) /* Bit 7: System power down enable bit */
+#define CLK_PWRCON_PD_WAIT_CPU (1 << 8) /* Bit 8: Power down entry condition */
+
+/* AHB devices clock enable control register */
+
+#define CLK_AHBCLK_PDMA_EN (1 << 1) /* Bit 1: PDMA acontroller clock enable control */
+#define CLK_AHBCLK_ISP_EN (1 << 2) /* Bit 2: FLASH ISPO controller clock enable control */
+#define CLK_AHBCLK_EBI_EN (1 << 3) /* Bit 3: EBI controller clock enable control */
+
+/* APB devices clock enable control register */
+
+#define CLK_APBCLK_WDT_EN (1 << 0) /* Bit 0: Watchdog time clock enable */
+#define CLK_APBCLK_RTC_EN (1 << 1) /* Bit 1: Real time clock clock enable */
+#define CLK_APBCLK_TMR0_EN (1 << 2) /* Bit 2: Timer0 clock enable */
+#define CLK_APBCLK_TMR1_EN (1 << 3) /* Bit 3: Timer1 clock enable */
+#define CLK_APBCLK_TMR2_EN (1 << 4) /* Bit 4: Timer2 clock enable */
+#define CLK_APBCLK_TMR3_EN (1 << 5) /* Bit 5: Timer3 clock enable */
+#define CLK_APBCLK_FDIV_EN (1 << 6) /* Bit 6: Frequency divider output clock enable */
+#define CLK_APBCLK_I2C0_EN (1 << 8) /* Bit 8: I2C0 clock enable */
+#define CLK_APBCLK_I2C1_EN (1 << 9) /* Bit 9: I2C1 clock enable */
+#define CLK_APBCLK_SPI0_EN (1 << 12) /* Bit 12: SPI0 clock enable */
+#define CLK_APBCLK_SPI1_EN (1 << 13) /* Bit 13: SPI1 clock enable */
+#define CLK_APBCLK_SPI2_EN (1 << 14) /* Bit 14: SPI2 clock enable */
+#define CLK_APBCLK_SPI3_EN (1 << 15) /* Bit 15: SPI3 clock enable */
+#define CLK_APBCLK_UART0_EN (1 << 16) /* Bit 16: UART0 clock enable */
+#define CLK_APBCLK_UART1_EN (1 << 17) /* Bit 17: UART1 clock enable */
+#define CLK_APBCLK_UART2_EN (1 << 18) /* Bit 18: UART2 clock enable */
+#define CLK_APBCLK_PWM01_EN (1 << 20) /* Bit 20: PWM_01 clock enable */
+#define CLK_APBCLK_PWM23_EN (1 << 21) /* Bit 21: PWM_23 clock enable */
+#define CLK_APBCLK_PWM45_EN (1 << 22) /* Bit 22: PWM_45 clock enable */
+#define CLK_APBCLK_PWM67_EN (1 << 23) /* Bit 23: PWM_67 clock enable */
+#define CLK_APBCLK_USBD_EN (1 << 27) /* Bit 27: USB 2.0 FS device controller clock enable */
+#define CLK_APBCLK_ADC_EN (1 << 28) /* Bit 28: Analog-digital-converter clock enable */
+#define CLK_APBCLK_I2S_EN (1 << 29) /* Bit 29: I2S clock enable */
+#define CLK_APBCLK_ACMP_EN (1 << 30) /* Bit 30: Analog comparator clock enable */
+#define CLK_APBCLK_PS2_EN (1 << 31) /* Bit 31: PS/2 clock enable */
+
+/* Clock status monitor register */
+
+#define CLK_CLKSTATUS_XTL12M_STB (1 << 0) /* Bit 0: External 4~24 mhz high speed crystal
+ * clock source stable flag */
+#define CLK_CLKSTATUS_STL32K_STB (1 << 1) /* Bit 1: External 32.768 kHz low speed crystal
+ * clock source stable flag */
+#define CLK_CLKSTATUS_PLL_STB (1 << 2) /* Bit 2: Internal PLL clock source stable flag */
+#define CLK_CLKSTATUS_OSC10K_STB (1 << 3) /* Bit 3: Internal 10kHz low speed clock source
+ * stable flag */
+#define CLK_CLKSTATUS_OSC22M_STB (1 << 4) /* Bit 4: Internal 22.1184MHz high speed
+ * osciallator clock source stable flag */
+#define CLK_CLKSTATUS_CLK_SW_FAIL (1 << 7) /* Bit 7: Clock switching fail flag */
+
+/* Clock source select control register 0 */
+
+#define CLK_CLKSEL0_HCLK_S_SHIFT (0) /* Bits 0-2: HCLK clock source select */
+#define CLK_CLKSEL0_HCLK_S_MASK (7 << CLK_CLKSEL0_HCLK_S_SHIFT)
+# define CLK_CLKSEL0_HCLK_S_XTALHI (0 << CLK_CLKSEL0_HCLK_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL0_HCLK_S_XTALLO (1 << CLK_CLKSEL0_HCLK_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL0_HCLK_S_PLL (2 << CLK_CLKSEL0_HCLK_S_SHIFT) /* PLL clock */
+# define CLK_CLKSEL0_HCLK_S_INTLO (3 << CLK_CLKSEL0_HCLK_S_SHIFT) /* Internal low speed clock */
+# define CLK_CLKSEL0_HCLK_S_INTHI (7 << CLK_CLKSEL0_HCLK_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL0_STCLK_S_SHIFT (3) /* Bits 3-5: Cortex M0 Systick clock source select */
+#define CLK_CLKSEL0_STCLK_S_MASK (7 << CLK_CLKSEL0_STCLK_S_SHIFT)
+# define CLK_CLKSEL0_STCLK_S_XTALHI (0 << CLK_CLKSEL0_STCLK_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL0_STCLK_S_XTALLO (1 << CLK_CLKSEL0_STCLK_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL0_STCLK_S_XTALDIV2 (2 << CLK_CLKSEL0_STCLK_S_SHIFT) /* High speed XTAL clock/2 */
+# define CLK_CLKSEL0_STCLK_S_HCLKDIV2 (3 << CLK_CLKSEL0_STCLK_S_SHIFT) /* HCLK/2 */
+# define CLK_CLKSEL0_STCLK_S_INTDIV2 (7 << CLK_CLKSEL0_STCLK_S_SHIFT) /* Internal high speed clock/2 */
+
+/* Clock source select control register 1 */
+
+#define CLK_CLKSEL1_WDT_S_SHIFT (0) /* Bits 0-1: Watchdog timer clock source select */
+#define CLK_CLKSEL1_WDT_S_MASK (3 << CLK_CLKSEL1_WDT_S_SHIFT)
+# define CLK_CLKSEL1_ADC_S_HCLKDIV (2 << CLK_CLKSEL1_WDT_S_SHIFT) /* HCLK / 2048 */
+# define CLK_CLKSEL1_ADC_S_INTLO (3 << CLK_CLKSEL1_WDT_S_SHIFT) /* Internal low speed clock */
+#define CLK_CLKSEL1_ADC_S_SHIFT (2) /* Bits 2-3: ADC clock source select */
+#define CLK_CLKSEL1_ADC_S_MASK (3 << CLK_CLKSEL1_ADC_S_SHIFT)
+# define CLK_CLKSEL1_ADC_S_XTALHI (0 << CLK_CLKSEL1_ADC_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_ADC_S_PLL (1 << CLK_CLKSEL1_ADC_S_SHIFT) /* PLL */
+# define CLK_CLKSEL1_ADC_S_INTHI (3 << CLK_CLKSEL1_ADC_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_TMR0_S_SHIFT (8) /* Bits 8-10: Timer0 clock source select */
+#define CLK_CLKSEL1_TMR0_S_MASK (7 << CLK_CLKSEL1_TMR0_S_SHIFT)
+# define CLK_CLKSEL1_TMR0_S_XTALHI (0 << CLK_CLKSEL1_TMR0_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_TMR0_S_XTALLO (1 << CLK_CLKSEL1_TMR0_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_TMR0_S_HCLK (2 << CLK_CLKSEL1_TMR0_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_TMR0_S_INTHI (7 << CLK_CLKSEL1_TMR0_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_TMR1_S_SHIFT (12) /* Bits 12-14: Timer1 clock source select */
+#define CLK_CLKSEL1_TMR1_S_MASK (7 << CLK_CLKSEL1_TMR1_S_SHIFT)
+# define CLK_CLKSEL1_TMR1_S_XTALHI (0 << CLK_CLKSEL1_TMR1_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_TMR1_S_XTALLO (1 << CLK_CLKSEL1_TMR1_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_TMR1_S_HCLK (2 << CLK_CLKSEL1_TMR1_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_TMR1_S_INTHI (7 << CLK_CLKSEL1_TMR1_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_TMR2_S_SHIFT (16) /* Bits 16-18: Timer2 clock source select */
+#define CLK_CLKSEL1_TMR2_S_MASK (7 << CLK_CLKSEL1_TMR2_S_SHIFT)
+# define CLK_CLKSEL1_TMR2_S_XTALHI (0 << CLK_CLKSEL1_TMR2_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_TMR2_S_XTALLO (1 << CLK_CLKSEL1_TMR2_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_TMR2_S_HCLK (2 << CLK_CLKSEL1_TMR2_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_TMR2_S_INTHI (7 << CLK_CLKSEL1_TMR2_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_TMR3_S_SHIFT (20) /* Bits 20-22: Timer3 clock source select */
+#define CLK_CLKSEL1_TMR3_S_MASK (7 << CLK_CLKSEL1_TMR3_S_SHIFT)
+# define CLK_CLKSEL1_TMR3_S_XTALHI (0 << CLK_CLKSEL1_TMR3_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_TMR3_S_XTALLO (1 << CLK_CLKSEL1_TMR3_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_TMR3_S_HCLK (2 << CLK_CLKSEL1_TMR3_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_TMR3_S_INTHI (7 << CLK_CLKSEL1_TMR3_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_UART_S_SHIFT (24) /* Bits 24-25: UART clock source select */
+#define CLK_CLKSEL1_UART_S_MASK (3 << CLK_CLKSEL1_UART_S_SHIFT)
+# define CLK_CLKSEL1_UART_S_XTALHI (0 << CLK_CLKSEL1_UART_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_UART_S_PLL (1 << CLK_CLKSEL1_UART_S_SHIFT) /* PLL */
+# define CLK_CLKSEL1_UART_S_INTHI (3 << CLK_CLKSEL1_UART_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_PWM01_S_SHIFT (28) /* Bits 28-29: PWM0 and PWM1 clock source select */
+#define CLK_CLKSEL1_PWM01_S_MASK (3 << CLK_CLKSEL1_PWM01_S_SHIFT)
+# define CLK_CLKSEL1_PWM01_S_XTALHI (0 << CLK_CLKSEL1_PWM01_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_PWM01_S_XTALLO (1 << CLK_CLKSEL1_PWM01_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_PWM01_S_HCLK (2 << CLK_CLKSEL1_PWM01_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_PWM01_S_INTHI (3 << CLK_CLKSEL1_PWM01_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL1_PWM23_S_SHIFT (30) /* Bits 30-31: PWM2 and PWM3 clock source select */
+#define CLK_CLKSEL1_PWM23_S_MASK (3 << CLK_CLKSEL1_PWM23_S_SHIFT)
+# define CLK_CLKSEL1_PWM23_S_XTALHI (0 << CLK_CLKSEL1_PWM23_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_PWM23_S_XTALLO (1 << CLK_CLKSEL1_PWM23_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_PWM23_S_HCLK (2 << CLK_CLKSEL1_PWM23_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_PWM23_S_INTHI (3 << CLK_CLKSEL1_PWM23_S_SHIFT) /* Internal high speed clock */
+
+/* Clock source select control register 2 */
+
+#define CLK_CLKSEL2_I2S_S_SHIFT (0) /* Bits 0-1: I2S clock source select */
+#define CLK_CLKSEL2_I2S_S_MASK (3 << CLK_CLKSEL2_I2S_S_SHIFT)
+# define CLK_CLKSEL1_I2S_S_XTALHI (0 << CLK_CLKSEL2_I2S_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_I2S_S_XTALLO (1 << CLK_CLKSEL2_I2S_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_I2S_S_HCLK (2 << CLK_CLKSEL2_I2S_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_I2S_S_INTHI (3 << CLK_CLKSEL2_I2S_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL2_FRQDIV_S_SHIFT (2) /* Bits 2-3: Frequency divider clock source select */
+#define CLK_CLKSEL2_FRQDIV_S_MASK (3 << CLK_CLKSEL2_FRQDIV_S_SHIFT)
+# define CLK_CLKSEL1_FRQDIV_S_XTALHI (0 << CLK_CLKSEL2_FRQDIV_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_FRQDIV_S_XTALLO (1 << CLK_CLKSEL2_FRQDIV_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_FRQDIV_S_HCLK (2 << CLK_CLKSEL2_FRQDIV_S_SHIFT) /* HCLK */
+#define CLK_CLKSEL2_PWM45_S_SHIFT (4) /* Bits 4-5: PWM4 and PWM5 clock source select */
+#define CLK_CLKSEL2_PWM45_S_MASK (3 << CLK_CLKSEL2_PWM45_S_SHIFT)
+# define CLK_CLKSEL1_PWM45_S_XTALHI (0 << CLK_CLKSEL2_PWM45_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_PWM45_S_XTALLO (1 << CLK_CLKSEL2_PWM45_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_PWM45_S_HCLK (2 << CLK_CLKSEL2_PWM45_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_PWM45_S_INTHI (3 << CLK_CLKSEL2_PWM45_S_SHIFT) /* Internal high speed clock */
+#define CLK_CLKSEL2_PWM67_S_SHIFT (6) /* Bits 6-7: PWM6 and PWM7 clock source select */
+#define CLK_CLKSEL2_PWM67_S_MASK (3 << CLK_CLKSEL2_PWM67_S_SHIFT)
+# define CLK_CLKSEL1_PWM67_S_XTALHI (0 << CLK_CLKSEL2_PWM67_S_SHIFT) /* High speed XTAL clock */
+# define CLK_CLKSEL1_PWM67_S_XTALLO (1 << CLK_CLKSEL2_PWM67_S_SHIFT) /* Low speed XTAL clock */
+# define CLK_CLKSEL1_PWM67_S_HCLK (2 << CLK_CLKSEL2_PWM67_S_SHIFT) /* HCLK */
+# define CLK_CLKSEL1_PWM67_S_INTHI (3 << CLK_CLKSEL2_PWM67_S_SHIFT) /* Internal high speed clock */
+
+/* Clock divider number register */
+
+#define CLK_CLKDIV_HCLK_N_SHIFT (0) /* Bits 0-3: HCLCK divide from clock source */
+#define CLK_CLKDIV_HCLK_N_MASK (15 << CLK_CLKDIV_HCLK_N_SHIFT)
+# define CLK_CLKDIV_HCLK_N(n) (((n)-1) << CLK_CLKDIV_HCLK_N_SHIFT) /* n=1..16 */
+#define CLK_CLKDIV_USB_N_SHIFT (4) /* Bits 4-7: USBD divide from clock source */
+#define CLK_CLKDIV_USB_N_MASK (15 << CLK_CLKDIV_USB_N_SHIFT)
+# define CLK_CLKDIV_USB_N(n) (((n)-1) << CLK_CLKDIV_USB_N_SHIFT) /* n=1..16 */
+#define CLK_CLKDIV_UART_N_SHIFT (8) /* Bits 8-11 UART divide from clock source */
+#define CLK_CLKDIV_UART_N_MASK (15 << CLK_CLKDIV_UART_N_SHIFT)
+# define CLK_CLKDIV_UART_N(n) (((n)-1) << CLK_CLKDIV_UART_N_SHIFT) /* n=1..16 */
+#define CLK_CLKDIV_ADC_N_SHIFT (16) /* Bits 16-23: ADC divide from clock source */
+#define CLK_CLKDIV_ADC_N_MASK (255 << CLK_CLKDIV_ADC_N_SHIFT)
+# define CLK_CLKDIV_ADC_N(n) (((n)-1) << CLK_CLKDIV_UART_N_SHIFT) /* n=1..256 */
+
+/* PLL control register */
+
+#define CLK_PLLCON_FB_DV_SHIFT (0) /* Bits 0-8: PLL feedback divider control pins */
+#define CLK_PLLCON_FB_DV_MASK (0x1ff << CLK_PLLCON_FB_DV_SHIFT)
+# define CLK_PLLCON_FB_DV(n) ((n) << CLK_PLLCON_FB_DV_SHIFT)
+#define CLK_PLLCON_IN_DV_SHIFT (9) /* bits 9-13: PLL input divider control pins */
+#define CLK_PLLCON_IN_DV_MASK (0x1f << CLK_PLLCON_IN_DV_SHIFT)
+# define CLK_PLLCON_IN_DV(n) ((n) << CLK_PLLCON_IN_DV_SHIFT)
+#define CLK_PLLCON_OUT_DV_SHIFT (14) /* Bits 14-15: PLL output divider control pins */
+#define CLK_PLLCON_OUT_DV_MASK (3 << CLK_PLLCON_OUT_DV_SHIFT)
+# define CLK_PLLCON_OUT_DV(n) ((n) << CLK_PLLCON_OUT_DV_SHIFT)
+#define CLK_PLLCON_PD (1 << 16) /* Bit 16: Power down mode */
+#define CLK_PLLCON_BP (1 << 17) /* Bit 17: PLL bypass control */
+#define CLK_PLLCON_OE (1 << 18) /* Bit 18: PLL OE (FOUT enable) pin control */
+#define CLK_PLLCON_PLL_SRC (1 << 19) /* Bit 19: PLL source clock select */
+
+/* Frequency divider control register */
+
+#define CLK_FRQDIV_FSEL_SHIFT (0) /* Bits 0-3: Divider output frequency selection bits */
+#define CLK_FRQDIV_FSEL_MASK (15 << CLK_FRQDIV_FSEL_SHIFT)
+# define CLK_FRQDIV_FSEL(n) ((n) << CLK_FRQDIV_FSEL_SHIFT) /* fout = fin / (2^(n+1)) */
+#define CLK_FRQDIV_DIVIDER_EN (1 << 4) /* Bit 4: Frequency divider enable bit */
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_CLK_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_cmp.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_cmp.h
new file mode 100644
index 000000000..64d11b31e
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_cmp.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_cmp.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_CMP_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_CMP_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_CMP_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_ebi.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_ebi.h
new file mode 100644
index 000000000..142ae60ab
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_ebi.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_ebi.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_EBI_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_EBI_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_EBI_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_gcr.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_gcr.h
new file mode 100644
index 000000000..cf09cac81
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_gcr.h
@@ -0,0 +1,373 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_gcr.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_GCR_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_GCR_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+#define NUC_GCR_PDID_OFFSET 0x0000 /* Part didentification number register */
+#define NUC_GCR_RSTSRC_OFFSET 0x0004 /* System reset source register */
+#define NUC_GCR_IPRSTC1_OFFSET 0x0008 /* IP Reset control register 1 */
+#define NUC_GCR_IPRSTC2_OFFSET 0x000c /* IP Reset control register 2 */
+#define NUC_GCR_CPR_OFFSET 0x0010 /* Chip performance register */
+#define NUC_GCR_BODCR_OFFSET 0x0018 /* Brown-out detector control register */
+#define NUC_GCR_TEMPCR_OFFSET 0x001c /* Temperature sensor control register */
+#define NUC_GCR_PORCR_OFFSET 0x0024 /* Power-on-reset control register */
+#define NUC_GCR_GPA_MFP_OFFSET 0x0030 /* Multiple function pin GPIOA control register */
+#define NUC_GCR_GPB_MFP_OFFSET 0x0034 /* Multiple function pin GPIOB control register */
+#define NUC_GCR_GPC_MFP_OFFSET 0x0038 /* Multiple function pin GPIOC control register */
+#define NUC_GCR_GPD_MFP_OFFSET 0x003C /* Multiple function pin GPIOD control register */
+#define NUC_GCR_GPE_MFP_OFFSET 0x0040 /* Multiple function pin GPIOE control register */
+#define NUC_GCR_ALT_MFP_OFFSET 0x0050 /* Alternative multiple function pin control register */
+#define NUC_GCR_REGWRPROT_OFFSET 0x0100 /* Register write-protection control register */
+
+/* Register addresses ***********************************************************************/
+
+#define NUC_GCR_PDID (NUC_GCR_BASE+NUC_GCR_PDID_OFFSET)
+#define NUC_GCR_RSTSRC (NUC_GCR_BASE+NUC_GCR_RSTSRC_OFFSET)
+#define NUC_GCR_IPRSTC1 (NUC_GCR_BASE+NUC_GCR_IPRSTC1_OFFSET)
+#define NUC_GCR_IPRSTC2 (NUC_GCR_BASE+NUC_GCR_IPRSTC2_OFFSET)
+#define NUC_GCR_CPR (NUC_GCR_BASE+NUC_GCR_CPR_OFFSET)
+#define NUC_GCR_BODCR (NUC_GCR_BASE+NUC_GCR_BODCR_OFFSET)
+#define NUC_GCR_TEMPCR (NUC_GCR_BASE+NUC_GCR_TEMPCR_OFFSET)
+#define NUC_GCR_PORCR (NUC_GCR_BASE+NUC_GCR_PORCR_OFFSET)
+#define NUC_GCR_GPA_MFP (NUC_GCR_BASE+NUC_GCR_GPA_MFP_OFFSET)
+#define NUC_GCR_GPB_MFP (NUC_GCR_BASE+NUC_GCR_GPB_MFP_OFFSET)
+#define NUC_GCR_GPC_MFP (NUC_GCR_BASE+NUC_GCR_GPC_MFP_OFFSET)
+#define NUC_GCR_GPD_MFP (NUC_GCR_BASE+NUC_GCR_GPD_MFP_OFFSET)
+#define NUC_GCR_GPE_MFP (NUC_GCR_BASE+NUC_GCR_GPE_MFP_OFFSET)
+#define NUC_GCR_ALT_MFP (NUC_GCR_BASE+NUC_GCR_ALT_MFP_OFFSET)
+#define NUC_GCR_REGWRPROT (NUC_GCR_BASE+NUC_GCR_REGWRPROT_OFFSET)
+
+/* Register bit-field definitions ***********************************************************/
+
+/* Part didentification number register (32-bit part ID number) */
+
+/* System reset source register */
+
+#define GCR_RSTSRC_POR (1 << 0) /* Bit 0: Power-on reset (POR) or chip reset (CHIP_RST) */
+#define GCR_RSTSRC_RESET (1 << 1) /* Bit 1: /RESET pin */
+#define GCR_RSTSRC_WDT (1 << 2) /* Bit 2: Watchdog timer */
+#define GCR_RSTSRC_LVR (1 << 3) /* Bit 3: Low voltage reset controller */
+#define GCR_RSTSRC_BOD (1 << 4) /* Bit 4: Brown-out detection */
+#define GCR_RSTSRC_SYS (1 << 5) /* Bit 5: Software set AIRCR:SYSRESETREQ */
+#define GCR_RSTSRC_CPU (1 << 7) /* Bit 7: Sofware set CPU_RST */
+
+/* IP Reset control register 1 */
+
+#define GCR_IPRSTC1_CHIP_RST (1 << 0) /* Bit 0: Chip one-shot reset */
+#define GCR_IPRSTC1_CPU_RST (1 << 1) /* Bit 1: CPU kernel one-shot reset */
+#define GCR_IPRSTC1_PDMA_RST (1 << 2) /* Bit 2: PDMA controller reset */
+#define GCR_IPRSTC1_EBI_RST (1 << 3) /* Bit 3: EBI controller reset */
+
+/* IP Reset control register 2 */
+
+#define GCR_IPRSTC2_GPIO_RST (1 << 1) /* Bit 1: GPIO controller reset */
+#define GCR_IPRSTC2_TMR0_RST (1 << 2) /* Bit 2: Timer0 controller reset */
+#define GCR_IPRSTC2_TMR1_RST (1 << 3) /* Bit 3: Timer1 controller reset */
+#define GCR_IPRSTC2_TMR2_RST (1 << 4) /* Bit 4: Timer2 controller reset */
+#define GCR_IPRSTC2_TMR3_RST (1 << 5) /* Bit 5: Timer3 controller reset */
+#define GCR_IPRSTC2_I2C0_RST (1 << 8) /* Bit 8: I2C0 controller reset */
+#define GCR_IPRSTC2_I2C1_RST (1 << 9) /* Bit 9: I2C1 controller reset */
+#define GCR_IPRSTC2_SPI0_RST (1 << 12) /* Bit 12: SPI0 controller reset */
+#define GCR_IPRSTC2_SPI1_RST (1 << 13) /* Bit 13: SPI1 controller reset */
+#define GCR_IPRSTC2_SPI2_RST (1 << 14) /* Bit 14: SPI2 controller reset */
+#define GCR_IPRSTC2_SPI3_RST (1 << 15) /* Bit 15: SPI3 controller reset */
+#define GCR_IPRSTC2_UART0_RST (1 << 16) /* Bit 16: UART0 controller reset */
+#define GCR_IPRSTC2_UART1_RST (1 << 17) /* Bit 17: UART1 controller reset */
+#define GCR_IPRSTC2_UART2_RST (1 << 18) /* Bit 18: UART2 controller reset */
+#define GCR_IPRSTC2_PWM03_RST (1 << 20) /* Bit 20: PWM0/1/2/3 controller reset */
+#define GCR_IPRSTC2_PWM47_RST (1 << 21) /* Bit 21: PWM4/5/6/7 controller reset */
+#define GCR_IPRSTC2_ACMP_RST (1 << 22) /* Bit 22: Analog comparator controller reset */
+#define GCR_IPRSTC2_PS2_RST (1 << 23) /* Bit 23: PS/2 controller reset */
+#define GCR_IPRSTC2_USBD_RST (1 << 27) /* Bit 27: USB device controller reset */
+#define GCR_IPRSTC2_ADC_RST (1 << 28) /* Bit 28: ADC controller reset */
+#define GCR_IPRSTC2_I2S_RST (1 << 29) /* Bit 29: I2S controller reset */
+
+/* Chip performance register */
+
+#define GCR_CPR_HPE (1 << 0) /* Bit 0: High performance enable */
+
+/* Brown-out detector control register */
+
+#define GCR_BODCR_BOD_EN (1 << 0) /* Bit 0: Brown-ut detector enable */
+#define GCR_BODCR_BOD_VL_SHIFT (1) /* Bits 1-2: Brown-out detector threshold voltage selection */
+#define GCR_BODCR_BOD_VL_MASK (3 << GCR_BODCR_BOD_VL_SHIFT)
+# define GCR_BODCR_BOD_VL_2p2V (0 << GCR_BODCR_BOD_VL_SHIFT) /* 2.2V */
+# define GCR_BODCR_BOD_VL_2p7V (1 << GCR_BODCR_BOD_VL_SHIFT) /* 2.7V */
+# define GCR_BODCR_BOD_VL_3p8V (2 << GCR_BODCR_BOD_VL_SHIFT) /* 3.8V */
+# define GCR_BODCR_BOD_VL_4p5V (3 << GCR_BODCR_BOD_VL_SHIFT) /* 4.5V */
+#define GCR_BODCR_BOD_RSTEN (1 << 3) /* Bit 3: Brown-out reset enable */
+#define GCR_BODCR_BOD_INTF (1 << 4) /* Bit 4: Brown-out deletector interrupt flag */
+#define GCR_BODCR_BOD_LPM (1 << 5) /* Bit 5: Brown-out detector low power mode */
+#define GCR_BODCR_BOD_OUT (1 << 6) /* Bit 6: Brown-out detector output status */
+#define GCR_BODCR_LVR_EN (1 << 7) /* Bit 7: Low voltaghe reset enable */
+
+/* Temperature sensor control register */
+
+#define GCR_TEMPCR_VTEMP_EN (1 << 0) /* Bit 0: Temperature sensor enable */
+
+/* Power-on-reset control register */
+
+#define GCR_PORCR_MASK (0xffff) /* Bits 9-15: POR disable code */
+
+/* Multiple function pin GPIOA control register */
+
+#define GCR_GPA_MFP(n) (1 << (n)) /* Bits 0-15: PAn pin function selection */
+# define GCR_GPA_MFP0 (1 << 0)
+# define GCR_GPA_MFP1 (1 << 1)
+# define GCR_GPA_MFP2 (1 << 2)
+# define GCR_GPA_MFP3 (1 << 3)
+# define GCR_GPA_MFP4 (1 << 4)
+# define GCR_GPA_MFP5 (1 << 5)
+# define GCR_GPA_MFP6 (1 << 6)
+# define GCR_GPA_MFP7 (1 << 7)
+# define GCR_GPA_MFP8 (1 << 8)
+# define GCR_GPA_MFP9 (1 << 9)
+# define GCR_GPA_MFP10 (1 << 10)
+# define GCR_GPA_MFP11 (1 << 11)
+# define GCR_GPA_MFP12 (1 << 12)
+# define GCR_GPA_MFP13 (1 << 13)
+# define GCR_GPA_MFP14 (1 << 14)
+# define GCR_GPA_MFP15 (1 << 15)
+#define GCR_GPA_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPA_TYPE0 (1 << 0)
+# define GCR_GPA_TYPE1 (1 << 1)
+# define GCR_GPA_TYPE2 (1 << 2)
+# define GCR_GPA_TYPE3 (1 << 3)
+# define GCR_GPA_TYPE4 (1 << 4)
+# define GCR_GPA_TYPE5 (1 << 5)
+# define GCR_GPA_TYPE6 (1 << 6)
+# define GCR_GPA_TYPE7 (1 << 7)
+# define GCR_GPA_TYPE8 (1 << 8)
+# define GCR_GPA_TYPE9 (1 << 9)
+# define GCR_GPA_TYPE10 (1 << 10)
+# define GCR_GPA_TYPE11 (1 << 11)
+# define GCR_GPA_TYPE12 (1 << 12)
+# define GCR_GPA_TYPE13 (1 << 13)
+# define GCR_GPA_TYPE14 (1 << 14)
+# define GCR_GPA_TYPE15 (1 << 15)
+
+/* Multiple function pin GPIOB control register */
+
+#define GCR_GPB_MFP(n) (1 << (n)) /* Bits 0-15: PBn pin function selection */
+# define GCR_GPB_MFP0 (1 << 0)
+# define GCR_GPB_MFP1 (1 << 1)
+# define GCR_GPB_MFP2 (1 << 2)
+# define GCR_GPB_MFP3 (1 << 3)
+# define GCR_GPB_MFP4 (1 << 4)
+# define GCR_GPB_MFP5 (1 << 5)
+# define GCR_GPB_MFP6 (1 << 6)
+# define GCR_GPB_MFP7 (1 << 7)
+# define GCR_GPB_MFP8 (1 << 8)
+# define GCR_GPB_MFP9 (1 << 9)
+# define GCR_GPB_MFP10 (1 << 10)
+# define GCR_GPB_MFP11 (1 << 11)
+# define GCR_GPB_MFP12 (1 << 12)
+# define GCR_GPB_MFP13 (1 << 13)
+# define GCR_GPB_MFP14 (1 << 14)
+# define GCR_GPB_MFP15 (1 << 15)
+#define GCR_GPB_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPB_TYPE0 (1 << 0)
+# define GCR_GPB_TYPE1 (1 << 1)
+# define GCR_GPB_TYPE2 (1 << 2)
+# define GCR_GPB_TYPE3 (1 << 3)
+# define GCR_GPB_TYPE4 (1 << 4)
+# define GCR_GPB_TYPE5 (1 << 5)
+# define GCR_GPB_TYPE6 (1 << 6)
+# define GCR_GPB_TYPE7 (1 << 7)
+# define GCR_GPB_TYPE8 (1 << 8)
+# define GCR_GPB_TYPE9 (1 << 9)
+# define GCR_GPB_TYPE10 (1 << 10)
+# define GCR_GPB_TYPE11 (1 << 11)
+# define GCR_GPB_TYPE12 (1 << 12)
+# define GCR_GPB_TYPE13 (1 << 13)
+# define GCR_GPB_TYPE14 (1 << 14)
+# define GCR_GPB_TYPE15 (1 << 15)
+
+/* Multiple function pin GPIOC control register */
+
+#define GCR_GPC_MFP(n) (1 << (n)) /* Bits 0-15: PCn pin function selection */
+# define GCR_GPC_MFP0 (1 << 0)
+# define GCR_GPC_MFP1 (1 << 1)
+# define GCR_GPC_MFP2 (1 << 2)
+# define GCR_GPC_MFP3 (1 << 3)
+# define GCR_GPC_MFP4 (1 << 4)
+# define GCR_GPC_MFP5 (1 << 5)
+# define GCR_GPC_MFP6 (1 << 6)
+# define GCR_GPC_MFP7 (1 << 7)
+# define GCR_GPC_MFP8 (1 << 8)
+# define GCR_GPC_MFP9 (1 << 9)
+# define GCR_GPC_MFP10 (1 << 10)
+# define GCR_GPC_MFP11 (1 << 11)
+# define GCR_GPC_MFP12 (1 << 12)
+# define GCR_GPC_MFP13 (1 << 13)
+# define GCR_GPC_MFP14 (1 << 14)
+# define GCR_GPC_MFP15 (1 << 15)
+#define GCR_GPC_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPC_TYPE0 (1 << 0)
+# define GCR_GPC_TYPE1 (1 << 1)
+# define GCR_GPC_TYPE2 (1 << 2)
+# define GCR_GPC_TYPE3 (1 << 3)
+# define GCR_GPC_TYPE4 (1 << 4)
+# define GCR_GPC_TYPE5 (1 << 5)
+# define GCR_GPC_TYPE6 (1 << 6)
+# define GCR_GPC_TYPE7 (1 << 7)
+# define GCR_GPC_TYPE8 (1 << 8)
+# define GCR_GPC_TYPE9 (1 << 9)
+# define GCR_GPC_TYPE10 (1 << 10)
+# define GCR_GPC_TYPE11 (1 << 11)
+# define GCR_GPC_TYPE12 (1 << 12)
+# define GCR_GPC_TYPE13 (1 << 13)
+# define GCR_GPC_TYPE14 (1 << 14)
+# define GCR_GPC_TYPE15 (1 << 15)
+
+/* Multiple function pin GPIOD control register */
+
+#define GCR_GPD_MFP(n) (1 << (n)) /* Bits 0-15: PDn pin function selection */
+# define GCR_GPD_MFP0 (1 << 0)
+# define GCR_GPD_MFP1 (1 << 1)
+# define GCR_GPD_MFP2 (1 << 2)
+# define GCR_GPD_MFP3 (1 << 3)
+# define GCR_GPD_MFP4 (1 << 4)
+# define GCR_GPD_MFP5 (1 << 5)
+# define GCR_GPD_MFP6 (1 << 6)
+# define GCR_GPD_MFP7 (1 << 7)
+# define GCR_GPD_MFP8 (1 << 8)
+# define GCR_GPD_MFP9 (1 << 9)
+# define GCR_GPD_MFP10 (1 << 10)
+# define GCR_GPD_MFP11 (1 << 11)
+# define GCR_GPD_MFP12 (1 << 12)
+# define GCR_GPD_MFP13 (1 << 13)
+# define GCR_GPD_MFP14 (1 << 14)
+# define GCR_GPD_MFP15 (1 << 15)
+#define GCR_GPD_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPD_TYPE0 (1 << 0)
+# define GCR_GPD_TYPE1 (1 << 1)
+# define GCR_GPD_TYPE2 (1 << 2)
+# define GCR_GPD_TYPE3 (1 << 3)
+# define GCR_GPD_TYPE4 (1 << 4)
+# define GCR_GPD_TYPE5 (1 << 5)
+# define GCR_GPD_TYPE6 (1 << 6)
+# define GCR_GPD_TYPE7 (1 << 7)
+# define GCR_GPD_TYPE8 (1 << 8)
+# define GCR_GPD_TYPE9 (1 << 9)
+# define GCR_GPD_TYPE10 (1 << 10)
+# define GCR_GPD_TYPE11 (1 << 11)
+# define GCR_GPD_TYPE12 (1 << 12)
+# define GCR_GPD_TYPE13 (1 << 13)
+# define GCR_GPD_TYPE14 (1 << 14)
+# define GCR_GPD_TYPE15 (1 << 15)
+
+/* Multiple function pin GPIOE control register */
+
+#define GCR_GPE_MFP(n) (1 << (n)) /* Bits 0-15: PDn pin function selection */
+# define GCR_GPE_MFP0 (1 << 0)
+# define GCR_GPE_MFP1 (1 << 1)
+# define GCR_GPE_MFP2 (1 << 2)
+# define GCR_GPE_MFP3 (1 << 3)
+# define GCR_GPE_MFP4 (1 << 4)
+# define GCR_GPE_MFP5 (1 << 5)
+#define GCR_GPE_TYPE(n) (1 << ((n)+16)) /* Bits 16-31: Enable Schmitt trigger function */
+# define GCR_GPE_TYPE0 (1 << 0)
+# define GCR_GPE_TYPE1 (1 << 1)
+# define GCR_GPE_TYPE2 (1 << 2)
+# define GCR_GPE_TYPE3 (1 << 3)
+# define GCR_GPE_TYPE4 (1 << 4)
+# define GCR_GPE_TYPE5 (1 << 5)
+
+/* Alternative multiple function pin control register */
+
+#define GCR_ALT_MFP_PB10_S01 (1 << 0) /* Bit 0: Determines PB.10 function */
+#define GCR_ALT_MFP_PB9_S11 (1 << 1) /* Bit 1: Determines PB.9 function */
+#define GCR_ALT_MFP_PA7_S21 (1 << 2) /* Bit 2: Determines PA.7 function */
+#define GCR_ALT_MFP_PB14_S31 (1 << 3) /* Bit 3: Determines PB.14 function */
+#define GCR_ALT_MFP_PB11_PWM4 (1 << 4) /* Bit 4: Determines PB.11 function */
+#define GCR_ALT_MFP_PC0_I2SRCLK (1 << 5) /* Bit 5: Determines PC.0 function */
+#define GCR_ALT_MFP_PC1_I2SBCLK (1 << 6) /* Bit 6: Determines PC.1 function */
+#define GCR_ALT_MFP_PC2_I2SD1 (1 << 7) /* Bit 7: Determines PC.2 function */
+#define GCR_ALT_MFP_PC3_I2SD0 (1 << 8) /* Bit 8: Determines PC.3 function */
+#define GCR_ALT_MFP_PA15_I2SMCLK (1 << 9) /* Bit 9: Determines PA.15 function */
+#define GCR_ALT_MFP_PB12_CLKO (1 << 10) /* Bit 10: Determines PB.12 function */
+#define GCR_ALT_MFP_EBI_EN (1 << 11) /* Bit 11: Determines PA.6, PA.7, PA.10, PA.11,
+ * PB.6, PB.7, PB.12, PB.13, PC.6, PC.7, PC.14,
+ * PC.15 function */
+#define GCR_ALT_MFP_EBI_MCLK_EN (1 << 12) /* Bit 12: Determines PC.8 function */
+#define GCR_ALT_MFP_EBI_NWRL_EN (1 << 13) /* Bit 13: Determines PB.2 function */
+#define GCR_ALT_MFP_EBI_NWRH_WN (1 << 14) /* Bit 14: Determines PB.3 function */
+#define GCR_ALT_MFP_EBI_HB_EN0 (1 << 16) /* Bit 16: Determines PA.5 function */
+#define GCR_ALT_MFP_EBI_HB_EN1 (1 << 17) /* Bit 17: Determines PA.4 function */
+#define GCR_ALT_MFP_EBI_HB_EN2 (1 << 18) /* Bit 18: Determines PA.3 function */
+#define GCR_ALT_MFP_EBI_HB_EN3 (1 << 19) /* Bit 19: Determines PA.2 function */
+#define GCR_ALT_MFP_EBI_HB_EN4 (1 << 20) /* Bit 20: Determines PA.1 function */
+#define GCR_ALT_MFP_EBI_HB_EN5 (1 << 21) /* Bit 21: Determines PA.12 function */
+#define GCR_ALT_MFP_EBI_HB_EN6 (1 << 22) /* Bit 22: Determines PA.13 function */
+#define GCR_ALT_MFP_EBI_HB_EN7 (1 << 23) /* Bit 23: Determines PA.14 function */
+
+/* Register write-protection control register */
+
+ /* Write: */
+#define GCR_REGWRPROT_MASK (0xff) /* Bits 0-7: Register write protection code */
+# define GCR_REGWRPROT_1 (0x59) /* Disable sequence */
+# define GCR_REGWRPROT_2 (0x16)
+# define GCR_REGWRPROT_3 (0x88)
+ /* Read: */
+#define GCR_REGWRPROT_DIS (1 << 0) /* Bit 0: Register write protectino disable index */
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_GCR_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h
new file mode 100644
index 000000000..4bc1b61f9
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h
@@ -0,0 +1,554 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_gpio.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_GPIO_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_GPIO_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+#define NUC_GPIO_PORTA 0
+#define NUC_GPIO_PORTB 1
+#define NUC_GPIO_PORTC 2
+#define NUC_GPIO_PORTD 3
+#define NUC_GPIO_PORTE 4
+
+/* GPIO control registers */
+
+#define NUC_GPIO_CTRL_OFFSET(n) (0x0000 + ((n) << 6))
+#define NUC_GPIOA_CTRL_OFFSET (0x0000 + ((NUC_GPIO_PORTA) << 6))
+#define NUC_GPIOB_CTRL_OFFSET (0x0000 + ((NUC_GPIO_PORTB) << 6))
+#define NUC_GPIOC_CTRL_OFFSET (0x0000 + ((NUC_GPIO_PORTC) << 6))
+#define NUC_GPIOD_CTRL_OFFSET (0x0000 + ((NUC_GPIO_PORTD) << 6))
+#define NUC_GPIOE_CTRL_OFFSET (0x0000 + ((NUC_GPIO_PORTE) << 6))
+
+#define NUC_GPIO_PMD_OFFSET 0x0000 /* GPIO port pin I/O mode control */
+#define NUC_GPIO_OFFD_OFFSET 0x0004 /* GPIO port pin digital input path disable control */
+#define NUC_GPIO_DOUT_OFFSET 0x0008 /* GPIO port data output value */
+#define NUC_GPIO_DMASK_OFFSET 0x000c /* GPIO port data output write mask */
+#define NUC_GPIO_PIN_OFFSET 0x0010 /* GPIO port pin value */
+#define NUC_GPIO_DBEN_OFFSET 0x0014 /* GPIO port de-bounce enable */
+#define NUC_GPIO_IMD_OFFSET 0x0018 /* GPIO port interrupt mode control */
+#define NUC_GPIO_IEN_OFFSET 0x001c /* GPIO port interrupt enable */
+#define NUC_GPIO_ISRC_OFFSET 0x0020 /* GPIO port interrupt source flag */
+
+/* GPIO port A control registers */
+
+#define NUC_GPIOA_PMD_OFFSET (NUC_GPIOA_CTRL_OFFSET+NUC_GPIO_PMD_OFFSET)
+#define NUC_GPIOA_OFFD_OFFSET (NUC_GPIOA_CTRL_OFFSET+NUC_GPIO_OFFD_OFFSET)
+#define NUC_GPIOA_DOUT_OFFSET (NUC_GPIOA_CTRL_OFFSET+NUC_GPIO_DOUT_OFFSET)
+#define NUC_GPIOA_DMASK_OFFSET (NUC_GPIOA_CTRL_OFFSET+NUC_GPIO_DMASK_OFFSET)
+#define NUC_GPIOA_PIN_OFFSET (NUC_GPIOA_CTRL_OFFSET+NUC_GPIO_PIN_OFFSET)
+#define NUC_GPIOA_DBEN_OFFSET (NUC_GPIOA_CTRL_OFFSET+NUC_GPIO_DBEN_OFFSET)
+#define NUC_GPIOA_IMD_OFFSET (NUC_GPIOA_CTRL_OFFSET+NUC_GPIO_IMD_OFFSET)
+#define NUC_GPIOA_IEN_OFFSET (NUC_GPIOA_CTRL_OFFSET+NUC_GPIO_IEN_OFFSET)
+#define NUC_GPIOA_ISRC_OFFSET (NUC_GPIOA_CTRL_OFFSET+NUC_GPIO_ISRC_OFFSET)
+
+/* GPIO port B control registers */
+
+#define NUC_GPIOB_PMD_OFFSET (NUC_GPIOB_CTRL_OFFSET+NUC_GPIO_PMD_OFFSET)
+#define NUC_GPIOB_OFFD_OFFSET (NUC_GPIOB_CTRL_OFFSET+NUC_GPIO_OFFD_OFFSET)
+#define NUC_GPIOB_DOUT_OFFSET (NUC_GPIOB_CTRL_OFFSET+NUC_GPIO_DOUT_OFFSET)
+#define NUC_GPIOB_DMASK_OFFSET (NUC_GPIOB_CTRL_OFFSET+NUC_GPIO_DMASK_OFFSET)
+#define NUC_GPIOB_PIN_OFFSET (NUC_GPIOB_CTRL_OFFSET+NUC_GPIO_PIN_OFFSET)
+#define NUC_GPIOB_DBEN_OFFSET (NUC_GPIOB_CTRL_OFFSET+NUC_GPIO_DBEN_OFFSET)
+#define NUC_GPIOB_IMD_OFFSET (NUC_GPIOB_CTRL_OFFSET+NUC_GPIO_IMD_OFFSET)
+#define NUC_GPIOB_IEN_OFFSET (NUC_GPIOB_CTRL_OFFSET+NUC_GPIO_IEN_OFFSET)
+#define NUC_GPIOB_ISRC_OFFSET (NUC_GPIOB_CTRL_OFFSET+NUC_GPIO_ISRC_OFFSET)
+
+/* GPIO port C control registers */
+
+#define NUC_GPIOC_PMD_OFFSET (NUC_GPIOC_CTRL_OFFSET+NUC_GPIO_PMD_OFFSET)
+#define NUC_GPIOC_OFFD_OFFSET (NUC_GPIOC_CTRL_OFFSET+NUC_GPIO_OFFD_OFFSET)
+#define NUC_GPIOC_DOUT_OFFSET (NUC_GPIOC_CTRL_OFFSET+NUC_GPIO_DOUT_OFFSET)
+#define NUC_GPIOC_DMASK_OFFSET (NUC_GPIOC_CTRL_OFFSET+NUC_GPIO_DMASK_OFFSET)
+#define NUC_GPIOC_PIN_OFFSET (NUC_GPIOC_CTRL_OFFSET+NUC_GPIO_PIN_OFFSET)
+#define NUC_GPIOC_DBEN_OFFSET (NUC_GPIOC_CTRL_OFFSET+NUC_GPIO_DBEN_OFFSET)
+#define NUC_GPIOC_IMD_OFFSET (NUC_GPIOC_CTRL_OFFSET+NUC_GPIO_IMD_OFFSET)
+#define NUC_GPIOC_IEN_OFFSET (NUC_GPIOC_CTRL_OFFSET+NUC_GPIO_IEN_OFFSET)
+#define NUC_GPIOC_ISRC_OFFSET (NUC_GPIOC_CTRL_OFFSET+NUC_GPIO_ISRC_OFFSET)
+
+/* GPIO port D control registers */
+
+#define NUC_GPIOD_PMD_OFFSET (NUC_GPIOD_CTRL_OFFSET+NUC_GPIO_PMD_OFFSET)
+#define NUC_GPIOD_OFFD_OFFSET (NUC_GPIOD_CTRL_OFFSET+NUC_GPIO_OFFD_OFFSET)
+#define NUC_GPIOD_DOUT_OFFSET (NUC_GPIOD_CTRL_OFFSET+NUC_GPIO_DOUT_OFFSET)
+#define NUC_GPIOD_DMASK_OFFSET (NUC_GPIOD_CTRL_OFFSET+NUC_GPIO_DMASK_OFFSET)
+#define NUC_GPIOD_PIN_OFFSET (NUC_GPIOD_CTRL_OFFSET+NUC_GPIO_PIN_OFFSET)
+#define NUC_GPIOD_DBEN_OFFSET (NUC_GPIOD_CTRL_OFFSET+NUC_GPIO_DBEN_OFFSET)
+#define NUC_GPIOD_IMD_OFFSET (NUC_GPIOD_CTRL_OFFSET+NUC_GPIO_IMD_OFFSET)
+#define NUC_GPIOD_IEN_OFFSET (NUC_GPIOD_CTRL_OFFSET+NUC_GPIO_IEN_OFFSET)
+#define NUC_GPIOD_ISRC_OFFSET (NUC_GPIOD_CTRL_OFFSET+NUC_GPIO_ISRC_OFFSET)
+
+/* GPIO port E control registers */
+
+#define NUC_GPIOE_PMD_OFFSET (NUC_GPIOE_CTRL_OFFSET+NUC_GPIO_PMD_OFFSET)
+#define NUC_GPIOE_OFFD_OFFSET (NUC_GPIOE_CTRL_OFFSET+NUC_GPIO_OFFD_OFFSET)
+#define NUC_GPIOE_DOUT_OFFSET (NUC_GPIOE_CTRL_OFFSET+NUC_GPIO_DOUT_OFFSET)
+#define NUC_GPIOE_DMASK_OFFSET (NUC_GPIOE_CTRL_OFFSET+NUC_GPIO_DMASK_OFFSET)
+#define NUC_GPIOE_PIN_OFFSET (NUC_GPIOE_CTRL_OFFSET+NUC_GPIO_PIN_OFFSET)
+#define NUC_GPIOE_DBEN_OFFSET (NUC_GPIOE_CTRL_OFFSET+NUC_GPIO_DBEN_OFFSET)
+#define NUC_GPIOE_IMD_OFFSET (NUC_GPIOE_CTRL_OFFSET+NUC_GPIO_IMD_OFFSET)
+#define NUC_GPIOE_IEN_OFFSET (NUC_GPIOE_CTRL_OFFSET+NUC_GPIO_IEN_OFFSET)
+#define NUC_GPIOE_ISRC_OFFSET (NUC_GPIOE_CTRL_OFFSET+NUC_GPIO_ISRC_OFFSET)
+
+/* Debounce control registers */
+
+#define NUC_GPIO_DBNCECON_OFFSEt 0x0180 /* De-bounce cycle control register */
+
+/* GPIO port data I/O register offsets */
+
+#define NUC_PORT_DATAIO_OFFSET(p) (0x0200 + ((p)<< 6))
+# define NUC_PORTA_DATAIO_OFFSET (0x0200 + ((NUC_GPIO_PORTA) << 6))
+# define NUC_PORTB_DATAIO_OFFSET (0x0200 + ((NUC_GPIO_PORTB) << 6))
+# define NUC_PORTC_DATAIO_OFFSET (0x0200 + ((NUC_GPIO_PORTC) << 6))
+# define NUC_PORTD_DATAIO_OFFSET (0x0200 + ((NUC_GPIO_PORTD) << 6))
+# define NUC_PORTE_DATAIO_OFFSET (0x0200 + ((NUC_GPIO_PORTE) << 6))
+
+/* GPIO port pin data I/O register offsets */
+
+#define NUC_PORT_PIN_OFFSET(n) ((n) << 2)
+# define NUC_PORT_PIN0_OFFSET (0 << 2)
+# define NUC_PORT_PIN1_OFFSET (1 << 2)
+# define NUC_PORT_PIN2_OFFSET (2 << 2)
+# define NUC_PORT_PIN3_OFFSET (3 << 2)
+# define NUC_PORT_PIN4_OFFSET (4 << 2)
+# define NUC_PORT_PIN5_OFFSET (5 << 2)
+# define NUC_PORT_PIN6_OFFSET (16 << 2)
+# define NUC_PORT_PIN7_OFFSET (17 << 2)
+# define NUC_PORT_PIN8_OFFSET (18 << 2)
+# define NUC_PORT_PIN9_OFFSET (19 << 2)
+# define NUC_PORT_PIN10_OFFSET (10 << 2)
+# define NUC_PORT_PIN11_OFFSET (11 << 2)
+# define NUC_PORT_PIN12_OFFSET (12 << 2)
+# define NUC_PORT_PIN13_OFFSET (13 << 2)
+# define NUC_PORT_PIN14_OFFSET (14 << 2)
+# define NUC_PORT_PIN15_OFFSET (15 << 2)
+
+#define NUC_PORT_PDIO_OFFSET(p,n) (NUC_PORT_DATAIO_OFFSET(p)+NUC_PORT_PIN_OFFSET(n))
+
+/* GPIO PA Pin Data Input/Output */
+
+#define NUC_PORTA_PDIO_OFFSET(n) (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN_OFFSET(n))
+# define NUC_PA1_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA2_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA3_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA4_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA5_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA6_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA7_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA8_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA9_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA10_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA11_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA12_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA13_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA14_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PA15_PDIO_OFFSET (NUC_PORTA_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+
+/* GPIO PB Pin Data Input/Output */
+
+#define NUC_PORTB_PDIO_OFFSET(n) (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN_OFFSET(n))
+# define NUC_PB1_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB2_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB3_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB4_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB5_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB6_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB7_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB8_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB9_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB10_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB11_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB12_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB13_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB14_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PB15_PDIO_OFFSET (NUC_PORTB_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+
+/* GPIO PC Pin Data Input/Output */
+
+#define NUC_PORTC_PDIO_OFFSET(n) (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN_OFFSET(n))
+# define NUC_PC1_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC2_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC3_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC4_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC5_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC6_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC7_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC8_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC9_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC10_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC11_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC12_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC13_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC14_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PC15_PDIO_OFFSET (NUC_PORTC_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+
+/* GPIO PD Pin Data Input/Output */
+
+#define NUC_PORTD_PDIO_OFFSET(n) (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN_OFFSET(n))
+# define NUC_PD1_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD2_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD3_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD4_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD5_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD6_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD7_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD8_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD9_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD10_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD11_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD12_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD13_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD14_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+# define NUC_PD15_PDIO_OFFSET (NUC_PORTD_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+
+/* GPIO PE Pin Data Input/Output */
+
+#define NUC_PORTE_PDIO_OFFSET(n) (NUC_PORTE_DATAIO_OFFSET+NUC_PORT_PIN_OFFSET(n))
+# define NUC_PE5_PDIO_OFFSET (NUC_PORTE_DATAIO_OFFSET+NUC_PORT_PIN0_OFFSET)
+
+/* Register addresses ***********************************************************************/
+
+/* GPIO control registers */
+
+#define NUC_GPIO_CTRL_BASE(n) (NUC_GPIO_BASE+NUC_GPIO_CTRL_OFFSET(n))
+#define NUC_GPIOA_CTRL_BASE (NUC_GPIO_BASE+NUC_GPIOA_CTRL_OFFSET)
+#define NUC_GPIOB_CTRL_BASE (NUC_GPIO_BASE+NUC_GPIOB_CTRL_OFFSET)
+#define NUC_GPIOC_CTRL_BASE (NUC_GPIO_BASE+NUC_GPIOC_CTRL_OFFSET)
+#define NUC_GPIOD_CTRL_BASE (NUC_GPIO_BASE+NUC_GPIOD_CTRL_OFFSET)
+#define NUC_GPIOE_CTRL_BASE (NUC_GPIO_BASE+NUC_GPIOE_CTRL_OFFSET)
+
+/* GPIO port A control registers */
+
+#define NUC_GPIOA_PMD (NUC_GPIO_BASE+NUC_GPIOA_PMD_OFFSET)
+#define NUC_GPIOA_OFFD (NUC_GPIO_BASE+NUC_GPIOA_OFFD_OFFSET)
+#define NUC_GPIOA_DOUT (NUC_GPIO_BASE+NUC_GPIOA_DOUT_OFFSET)
+#define NUC_GPIOA_DMASK (NUC_GPIO_BASE+NUC_GPIOA_DMASK_OFFSET)
+#define NUC_GPIOA_PIN (NUC_GPIO_BASE+NUC_GPIOA_PIN_OFFSET)
+#define NUC_GPIOA_DBEN (NUC_GPIO_BASE+NUC_GPIOA_DBEN_OFFSET)
+#define NUC_GPIOA_IMD (NUC_GPIO_BASE+NUC_GPIOA_IMD_OFFSET)
+#define NUC_GPIOA_IEN (NUC_GPIO_BASE+NUC_GPIOA_IEN_OFFSET)
+#define NUC_GPIOA_ISRC (NUC_GPIO_BASE+NUC_GPIOA_ISRC_OFFSET)
+
+/* GPIO port B control registers */
+
+#define NUC_GPIOB_PMD (NUC_GPIO_BASE+NUC_GPIOB_PMD_OFFSET)
+#define NUC_GPIOB_OFFD (NUC_GPIO_BASE+NUC_GPIOB_OFFD_OFFSET)
+#define NUC_GPIOB_DOUT (NUC_GPIO_BASE+NUC_GPIOB_DOUT_OFFSET)
+#define NUC_GPIOB_DMASK (NUC_GPIO_BASE+NUC_GPIOB_DMASK_OFFSET)
+#define NUC_GPIOB_PIN (NUC_GPIO_BASE+NUC_GPIOB_PIN_OFFSET)
+#define NUC_GPIOB_DBEN (NUC_GPIO_BASE+NUC_GPIOB_DBEN_OFFSET)
+#define NUC_GPIOB_IMD (NUC_GPIO_BASE+NUC_GPIOB_IMD_OFFSET)
+#define NUC_GPIOB_IEN (NUC_GPIO_BASE+NUC_GPIOB_IEN_OFFSET)
+#define NUC_GPIOB_ISRC (NUC_GPIO_BASE+NUC_GPIOB_ISRC_OFFSET)
+
+/* GPIO port C control registers */
+
+#define NUC_GPIOC_PMD (NUC_GPIO_BASE+NUC_GPIOC_PMD_OFFSET)
+#define NUC_GPIOC_OFFD (NUC_GPIO_BASE+NUC_GPIOC_OFFD_OFFSET)
+#define NUC_GPIOC_DOUT (NUC_GPIO_BASE+NUC_GPIOC_DOUT_OFFSET)
+#define NUC_GPIOC_DMASK (NUC_GPIO_BASE+NUC_GPIOC_DMASK_OFFSET)
+#define NUC_GPIOC_PIN (NUC_GPIO_BASE+NUC_GPIOC_PIN_OFFSET)
+#define NUC_GPIOC_DBEN (NUC_GPIO_BASE+NUC_GPIOC_DBEN_OFFSET)
+#define NUC_GPIOC_IMD (NUC_GPIO_BASE+NUC_GPIOC_IMD_OFFSET)
+#define NUC_GPIOC_IEN (NUC_GPIO_BASE+NUC_GPIOC_IEN_OFFSET)
+#define NUC_GPIOC_ISRC (NUC_GPIO_BASE+NUC_GPIOC_ISRC_OFFSET)
+
+/* GPIO port D control registers */
+
+#define NUC_GPIOD_PMD (NUC_GPIO_BASE+NUC_GPIOD_PMD_OFFSET)
+#define NUC_GPIOD_OFFD (NUC_GPIO_BASE+NUC_GPIOD_OFFD_OFFSET)
+#define NUC_GPIOD_DOUT (NUC_GPIO_BASE+NUC_GPIOD_DOUT_OFFSET)
+#define NUC_GPIOD_DMASK (NUC_GPIO_BASE+NUC_GPIOD_DMASK_OFFSET)
+#define NUC_GPIOD_PIN (NUC_GPIO_BASE+NUC_GPIOD_PIN_OFFSET)
+#define NUC_GPIOD_DBEN (NUC_GPIO_BASE+NUC_GPIOD_DBEN_OFFSET)
+#define NUC_GPIOD_IMD (NUC_GPIO_BASE+NUC_GPIOD_IMD_OFFSET)
+#define NUC_GPIOD_IEN (NUC_GPIO_BASE+NUC_GPIOD_IEN_OFFSET)
+#define NUC_GPIOD_ISRC (NUC_GPIO_BASE+NUC_GPIOD_ISRC_OFFSET)
+
+/* GPIO port E control registers */
+
+#define NUC_GPIOE_PMD (NUC_GPIO_BASE+NUC_GPIOE_PMD_OFFSET)
+#define NUC_GPIOE_OFFD (NUC_GPIO_BASE+NUC_GPIOE_OFFD_OFFSET)
+#define NUC_GPIOE_DOUT (NUC_GPIO_BASE+NUC_GPIOE_DOUT_OFFSET)
+#define NUC_GPIOE_DMASK (NUC_GPIO_BASE+NUC_GPIOE_DMASK_OFFSET)
+#define NUC_GPIOE_PIN (NUC_GPIO_BASE+NUC_GPIOE_PIN_OFFSET)
+#define NUC_GPIOE_DBEN (NUC_GPIO_BASE+NUC_GPIOE_DBEN_OFFSET)
+#define NUC_GPIOE_IMD (NUC_GPIO_BASE+NUC_GPIOE_IMD_OFFSET)
+#define NUC_GPIOE_IEN (NUC_GPIO_BASE+NUC_GPIOE_IEN_OFFSET)
+#define NUC_GPIOE_ISRC (NUC_GPIO_BASE+NUC_GPIOE_ISRC_OFFSET)
+
+/* Debounce control registers */
+
+#define NUC_GPIO_DBNCECON (NUC_GPIO_BASE+NUC_GPIO_DBNCECON_OFFSET)
+
+/* GPIO port data I/O register offsets */
+
+#define NUC_PORT_DATAIO_BASE(p) (NUC_GPIO_BASE+NUC_PORT_DATAIO_OFFSET(p))
+# define NUC_PORTA_DATAIO_BASE (NUC_GPIO_BASE+NUC_PORTA_DATAIO_OFFSET)
+# define NUC_PORTB_DATAIO_BASE (NUC_GPIO_BASE+NUC_PORTB_DATAIO_OFFSET)
+# define NUC_PORTC_DATAIO_BASE (NUC_GPIO_BASE+NUC_PORTC_DATAIO_OFFSET)
+# define NUC_PORTD_DATAIO_BASE (NUC_GPIO_BASE+NUC_PORTD_DATAIO_OFFSET)
+# define NUC_PORTE_DATAIO_BASE (NUC_GPIO_BASE+NUC_PORTE_DATAIO_OFFSET)
+
+#define NUC_PORT_PDIO(p,n) (NUC_GPIO_BASE+NUC_PORT_PDIO_OFFSET(p,n))
+
+/* GPIO PA Pin Data Input/Output */
+
+#define NUC_PORTA_PDIO(n) (NUC_GPIO_BASE+NUC_PORTA_PDIO_OFFSET(n))
+# define NUC_PA1_PDIO (NUC_GPIO_BASE+NUC_PA1_PDIO_OFFSET)
+# define NUC_PA2_PDIO (NUC_GPIO_BASE+NUC_PA2_PDIO_OFFSET)
+# define NUC_PA3_PDIO (NUC_GPIO_BASE+NUC_PA3_PDIO_OFFSET)
+# define NUC_PA4_PDIO (NUC_GPIO_BASE+NUC_PA4_PDIO_OFFSET)
+# define NUC_PA5_PDIO (NUC_GPIO_BASE+NUC_PA5_PDIO_OFFSET)
+# define NUC_PA6_PDIO (NUC_GPIO_BASE+NUC_PA6_PDIO_OFFSET)
+# define NUC_PA7_PDIO (NUC_GPIO_BASE+NUC_PA7_PDIO_OFFSET)
+# define NUC_PA8_PDIO (NUC_GPIO_BASE+NUC_PA8_PDIO_OFFSET)
+# define NUC_PA9_PDIO (NUC_GPIO_BASE+NUC_PA9_PDIO_OFFSET)
+# define NUC_PA10_PDIO (NUC_GPIO_BASE+NUC_PA10_PDIO_OFFSET)
+# define NUC_PA11_PDIO (NUC_GPIO_BASE+NUC_PA11_PDIO_OFFSET)
+# define NUC_PA12_PDIO (NUC_GPIO_BASE+NUC_PA12_PDIO_OFFSET)
+# define NUC_PA13_PDIO (NUC_GPIO_BASE+NUC_PA13_PDIO_OFFSET)
+# define NUC_PA14_PDIO (NUC_GPIO_BASE+NUC_PA14_PDIO_OFFSET)
+# define NUC_PA15_PDIO (NUC_GPIO_BASE+NUC_PA15_PDIO_OFFSET)
+
+/* GPIO PB Pin Data Input/Output */
+
+#define NUC_PORTB_PDIO(n) (NUC_GPIO_BASE+NUC_PORTB_PDIO_OFFSET(n))
+# define NUC_PB1_PDIO (NUC_GPIO_BASE+NUC_PB1_PDIO_OFFSET)
+# define NUC_PB2_PDIO (NUC_GPIO_BASE+NUC_PB2_PDIO_OFFSET)
+# define NUC_PB3_PDIO (NUC_GPIO_BASE+NUC_PB3_PDIO_OFFSET)
+# define NUC_PB4_PDIO (NUC_GPIO_BASE+NUC_PB4_PDIO_OFFSET)
+# define NUC_PB5_PDIO (NUC_GPIO_BASE+NUC_PB5_PDIO_OFFSET)
+# define NUC_PB6_PDIO (NUC_GPIO_BASE+NUC_PB6_PDIO_OFFSET)
+# define NUC_PB7_PDIO (NUC_GPIO_BASE+NUC_PB7_PDIO_OFFSET)
+# define NUC_PB8_PDIO (NUC_GPIO_BASE+NUC_PB8_PDIO_OFFSET)
+# define NUC_PB9_PDIO (NUC_GPIO_BASE+NUC_PB9_PDIO_OFFSET)
+# define NUC_PB10_PDIO (NUC_GPIO_BASE+NUC_PB10_PDIO_OFFSET)
+# define NUC_PB11_PDIO (NUC_GPIO_BASE+NUC_PB11_PDIO_OFFSET)
+# define NUC_PB12_PDIO (NUC_GPIO_BASE+NUC_PB12_PDIO_OFFSET)
+# define NUC_PB13_PDIO (NUC_GPIO_BASE+NUC_PB13_PDIO_OFFSET)
+# define NUC_PB14_PDIO (NUC_GPIO_BASE+NUC_PB14_PDIO_OFFSET)
+# define NUC_PB15_PDIO (NUC_GPIO_BASE+NUC_PB15_PDIO_OFFSET)
+
+/* GPIO PC Pin Data Input/Output */
+
+#define NUC_PORTC_PDIO(n) (NUC_GPIO_BASE+NUC_PORTC_PDIO_OFFSET(n))
+# define NUC_PC1_PDIO (NUC_GPIO_BASE+NUC_PC1_PDIO_OFFSET)
+# define NUC_PC2_PDIO (NUC_GPIO_BASE+NUC_PC2_PDIO_OFFSET)
+# define NUC_PC3_PDIO (NUC_GPIO_BASE+NUC_PC3_PDIO_OFFSET)
+# define NUC_PC4_PDIO (NUC_GPIO_BASE+NUC_PC4_PDIO_OFFSET)
+# define NUC_PC5_PDIO (NUC_GPIO_BASE+NUC_PC5_PDIO_OFFSET)
+# define NUC_PC6_PDIO (NUC_GPIO_BASE+NUC_PC6_PDIO_OFFSET)
+# define NUC_PC7_PDIO (NUC_GPIO_BASE+NUC_PC7_PDIO_OFFSET)
+# define NUC_PC8_PDIO (NUC_GPIO_BASE+NUC_PC8_PDIO_OFFSET)
+# define NUC_PC9_PDIO (NUC_GPIO_BASE+NUC_PC9_PDIO_OFFSET)
+# define NUC_PC10_PDIO (NUC_GPIO_BASE+NUC_PC10_PDIO_OFFSET)
+# define NUC_PC11_PDIO (NUC_GPIO_BASE+NUC_PC11_PDIO_OFFSET)
+# define NUC_PC12_PDIO (NUC_GPIO_BASE+NUC_PC12_PDIO_OFFSET)
+# define NUC_PC13_PDIO (NUC_GPIO_BASE+NUC_PC13_PDIO_OFFSET)
+# define NUC_PC14_PDIO (NUC_GPIO_BASE+NUC_PC14_PDIO_OFFSET)
+# define NUC_PC15_PDIO (NUC_GPIO_BASE+NUC_PC15_PDIO_OFFSET)
+
+/* GPIO PD Pin Data Input/Output */
+
+#define NUC_PORTD_PDIO(n) (NUC_GPIO_BASE+NUC_PORTD_PDIO_OFFSET(n))
+# define NUC_PD1_PDIO (NUC_GPIO_BASE+NUC_PD1_PDIO_OFFSET)
+# define NUC_PD2_PDIO (NUC_GPIO_BASE+NUC_PD2_PDIO_OFFSET)
+# define NUC_PD3_PDIO (NUC_GPIO_BASE+NUC_PD3_PDIO_OFFSET)
+# define NUC_PD4_PDIO (NUC_GPIO_BASE+NUC_PD4_PDIO_OFFSET)
+# define NUC_PD5_PDIO (NUC_GPIO_BASE+NUC_PD5_PDIO_OFFSET)
+# define NUC_PD6_PDIO (NUC_GPIO_BASE+NUC_PD6_PDIO_OFFSET)
+# define NUC_PD7_PDIO (NUC_GPIO_BASE+NUC_PD7_PDIO_OFFSET)
+# define NUC_PD8_PDIO (NUC_GPIO_BASE+NUC_PD8_PDIO_OFFSET)
+# define NUC_PD9_PDIO (NUC_GPIO_BASE+NUC_PD9_PDIO_OFFSET)
+# define NUC_PD10_PDIO (NUC_GPIO_BASE+NUC_PD10_PDIO_OFFSET)
+# define NUC_PD11_PDIO (NUC_GPIO_BASE+NUC_PD11_PDIO_OFFSET)
+# define NUC_PD12_PDIO (NUC_GPIO_BASE+NUC_PD12_PDIO_OFFSET)
+# define NUC_PD13_PDIO (NUC_GPIO_BASE+NUC_PD13_PDIO_OFFSET)
+# define NUC_PD14_PDIO (NUC_GPIO_BASE+NUC_PD14_PDIO_OFFSET)
+# define NUC_PD15_PDIO (NUC_GPIO_BASE+NUC_PD15_PDIO_OFFSET)
+
+/* GPIO PE Pin Data Input/Output */
+
+#define NUC_PORTE_PDIO(n) (NUC_GPIO_BASE+NUC_PORTE_PDIO_OFFSET(n))
+# define NUC_PE5_PDIO (NUC_GPIO_BASE+NUC_PE5_PDIO_OFFSET)
+
+/* Register bit-field definitions ***********************************************************/
+
+/* GPIO port pin I/O mode control */
+
+#define GPIO_PMD_INPUT 0
+#define GPIO_PMD_OUTPUT 1
+#define GPIO_PMD_OPENDRAIN 2
+#define GPIO_PMD_BIDI 3
+
+#define GPIO_PMD_SHIFT(n) ((n) << 1) /* Bits 2n-2n+_1: GPIOx Pin[n] mode control */
+#define GPIO_PMD_MASK(n) (3 << GPIO_PMD_SHIFT(n))
+# define GPIO_PMD_MASK(n,v) ((v) << GPIO_PMD_SHIFT(n))
+
+#define GPIO_PMD0_SHIFT (0) /* Bits 0-1: GPIOx Pin0 mode control */
+#define GPIO_PMD0_MASK (3 << GPIO_PMD0_SHIFT)
+# define GPIO_PMD0(v) ((v) << GPIO_PMD0_SHIFT)
+#define GPIO_PMD1_SHIFT (2) /* Bits 2-3: GPIOx Pin1 mode control */
+#define GPIO_PMD1_MASK (3 << GPIO_PMD1_SHIFT)
+# define GPIO_PMD1(v) ((v) << GPIO_PMD1_SHIFT)
+#define GPIO_PMD2_SHIFT (4) /* Bits 4-5: GPIOx Pin2 mode control */
+#define GPIO_PMD2_MASK (3 << GPIO_PMD2_SHIFT)
+# define GPIO_PMD2(v) ((v) << GPIO_PMD2_SHIFT)
+#define GPIO_PMD3_SHIFT (6) /* Bits 6-7: GPIOx Pin3 mode control */
+#define GPIO_PMD3_MASK (3 << GPIO_PMD3_SHIFT)
+# define GPIO_PMD3(v) ((v) << GPIO_PMD3_SHIFT)
+#define GPIO_PMD4_SHIFT (8) /* Bits 8-9: GPIOx Pin4 mode control */
+#define GPIO_PMD4_MASK (3 << GPIO_PMD4_SHIFT)
+# define GPIO_PMD4(v) ((v) << GPIO_PMD4_SHIFT)
+#define GPIO_PMD5_SHIFT (10) /* Bits 10-11: GPIOx Pin5 mode control */
+#define GPIO_PMD5_MASK (3 << GPIO_PMD5_SHIFT)
+# define GPIO_PMD5(v) ((v) << GPIO_PMD5_SHIFT)
+#define GPIO_PMD6_SHIFT (12) /* Bits 12-13: GPIOx Pin6 mode control */
+#define GPIO_PMD6_MASK (3 << GPIO_PMD6_SHIFT)
+# define GPIO_PMD6(v) ((v) << GPIO_PMD6_SHIFT)
+#define GPIO_PMD7_SHIFT (14) /* Bits 14-15: GPIOx Pin7 mode control */
+#define GPIO_PMD7_MASK (3 << GPIO_PMD7_SHIFT)
+# define GPIO_PMD7(v) ((v) << GPIO_PMD7_SHIFT)
+#define GPIO_PMD8_SHIFT (16) /* Bits 16-17: GPIOx Pin8 mode control */
+#define GPIO_PMD8_MASK (3 << GPIO_PMD8_SHIFT)
+# define GPIO_PMD8(v) ((v) << GPIO_PMD8_SHIFT)
+#define GPIO_PMD9_SHIFT (18) /* Bits 18-19: GPIOx Pin9 mode control */
+#define GPIO_PMD9_MASK (3 << GPIO_PMD9_SHIFT)
+# define GPIO_PMD9(v) ((v) << GPIO_PMD9_SHIFT)
+#define GPIO_PMD10_SHIFT (20) /* Bits 20-21: GPIOx Pin0 mode control */
+#define GPIO_PMD10_MASK (3 << GPIO_PMD10_SHIFT)
+# define GPIO_PMD10(v) ((v) << GPIO_PMD10_SHIFT)
+#define GPIO_PMD11_SHIFT (22) /* Bits 22-23: GPIOx Pin1 mode control */
+#define GPIO_PMD11_MASK (3 << GPIO_PMD11_SHIFT)
+# define GPIO_PMD11(v) ((v) << GPIO_PMD11_SHIFT)
+#define GPIO_PMD12_SHIFT (24) /* Bits 24-25: GPIOx Pin2 mode control */
+#define GPIO_PMD12_MASK (3 << GPIO_PMD12_SHIFT)
+# define GPIO_PMD12(v) ((v) << GPIO_PMD12_SHIFT)
+#define GPIO_PMD13_SHIFT (26) /* Bits 26-27: GPIOx Pin3 mode control */
+#define GPIO_PMD13_MASK (3 << GPIO_PMD13_SHIFT)
+# define GPIO_PMD13(v) ((v) << GPIO_PMD13_SHIFT)
+#define GPIO_PMD14_SHIFT (28) /* Bits 28-29: GPIOx Pin4 mode control */
+#define GPIO_PMD14_MASK (3 << GPIO_PMD14_SHIFT)
+# define GPIO_PMD14(v) ((v) << GPIO_PMD14_SHIFT)
+#define GPIO_PMD15_SHIFT (30) /* Bits 30-31: GPIOx Pin5 mode control */
+#define GPIO_PMD15_MASK (3 << GPIO_PMD15_SHIFT)
+# define GPIO_PMD15(v) ((v) << GPIO_PMD15_SHIFT)
+
+/* GPIO port pin digital input path disable control */
+
+#define GPIO_OFFD(n) (1 << (n)) /* Bit n: GPIOx Pin[n] digital input path disable control */
+
+/* GPIO port data output value */
+
+#define GPIO_DOUT(n) (1 << (n)) /* Bit n: GPIOx Pin[n] output value */
+
+/* GPIO port data output write mask */
+
+#define GPIO_DMASK(n) (1 << (n)) /* Bit n: GPIOx Pin[n] data output write mask */
+
+/* GPIO port pin value */
+
+#define GPIO_PIN(n) (1 << (n)) /* Bit n: GPIOx Pin[n] pin value */
+
+/* GPIO port de-bounce enable */
+
+#define GPIO_DBEN(n) (1 << (n)) /* Bit n: GPIOx Pin[n] input signal de-bounce enable */
+
+/* GPIO port interrupt mode control */
+
+#define GPIO_IMD(n) (1 << (n)) /* Bit n: GPIOx Pin[n] edge/level detection interrupt control */
+
+/* GPIO port interrupt enable */
+
+#define GPIO_IF_EN(n) (1 << (n)) /* Bit n: GPIOx Pin[n] interrupt enable low/falling */
+#define GPIO_IR_EN(n) (1 << ((n)+16)) /* Bit n: GPIOx Pin[n] interrupt enable high/rising */
+
+/* GPIO port interrupt source flag */
+
+#define GPIO_ISRC(n) (1 << (n)) /* Bit n: GPIOx Pin[n] interrupt source flag */
+
+/* De-bounce cycle control register */
+
+#define GPIO_DBNCECON_DBCLKSEL_SHIFT (0) /* Bits 0-3: De-bounce cycling count selection */
+#define GPIO_DBNCECON_DBCLKSEL_MASK (15 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_1 (0 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_2 (1 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_4 (2 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_8 (3 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_16 (4 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_32 (5 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_64 (6 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_128 (7 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_256 (8 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_512 (9 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_1024 (10 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_2048 (11 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_4096 (12 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_8102 (13 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_16384 (14 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+# define GPIO_DBNCECON_DBCLKSEL_32768 (15 << GPIO_DBNCECON_DBCLKSEL_SHIFT)
+#define GPIO_DBNCECON_DBCLKSRC (1 << 4) /* Bit 4: De-bounce counter clock source selection */
+#define GPIO_DBNCECON_ICLK_ON (1 << 5) /* Bit 5: Interrupt clock on mode */
+
+/* GPIO port data I/O registers */
+
+#define PORT_MASK (1) /* Bit 0: GPIOx Pin[n] data I/O */
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_GPIO_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_i2c.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_i2c.h
new file mode 100644
index 000000000..9b30e5797
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_i2c.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_i2c.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_I2C_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_I2C_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_I2C_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_i2s.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_i2s.h
new file mode 100644
index 000000000..c94206324
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_i2s.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_i2s.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_I2S_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_I2S_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_I2S_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_pdma.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_pdma.h
new file mode 100644
index 000000000..964c01f0d
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_pdma.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_pdma.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_PDMA_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_PDMA_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_PDMA_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_ps2d.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_ps2d.h
new file mode 100644
index 000000000..f01109332
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_ps2d.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_ps2d.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_PS2D_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_PS2D_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_PS2D_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_pwm.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_pwm.h
new file mode 100644
index 000000000..49f4f25a4
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_pwm.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_pwm.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_PWM_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_PWM_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_PWM_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_rtc.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_rtc.h
new file mode 100644
index 000000000..1ec5e2bae
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_rtc.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_rtc.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_RTC_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_RTC_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_RTC_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_spi.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_spi.h
new file mode 100644
index 000000000..74f46b1db
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_spi.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_spi.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_SPI_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_SPI_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_SPI_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_tmr.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_tmr.h
new file mode 100644
index 000000000..e97615ce9
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_tmr.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_tmr.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_TMR_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_TMR_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_TMR_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_uart.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_uart.h
new file mode 100644
index 000000000..34551ba97
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_uart.h
@@ -0,0 +1,280 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_uart.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_UART_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_UART_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+#define NUC_UART_RBR_OFFSET 0x0000 /* UART receive buffer register */
+#define NUC_UART_THR_OFFSET 0x0000 /* UART transmit holding register */
+#define NUC_UART_IER_OFFSET 0x0004 /* UART interrupt enable register */
+#define NUC_UART_FCR_OFFSET 0x0008 /* UART FIFO control register */
+#define NUC_UART_LCR_OFFSET 0x000c /* UART line control register */
+#define NUC_UART_MCR_OFFSET 0x0010 /* UART modem control register */
+#define NUC_UART_MSR_OFFSET 0x0014 /* UART modem status register */
+#define NUC_UART_FSR_OFFSET 0x0018 /* UART FIFO status register */
+#define NUC_UART_ISR_OFFSET 0x001c /* UART interrupt status register */
+#define NUC_UART_TOR_OFFSET 0x0020 /* UART time out register */
+#define NUC_UART_BAUD_OFFSET 0x0024 /* UART BAUD rate divisor register */
+#define NUC_UART_IRCR_OFFSET 0x0028 /* UART IrDA control register */
+#define NUC_UART_ALT_CSR_OFFSET 0x002c /* UART alternate control/status register */
+#define NUC_UART_FUN_SEL_OFFSET 0x0030 /* UART function select register */
+
+/* Register addresses ***********************************************************************/
+
+#define NUC_UART0_RBR (NUC_UART0_BASE+NUC_UART_RBR_OFFSET)
+#define NUC_UART0_THR (NUC_UART0_BASE+NUC_UART_THR_OFFSET)
+#define NUC_UART0_IER (NUC_UART0_BASE+NUC_UART_IER_OFFSET)
+#define NUC_UART0_FCR (NUC_UART0_BASE+NUC_UART_FCR_OFFSET)
+#define NUC_UART0_LCR (NUC_UART0_BASE+NUC_UART_LCR_OFFSET)
+#define NUC_UART0_MCR (NUC_UART0_BASE+NUC_UART_MCR_OFFSET)
+#define NUC_UART0_MSR (NUC_UART0_BASE+NUC_UART_MSR_OFFSET)
+#define NUC_UART0_FSR (NUC_UART0_BASE+NUC_UART_FSR_OFFSET)
+#define NUC_UART0_ISR (NUC_UART0_BASE+NUC_UART_ISR_OFFSET)
+#define NUC_UART0_TOR (NUC_UART0_BASE+NUC_UART_TOR_OFFSET)
+#define NUC_UART0_BAUD (NUC_UART0_BASE+NUC_UART_BAUD_OFFSET)
+#define NUC_UART0_IRCR (NUC_UART0_BASE+NUC_UART_IRCR_OFFSET)
+#define NUC_UART0_ALT_CSR (NUC_UART0_BASE+NUC_UART_ALT_CSR_OFFSET)
+#define NUC_UART0_FUN_SEL (NUC_UART0_BASE+NUC_UART_FUN_SEL_OFFSET)
+
+#define NUC_UART1_RBR (NUC_UART1_BASE+NUC_UART_RBR_OFFSET)
+#define NUC_UART1_THR (NUC_UART1_BASE+NUC_UART_THR_OFFSET)
+#define NUC_UART1_IER (NUC_UART1_BASE+NUC_UART_IER_OFFSET)
+#define NUC_UART1_FCR (NUC_UART1_BASE+NUC_UART_FCR_OFFSET)
+#define NUC_UART1_LCR (NUC_UART1_BASE+NUC_UART_LCR_OFFSET)
+#define NUC_UART1_MCR (NUC_UART1_BASE+NUC_UART_MCR_OFFSET)
+#define NUC_UART1_MSR (NUC_UART1_BASE+NUC_UART_MSR_OFFSET)
+#define NUC_UART1_FSR (NUC_UART1_BASE+NUC_UART_FSR_OFFSET)
+#define NUC_UART1_ISR (NUC_UART1_BASE+NUC_UART_ISR_OFFSET)
+#define NUC_UART1_TOR (NUC_UART1_BASE+NUC_UART_TOR_OFFSET)
+#define NUC_UART1_BAUD (NUC_UART1_BASE+NUC_UART_BAUD_OFFSET)
+#define NUC_UART1_IRCR (NUC_UART1_BASE+NUC_UART_IRCR_OFFSET)
+#define NUC_UART1_ALT_CSR (NUC_UART1_BASE+NUC_UART_ALT_CSR_OFFSET)
+#define NUC_UART1_FUN_SEL (NUC_UART1_BASE+NUC_UART_FUN_SEL_OFFSET)
+
+#define NUC_UART2_RBR (NUC_UART2_BASE+NUC_UART_RBR_OFFSET)
+#define NUC_UART2_THR (NUC_UART2_BASE+NUC_UART_THR_OFFSET)
+#define NUC_UART2_IER (NUC_UART2_BASE+NUC_UART_IER_OFFSET)
+#define NUC_UART2_FCR (NUC_UART2_BASE+NUC_UART_FCR_OFFSET)
+#define NUC_UART2_LCR (NUC_UART2_BASE+NUC_UART_LCR_OFFSET)
+#define NUC_UART2_MCR (NUC_UART2_BASE+NUC_UART_MCR_OFFSET)
+#define NUC_UART2_MSR (NUC_UART2_BASE+NUC_UART_MSR_OFFSET)
+#define NUC_UART2_FSR (NUC_UART2_BASE+NUC_UART_FSR_OFFSET)
+#define NUC_UART2_ISR (NUC_UART2_BASE+NUC_UART_ISR_OFFSET)
+#define NUC_UART2_TOR (NUC_UART2_BASE+NUC_UART_TOR_OFFSET)
+#define NUC_UART2_BAUD (NUC_UART2_BASE+NUC_UART_BAUD_OFFSET)
+#define NUC_UART2_IRCR (NUC_UART2_BASE+NUC_UART_IRCR_OFFSET)
+#define NUC_UART2_ALT_CSR (NUC_UART2_BASE+NUC_UART_ALT_CSR_OFFSET)
+#define NUC_UART2_FUN_SEL (NUC_UART2_BASE+NUC_UART_FUN_SEL_OFFSET)
+
+/* Register bit-field definitions ***********************************************************/
+
+/* UART receive buffer register */
+
+#define UART_RBR_MASK (0xff)
+
+/* UART transmit holding register */
+
+#define UART_THR_MASK (0xff)
+
+/* UART interrupt enable register */
+
+#define UART_IER_RDA_IEN (1 << 0) /* Bit 0: Receive data avaiable interrupt enable */
+#define UART_IER_THRE_IEN (1 << 1) /* Bit 1: Transmit holding register empty interrupt enable */
+#define UART_IER_RLS_IEN (1 << 2) /* Bit 2: Receive line status interrupt enable */
+#define UART_IER_MODEM_IEN (1 << 3) /* Bit 3: Modem status interrupt enable (UART0/1) */
+#define UART_IER_RTO_IEN (1 << 4) /* Bit 4: RX timeout interrupt enable */
+#define UART_IER_BUF_ERR_IEN (1 << 5) /* Bit 5: Buffer error interrupt enable */
+#define UART_IER_WAKE_EN (1 << 6) /* Bit 6: UART wake-up function enabled (UART0/1) */
+#define UART_IER_TIME_OUT_EN (1 << 11) /* Bit 11: Time out counter enable */
+#define UART_IER_AUTO_RTS_EN (1 << 12) /* Bit 12: RTS auto flow control enable (UART0/1) */
+#define UART_IER_AUTO_CTS_EN (1 << 13) /* Bit 13: CTS auto flow control enable (UART0/1) */
+#define UART_IER_DMA_TX_EN (1 << 14) /* Bit 14: TX DMA enable (UART0/1) */
+#define UART_IER_DMA_RX_EN (1 << 15) /* Bit 15: RX DMA enable (UART0/1) */
+
+/* UART FIFO control register */
+
+#define UART_FCR_RFR (1 << 1) /* Bit 1: RX filed software reset */
+#define UART_FCR_TFR (1 << 2) /* Bit 2: TX field softweare reset */
+#define UART_FCR_FRITL_SHIFT (4) /* Bits 4-7: RX FIFO interrupt trigger level */
+#define UART_FCR_FRITL_MASK (15 << UART_FCR_FRITL_SHIFT)
+# define UART_FCR_FRITL_1 (0 << UART_FCR_FRITL_SHIFT)
+# define UART_FCR_FRITL_4 (1 << UART_FCR_FRITL_SHIFT)
+# define UART_FCR_FRITL_8 (2 << UART_FCR_FRITL_SHIFT)
+# define UART_FCR_FRITL_14 (3 << UART_FCR_FRITL_SHIFT)
+# define UART_FCR_FRITL_30 (4 << UART_FCR_FRITL_SHIFT) /* High speed */
+# define UART_FCR_FRITL_46 (5 << UART_FCR_FRITL_SHIFT) /* High speed */
+# define UART_FCR_FRITL_62 (6 << UART_FCR_FRITL_SHIFT) /* High speed */
+#define UART_FCR_RX_DIS (1 << 8) /* Bit 8: Recive disable register */
+#define UART_FCR_RTS_TRI_LEV_SHIFT (16) /* Bits 16-19: RTS trigger level for auto flow control */
+#define UART_FCR_RTS_TRI_LEV_MASK (15 << UART_FCR_RTS_TRI_LEV_SHIFT)
+# define UART_FCR_RTS_TRI_LEV_1 (0 << UART_FCR_RTS_TRI_LEV_SHIFT)
+# define UART_FCR_RTS_TRI_LEV_4 (1 << UART_FCR_RTS_TRI_LEV_SHIFT)
+# define UART_FCR_RTS_TRI_LEV_8 (2 << UART_FCR_RTS_TRI_LEV_SHIFT)
+# define UART_FCR_RTS_TRI_LEV_14 (3 << UART_FCR_RTS_TRI_LEV_SHIFT)
+# define UART_FCR_RTS_TRI_LEV_30 (4 << UART_FCR_RTS_TRI_LEV_SHIFT) /* High speed */
+# define UART_FCR_RTS_TRI_LEV_46 (5 << UART_FCR_RTS_TRI_LEV_SHIFT) /* High speed */
+# define UART_FCR_RTS_TRI_LEV_62 (6 << UART_FCR_RTS_TRI_LEV_SHIFT) /* High speed */
+
+/* UART line control register */
+
+#define UART_LCR_WLS_SHIFT (0) /* Bits 0-1: Word length select */
+#define UART_LCR_WLS_MASK (3 << UART_LCR_WLS_SHIFT)
+# define UART_LCR_WLS_5 (0 << UART_LCR_WLS_SHIFT)
+# define UART_LCR_WLS_6 (1 << UART_LCR_WLS_SHIFT)
+# define UART_LCR_WLS_7 (2 << UART_LCR_WLS_SHIFT)
+# define UART_LCR_WLS_8 (3 << UART_LCR_WLS_SHIFT)
+#define UART_LCR_NSB (1 << 2) /* Bit 2: Number of stop bits */
+#define UART_LCR_PBE (1 << 3) /* Bit 3: Parity enable bit */
+#define UART_LCR_EPE (1 << 4) /* Bit 4: Even parity enable bit */
+#define UART_LCR_SPE (1 << 5) /* Bit 5: Sticky parity enable bit */
+#define UART_LCR_BCB (1 << 6) /* Bit 6: Break control bit */
+
+/* UART modem control register */
+
+#define UART_MCR_RTS (1 << 1) /* Bit 1: RTS signal (UART0/1) */
+#define UART_MCR_LEV_RTS (1 << 9) /* Bit 9: RTS trigger level (UART0/1) */
+#define UART_MCR_RTS_ST (1 << 13) /* Bit 13: RTS pin state (UART0/1) */
+
+/* UART modem status register */
+
+#define UART_MSR_DCTSF (1 << 0) /* Bit 0: CTS state change detected (UART0/1) */
+#define UART_MSR_CTS_ST (1 << 4) /* Bit 4: CTS pin status (UART0/1) */
+#define UART_MSR_LEV_CTS (1 << 8) /* Bit 8: CTS trigger level (UART0/1) */
+
+/* UART FIFO status register */
+
+#define UART_FSR_RX_OVER_IF (1 << 0) /* Bit 0: RX overflow error interrupt flag */
+#define UART_FSR_RS485_ADD_DETF (1 << 3) /* Bit 3: RS-485 address byte detection flag */
+#define UART_FSR_PEF (1 << 4) /* Bit 4: Parity error flag */
+#define UART_FSR_FEF (1 << 5) /* Bit 5: Framing error flag */
+#define UART_FSR_BIF (1 << 6) /* Bit 6: Break interrupt flag */
+#define UART_FSR_RX_POINTER_SHIFT (8) /* Bits 8-13: RX FIFO pointer */
+#define UART_FSR_RX_POINTER_MASK (0x3f << UART_FSR_RX_POINTER_SHIFT)
+#define UART_FSR_RX_EMPTY (1 << 14) /* Bit 14: Receiver FIFO emtpy */
+#define UART_FSR_TX_POINTER_SHIFT (16) /* Bits 16-21: TX FIFO pointer */
+#define UART_FSR_TX_POINTER_MASK (0x3f << UART_FSR_TX_POINTER_SHIFT)
+#define UART_FSR_TX_EMPTY (1 << 22) /* Bit 22: Transmitter FIFO empty flag */
+#define UART_FSR_TX_OVER_IF (1 << 24) /* Bit 24: TX overflow error interrupt flag */
+#define UART_FSR_TE_FLAG (1 << 28) /* Bit 28: Transmitter empty flag */
+
+/* UART interrupt status register */
+#define UART_ISR_
+
+#define UART_ISR_RDA_IF (1 << 0) /* Bit 0: Receive data avaiable interrupt flag */
+#define UART_ISR_THRE_IF (1 << 1) /* Bit 1: Transmit holding register empty interrupt flag */
+#define UART_ISR_RLS_IF (1 << 2) /* Bit 2: Receive line status interrupt flag */
+#define UART_ISR_MODEM_IF (1 << 3) /* Bit 3: Modem interrupt flag (UART0/1) */
+#define UART_ISR_TOUT_IF (1 << 4) /* Bit 4: Timeout interrupt flag */
+#define UART_ISR_BUF_ERR_IF (1 << 5) /* Bit 5: Buffer error interrupt flag */
+#define UART_ISR_RDA_INT (1 << 8) /* Bit 8: Receive data avaiable interrupt indicator */
+#define UART_ISR_THRE_INT (1 << 9) /* Bit 9: Transmit holding register empty interrupt indicator */
+#define UART_ISR_RLS_INT (1 << 10) /* Bit 10: Receive line status interrupt indicator */
+#define UART_ISR_MODEM_INT (1 << 11) /* Bit 11: Modem interrupt indicator (UART0/1) */
+#define UART_ISR_TOUT_INT (1 << 12) /* Bit 12: Timeout interrupt indicator */
+#define UART_ISR_BUF_ERR_INT (1 << 13) /* Bit 13: Buffer error interrupt indicator */
+#define UART_ISR_HW_RLS_IF (1 << 18) /* Bit 18: DMA mode receive line status interrupt flag */
+#define UART_ISR_HW_MODEM_IF (1 << 19) /* Bit 19: DMA mode modem interrupt flag (UART0/1) */
+#define UART_ISR_HW_TOUT_IF (1 << 20) /* Bit 20: DMA mode timeout interrupt flag */
+#define UART_ISR_HW_BUF_ERR_IF (1 << 21) /* Bit 21: DMA mode buffer error interrupt flag */
+#define UART_ISR_HW_RLS_INT (1 << 26) /* Bit 26: DMA mode receive line status interrupt indicator */
+#define UART_ISR_HW_MODEM_INT (1 << 27) /* Bit 27: DMA mode modem interrupt indicator (UART0/1) */
+#define UART_ISR_HW_TOUT_INT (1 << 28) /* Bit 28: DMA mode timeout interrupt indicator */
+#define UART_ISR_HW_BUF_ERR_INT (1 << 29) /* Bit 29: DMA mode buffer error interrupt indicator */
+
+/* UART time out register */
+
+#define UART_TOR_TOIC_SHIFT (0) /* Bits 0-7: Time out interrupt comparator */
+#define UART_TOR_TOIC_MASK (0xff << UART_TOR_TOIC_SHIFT)
+#define UART_TOR_DLY_SHIFT (8) /* Bits 8-15: TX delay time value */
+#define UART_TOR_DLY_MASK (0xff << UART_TOR_DLY_SHIFT)
+
+/* UART BAUD rate divisor register */
+
+#define UART_BAUD_BRD_SHIFT (0) /* Bits 0-15: Baud rate divider */
+#define UART_BAUD_BRD_MASK (0xffff << UART_BAUD_BRD_SHIFT)
+#define UART_BAUD_DIVIDER_X_SHIFT (24) /* Bits 24-27: Divider X */
+#define UART_BAUD_DIVIDER_X_MASK (15 << UART_BAUD_DIVIDER_X_SHIFT)
+#define UART_BAUD_DIV_X_OINE (1 << 28) /* Bit 28: Divider X equals one */
+#define UART_BAUD_DIV_X_EN (1 << 29) /* Bit 29: Divider X enable */
+
+/* UART IrDA control register */
+
+#define UART_IRCR_TX_SELECT (1 << 0) /* Bit 0: Invert RX input signal */
+#define UART_IRCR_INV_TX (1 << 1) /* Bit 1: Invert TX output signal */
+#define UART_IRCR_INV_RX (1 << 2) /* Bit 2: Enable IrDA transmitter */
+
+/* UART alternate control/status register */
+
+#define UART_ALT_CSR_RS485_NMM (1 << 8) /* Bit 8: RS-485 normal multi-drop operation mode (NMM) */
+#define UART_ALT_CSR_RS485_AAD (1 << 9) /* Bit 9: RS-485 auto address detection operation mode (AAD) */
+#define UART_ALT_CSR_RS485_AUD (1 << 10) /* Bit 10: RS-485 auto direction mode (AUD) */
+#define UART_ALT_CSR_RS485_ADD_EN (1 << 15) /* Bit 15: RS-485 address detection enable */
+#define UART_ALT_CSR_ADDR_MATCH_SHIFT (24) /* Bits 24-31: Address match value */
+#define UART_ALT_CSR_ADDR_MATCH_MASK (0xff << UART_ALT_CSR_ADDR_MATCH_SHIFT)
+
+/* UART function select register */
+
+#define UART_FUN_SEL_SHIFT (0) /* Bits 0-1: Function select enable */
+#define UART_FUN_SEL_MASK (3 << UART_FUN_SEL_SHIFT)
+# define UART_FUN_SEL_UART (0 << UART_FUN_SEL_SHIFT)
+# define UART_FUN_SEL_IRDA (2 << UART_FUN_SEL_SHIFT)
+# define UART_FUN_SEL_RS485 (3 << UART_FUN_SEL_SHIFT) /* Low density only */
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_UART_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_usbd.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_usbd.h
new file mode 100644
index 000000000..d950c3e8f
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_usbd.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_usbd.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_USBD_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_USBD_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_USBD_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_wdt.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_wdt.h
new file mode 100644
index 000000000..458efe977
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_wdt.h
@@ -0,0 +1,71 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/chip/nuc_wdt.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_CHIP_NUC_WDT_H
+#define __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_WDT_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+/* Register offsets *************************************************************************/
+
+
+/* Register addresses ***********************************************************************/
+
+
+/* Register bit-field definitions ***********************************************************/
+
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_CHIP_NUC_WDT_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_config.h b/nuttx/arch/arm/src/nuc1xx/nuc_config.h
new file mode 100644
index 000000000..5d175d5cd
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_config.h
@@ -0,0 +1,126 @@
+/************************************************************************************
+ * arch/arm/src/nuc1xx/nuc_config.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_NUC_CONFIG_H
+#define __ARCH_ARM_SRC_NUC1XX_NUC_CONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Limit the number of enabled UARTs to those supported by the chip architecture */
+
+#if NUC_NUARTS < 3
+# undef CONFIG_NUC_UART2
+#endif
+
+#if NUC_NUARTS < 2
+# undef CONFIG_NUC_UART1
+#endif
+
+#if NUC_NUARTS < 1
+# undef CONFIG_NUC_UART0
+#endif
+
+/* Are any UARTs enabled? */
+
+#undef HAVE_UART
+#if defined(CONFIG_NUC_UART0) || defined(CONFIG_NUC_UART1) || defined(CONFIG_NUC_UART2)
+# define HAVE_UART 1
+#endif
+
+/* Make sure all features are disabled for diabled U[S]ARTs. This simplifies
+ * checking later.
+ */
+
+#ifndef CONFIG_NUC_UART0
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART0_IRDAMODE
+# undef CONFIG_UART0_RS485MODE
+#endif
+
+#ifndef CONFIG_NUC_UART1
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART1_IRDAMODE
+# undef CONFIG_UART1_RS485MODE
+#endif
+
+#ifndef CONFIG_NUC_UART2
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef CONFIG_UART2_IRDAMODE
+# undef CONFIG_UART2_RS485MODE
+#endif
+
+/* Is there a serial console? There should be at most one defined. It could be on
+ * any UARTn, n=0,1,2 - OR - there might not be any serial console at all.
+ */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE)
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# define HAVE_CONSOLE 1
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# define HAVE_CONSOLE 1
+#elif defined(CONFIG_UART2_SERIAL_CONSOLE)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# define HAVE_CONSOLE 1
+#else
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+# undef HAVE_CONSOLE
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_NUC_CONFIG_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
new file mode 100644
index 000000000..b251ddbe6
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
@@ -0,0 +1,64 @@
+/********************************************************************************************
+ * arch/arm/src/nuc1xx/nuc_gpio.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_NUC1XX_NUC_GPIO_H
+#define __ARCH_ARM_SRC_NUC1XX_NUC_GPIO_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/chip/nuc_gpio.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Data
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Functions
+ ********************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_NUC1XX_NUC_GPIO_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_start.c b/nuttx/arch/arm/src/nuc1xx/nuc_start.c
new file mode 100644
index 000000000..767e959b4
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_start.c
@@ -0,0 +1,140 @@
+/****************************************************************************
+ * arch/arm/src/nuc1xx/nuc_start.c
+ * arch/arm/src/chip/nuc_start.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/init.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+#include "nuc_gpio.h"
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: showprogress
+ *
+ * Description:
+ * Print a character on the UART to show boot status.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+# define showprogress(c) up_lowputc(c)
+#else
+# define showprogress(c)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _start
+ *
+ * Description:
+ * This is the reset entry point.
+ *
+ ****************************************************************************/
+
+void __start(void)
+{
+ const uint32_t *src;
+ uint32_t *dest;
+
+ /* Configure the uart so that we can get debug output as soon as possible */
+
+ nuc_clockconfig();
+ nuc_lowsetup();
+ nuc_gpioinit();
+ showprogress('A');
+
+ /* Clear .bss. We'll do this inline (vs. calling memset) just to be
+ * certain that there are no issues with the state of global variables.
+ */
+
+ for (dest = &_sbss; dest < &_ebss; )
+ {
+ *dest++ = 0;
+ }
+ showprogress('B');
+
+ /* Move the intialized data section from his temporary holding spot in
+ * FLASH into the correct place in SRAM. The correct place in SRAM is
+ * give by _sdata and _edata. The temporary location is in FLASH at the
+ * end of all of the other read-only data (.text, .rodata) at _eronly.
+ */
+
+ for (src = &_eronly, dest = &_sdata; dest < &_edata; )
+ {
+ *dest++ = *src++;
+ }
+ showprogress('C');
+
+ /* Perform early serial initialization */
+
+#ifdef USE_EARLYSERIALINIT
+ up_earlyserialinit();
+#endif
+ showprogress('D');
+
+ /* Initialize onboard resources */
+
+ nuc_boardinitialize();
+ showprogress('E');
+
+ /* Then start NuttX */
+
+ showprogress('\r');
+ showprogress('\n');
+ os_start();
+
+ /* Shoulnd't get here */
+
+ for(;;);
+}
diff --git a/nuttx/arch/arm/src/stm32/stm32_start.c b/nuttx/arch/arm/src/stm32/stm32_start.c
index c6a176e5f..b90beeb16 100644
--- a/nuttx/arch/arm/src/stm32/stm32_start.c
+++ b/nuttx/arch/arm/src/stm32/stm32_start.c
@@ -2,7 +2,7 @@
* arch/arm/src/stm32/stm32_start.c
* arch/arm/src/chip/stm32_start.c
*
- * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -34,6 +34,10 @@
*
****************************************************************************/
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
#include <nuttx/config.h>
#include <stdint.h>
@@ -54,6 +58,10 @@
#endif
/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: showprogress
*
* Description:
@@ -68,10 +76,6 @@
#endif
/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
* Name: stm32_fpuconfig
*
* Description:
diff --git a/nuttx/configs/lincoln60/include/board.h b/nuttx/configs/lincoln60/include/board.h
index b616689ec..ca6aeb7ba 100644
--- a/nuttx/configs/lincoln60/include/board.h
+++ b/nuttx/configs/lincoln60/include/board.h
@@ -124,8 +124,8 @@
/* FLASH Configuration */
-#undef CONFIG_LP17_FLASH
-#define CONFIG_LP17_FLASH 1
+#undef CONFIG_LPC17_FLASH
+#define CONFIG_LPC17_FLASH 1
#define BOARD_FLASHCFG_VALUE 0x0000303a
/* LED definitions *********************************************************/
diff --git a/nuttx/configs/lpcxpresso-lpc1768/include/board.h b/nuttx/configs/lpcxpresso-lpc1768/include/board.h
index 10af5dfc1..086e30c81 100644
--- a/nuttx/configs/lpcxpresso-lpc1768/include/board.h
+++ b/nuttx/configs/lpcxpresso-lpc1768/include/board.h
@@ -119,8 +119,8 @@
/* FLASH Configuration */
-#undef CONFIG_LP17_FLASH
-#define CONFIG_LP17_FLASH 1
+#undef CONFIG_LPC17_FLASH
+#define CONFIG_LPC17_FLASH 1
#define BOARD_FLASHCFG_VALUE 0x0000303a
/* Ethernet configuration */
diff --git a/nuttx/configs/mbed/include/board.h b/nuttx/configs/mbed/include/board.h
index b2bda1f4c..eb35fbc3e 100644
--- a/nuttx/configs/mbed/include/board.h
+++ b/nuttx/configs/mbed/include/board.h
@@ -119,8 +119,8 @@
/* FLASH Configuration */
-#undef CONFIG_LP17_FLASH
-#define CONFIG_LP17_FLASH 1
+#undef CONFIG_LPC17_FLASH
+#define CONFIG_LPC17_FLASH 1
#define BOARD_FLASHCFG_VALUE 0x0000303a
/* LED definitions ******************************************************************/
diff --git a/nuttx/configs/nucleus2g/include/board.h b/nuttx/configs/nucleus2g/include/board.h
index 88fc2164c..7682a5df8 100644
--- a/nuttx/configs/nucleus2g/include/board.h
+++ b/nuttx/configs/nucleus2g/include/board.h
@@ -119,8 +119,8 @@
/* FLASH Configuration */
-#undef CONFIG_LP17_FLASH
-#define CONFIG_LP17_FLASH 1
+#undef CONFIG_LPC17_FLASH
+#define CONFIG_LPC17_FLASH 1
#define BOARD_FLASHCFG_VALUE 0x0000303a
/* LED definitions ******************************************************************/
diff --git a/nuttx/configs/nutiny-nuc120/include/Makefile b/nuttx/configs/nutiny-nuc120/include/Makefile
deleted file mode 100644
index e69de29bb..000000000
--- a/nuttx/configs/nutiny-nuc120/include/Makefile
+++ /dev/null
diff --git a/nuttx/configs/nutiny-nuc120/include/board.h b/nuttx/configs/nutiny-nuc120/include/board.h
index dab279878..276ce5d04 100644
--- a/nuttx/configs/nutiny-nuc120/include/board.h
+++ b/nuttx/configs/nutiny-nuc120/include/board.h
@@ -34,8 +34,8 @@
*
************************************************************************************/
-#ifndef _BITNO
-#define _BITNO
+#ifndef __CONFIGS_NUTINY_NUC12_INCLUDE_BOARD_H
+#define __CONFIGS_NUTINY_NUC12_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
@@ -54,18 +54,11 @@
/* LED definitions ******************************************************************/
/* The NuTiny has a single green LED that can be controlled from sofware. This LED
- * is connected to PIN17.
+ * is connected to PIN17. It is pulled high so a low value will illuminate the LED.
*/
-/* LED index values for use with nuc_setled() */
-
-#define BOARD_LED 0 /* Green LED */
#define BOARD_NLEDS 1
-/* LED bits for use with nuc_setleds() */
-
-#define BOARD_LED_BIT (1 << BOARD_LED)
-
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board the
* NuTiny. The following definitions describe how NuttX controls the LEDs:
*
@@ -80,7 +73,7 @@
* LED_SIGNAL In a signal handler LED might glow
* LED_ASSERTION An assertion failed LED ON while handling the assertion
* LED_PANIC The system has crashed LED Blinking at 2Hz
- * LED_IDLE STM32 is is sleep mode (Optional, not used)
+ * LED_IDLE NUC1XX is is sleep mode (Optional, not used)
*/
#define LED_STARTED 0
@@ -106,7 +99,8 @@
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -118,29 +112,13 @@ extern "C" {
* Name: nuc_boardinitialize
*
* Description:
- * All STM32 architectures must provide the following entry point. This entry point
+ * All NUC1XX architectures must provide the following entry point. This entry point
* is called early in the intitialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
-EXTERN void nuc_boardinitialize(void);
-
-/************************************************************************************
- * Name: nuc_ledinit, nuc_setled, and nuc_setleds
- *
- * Description:
- * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
- * CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
- * control the LEDs from user applications.
- *
- ************************************************************************************/
-
-#ifndef CONFIG_ARCH_LEDS
-EXTERN void nuc_ledinit(void);
-EXTERN void nuc_setled(int led, bool ledon);
-EXTERN void nuc_setleds(uint8_t ledset);
-#endif
+void nuc_boardinitialize(void);
#undef EXTERN
#if defined(__cplusplus)
@@ -148,4 +126,4 @@ EXTERN void nuc_setleds(uint8_t ledset);
#endif
#endif /* __ASSEMBLY__ */
-#endif /* _BITNO */
+#endif /* __CONFIGS_NUTINY_NUC12_INCLUDE_BOARD_H */
diff --git a/nuttx/configs/nutiny-nuc120/src/Makefile b/nuttx/configs/nutiny-nuc120/src/Makefile
new file mode 100644
index 000000000..7f05612d8
--- /dev/null
+++ b/nuttx/configs/nutiny-nuc120/src/Makefile
@@ -0,0 +1,116 @@
+############################################################################
+# configs/nutiny-nuc120/src/Makefile
+#
+# Copyright (C) 2013 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = nuc_boardinitialize.c
+
+ifeq ($(CONFIG_HAVE_CXX),y)
+CSRCS += nuc_cxxinitialize.c
+endif
+
+ifeq ($(CONFIG_ARCH_LEDS),y)
+CSRCS += nuc_led.c
+endif
+
+ifeq ($(CONFIG_NUC1XX_USBD),y)
+CSRCS += nuc_usbd.c
+endif
+
+ifeq ($(CONFIG_PWM),y)
+CSRCS += nuc_pwm.c
+endif
+
+ifeq ($(CONFIG_QENCODER),y)
+CSRCS += nuc_qencoder.c
+endif
+
+ifeq ($(CONFIG_WATCHDOG),y)
+CSRCS += nuc_watchdog.c
+endif
+
+ifeq ($(CONFIG_NSH_ARCHINIT),y)
+CSRCS += nuc_nsh.c
+endif
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+ CFLAGS += -I$(ARCH_SRCDIR)\chip -I$(ARCH_SRCDIR)\common -I$(ARCH_SRCDIR)\armv7-m
+else
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ $(Q) touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, libboard$(LIBEXT))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
diff --git a/nuttx/configs/nutiny-nuc120/src/nuc_boardinitialize.c b/nuttx/configs/nutiny-nuc120/src/nuc_boardinitialize.c
new file mode 100644
index 000000000..490413d3b
--- /dev/null
+++ b/nuttx/configs/nutiny-nuc120/src/nuc_boardinitialize.c
@@ -0,0 +1,102 @@
+/************************************************************************************
+ * configs/nutiny-nuc120/src/up_boot.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "nutiny-nuc120.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: nuc_boardinitialize
+ *
+ * Description:
+ * All NUC1XX architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void nuc_boardinitialize(void)
+{
+ /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
+ * nuc_spiinitialize() has been brought into the link.
+ */
+
+#if defined(CONFIG_NUC1XX_SPI1) || defined(CONFIG_NUC1XX_SPI2) || defined(CONFIG_NUC1XX_SPI3)
+ if (nuc_spiinitialize)
+ {
+ nuc_spiinitialize();
+ }
+#endif
+
+ /* Initialize USB if the 1) USB device controller is in the configuration and 2)
+ * disabled, and 3) the weak function nuc_usbinitialize() has been brought
+ * into the build. Presumeably either CONFIG_USBDEV is also selected.
+ */
+
+#ifdef CONFIG_NUC1XX_USB
+ if (nuc_usbinitialize)
+ {
+ nuc_usbinitialize();
+ }
+#endif
+
+ /* Configure on-board LED if LED support has been selected. */
+
+#ifdef CONFIG_ARCH_LEDS
+ nuc_ledinit();
+#endif
+}
diff --git a/nuttx/configs/nutiny-nuc120/src/nuc_led.c b/nuttx/configs/nutiny-nuc120/src/nuc_led.c
new file mode 100644
index 000000000..873a116e3
--- /dev/null
+++ b/nuttx/configs/nutiny-nuc120/src/nuc_led.c
@@ -0,0 +1,132 @@
+/****************************************************************************
+ * configs/nutiny-nuc120/src/up_autoleds.c
+ * arch/arm/src/board/up_autoleds.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+/* The NuTiny has a single green LED that can be controlled from sofware.
+ * This LED is connected to PIN17. It is pulled high so a low value will
+ * illuminate the LED.
+ *
+ * If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board the
+ * NuTiny. The following definitions describe how NuttX controls the LEDs:
+ *
+ * SYMBOL Meaning LED state
+ * Initially all LED is OFF
+ * ------------------- ----------------------- ------------- ------------
+ * LED_STARTED NuttX has been started LED ON
+ * LED_HEAPALLOCATE Heap has been allocated LED ON
+ * LED_IRQSENABLED Interrupts enabled LED ON
+ * LED_STACKCREATED Idle stack created LED ON
+ * LED_INIRQ In an interrupt LED should glow
+ * LED_SIGNAL In a signal handler LED might glow
+ * LED_ASSERTION An assertion failed LED ON while handling the assertion
+ * LED_PANIC The system has crashed LED Blinking at 2Hz
+ * LED_IDLE NUC1XX is is sleep mode (Optional, not used)
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "nuc_gpio.h"
+#include "nutiny-nuc120.h"
+
+#ifdef CONFIG_ARCH_LEDS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG with
+ * CONFIG_DEBUG_VERBOSE too)
+ */
+
+#undef LED_DEBUG /* Define to enable debug */
+
+#ifdef LED_DEBUG
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+void up_ledinit(void)
+{
+ nuc_configgpio(GPIO_LED);
+}
+
+/****************************************************************************
+ * Name: up_ledon
+ ****************************************************************************/
+
+void up_ledon(int led)
+{
+ nuc_gpiowrite(GPIO_LED, false);
+}
+
+/****************************************************************************
+ * Name: up_ledoff
+ ****************************************************************************/
+
+void up_ledoff(int led)
+{
+ nuc_gpiowrite(GPIO_LED, true);
+}
+
+#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/nutiny-nuc120/src/nutiny-nuc120.h b/nuttx/configs/nutiny-nuc120/src/nutiny-nuc120.h
new file mode 100644
index 000000000..f7f3184bc
--- /dev/null
+++ b/nuttx/configs/nutiny-nuc120/src/nutiny-nuc120.h
@@ -0,0 +1,116 @@
+/****************************************************************************************************
+ * configs/nutiny-nuc120/src/nutiny-nuc120.h
+ * arch/arm/src/board/nutiny-nuc120.n
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 __CONFIGS_NUTINY_NUC120_SRC_NUTINY_NUC120_H
+#define __CONFIGS_NUTINY_NUC120_SRC_NUTINY_NUC120_H
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+/* Configuration ************************************************************************************/
+
+/* NuTiny-EVB-120 GPIOs *****************************************************************************/
+/* The NuTiny has a single green LED that can be controlled from sofware. This LED
+ * is connected to PIN17. It is pulled high so a low value will illuminate the LED.
+ *
+ * If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board the
+ * NuTiny. The following definitions describe how NuttX controls the LEDs:
+ *
+ * SYMBOL Meaning LED state
+ * Initially all LED is OFF
+ * ------------------- ----------------------- ------------- ------------
+ * LED_STARTED NuttX has been started LED ON
+ * LED_HEAPALLOCATE Heap has been allocated LED ON
+ * LED_IRQSENABLED Interrupts enabled LED ON
+ * LED_STACKCREATED Idle stack created LED ON
+ * LED_INIRQ In an interrupt LED should glow
+ * LED_SIGNAL In a signal handler LED might glow
+ * LED_ASSERTION An assertion failed LED ON while handling the assertion
+ * LED_PANIC The system has crashed LED Blinking at 2Hz
+ * LED_IDLE NUC1XX is is sleep mode (Optional, not used)
+ */
+
+/* Button definitions ***************************************************************/
+/* The NuTiny has no buttons */
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public data
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Name: nuc_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the NuTiny-EVB-120 board.
+ *
+ ****************************************************************************************************/
+
+void weak_function nuc_spiinitialize(void);
+
+/****************************************************************************************************
+ * Name: nuc_usbinitialize
+ *
+ * Description:
+ * Called from nuc_usbinitialize very early in inialization to setup USB-related
+ * GPIO pins for the NuTiny-EVB-120 board.
+ *
+ ****************************************************************************************************/
+
+#ifdef CONFIG_STM32_USB
+void weak_function nuc_usbinitialize(void);
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_NUTINY_NUC120_SRC_NUTINY_NUC120_H */
+
diff --git a/nuttx/configs/olimex-lpc1766stk/include/board.h b/nuttx/configs/olimex-lpc1766stk/include/board.h
index 94fd74fee..172ce6cc0 100644
--- a/nuttx/configs/olimex-lpc1766stk/include/board.h
+++ b/nuttx/configs/olimex-lpc1766stk/include/board.h
@@ -124,8 +124,8 @@
/* FLASH Configuration */
-#undef CONFIG_LP17_FLASH
-#define CONFIG_LP17_FLASH 1
+#undef CONFIG_LPC17_FLASH
+#define CONFIG_LPC17_FLASH 1
#define BOARD_FLASHCFG_VALUE 0x0000303a
/* Ethernet configuration */
diff --git a/nuttx/configs/open1788/include/board.h b/nuttx/configs/open1788/include/board.h
index 4f1d83349..f7c848e47 100644
--- a/nuttx/configs/open1788/include/board.h
+++ b/nuttx/configs/open1788/include/board.h
@@ -57,11 +57,11 @@
* because the including C file may not have that file in its include path.
*/
-#define BOARD_XTAL_FREQUENCY (12000000) /* XTAL oscillator frequency */
-#define BOARD_OSCCLK_FREQUENCY BOARD_XTAL_FREQUENCY /* Main oscillator frequency */
-#define BOARD_RTCCLK_FREQUENCY (32768) /* RTC oscillator frequency */
-#define BOARD_INTRCOSC_FREQUENCY (4000000) /* Internal RC oscillator frequency */
-#define BOARD_WDTOSC_FREQUENCY (500000) /* WDT oscillator frequency */
+#define BOARD_XTAL_FREQUENCY (12000000) /* XTAL oscillator frequency */
+#define BOARD_OSCCLK_FREQUENCY BOARD_XTAL_FREQUENCY /* Main oscillator frequency */
+#define BOARD_RTCCLK_FREQUENCY (32768) /* RTC oscillator frequency */
+#define BOARD_INTRCOSC_FREQUENCY (4000000) /* Internal RC oscillator frequency */
+#define BOARD_WDTOSC_FREQUENCY (500000) /* WDT oscillator frequency */
/* This is the clock setup we configure for:
*
@@ -71,6 +71,7 @@
*/
#define LPC17_CCLK 120000000 /* 120Mhz */
+#define LPC17_PCLKDIV 2 /* Peripheral clock = LPC17_CCLK/2 */
/* Select the main oscillator as the frequency source. SYSCLK is then the frequency
* of the main oscillator.
@@ -87,7 +88,7 @@
#define BOARD_CCLKCFG_DIVIDER 6
#define BOARD_CCLKCFG_VALUE ((BOARD_CCLKCFG_DIVIDER-1) << SYSCON_CCLKCFG_CCLKDIV_SHIFT)
-/* PLL0. PLL0 is used to generate the CPU clock divider input (PLLCLK).
+/* PLL0. PLL0 is used to generate the CPU clock (PLLCLK).
*
* Source clock: Main oscillator
* PLL0 Multiplier value (M): 10
@@ -106,16 +107,17 @@
(((BOARD_PLL0CFG_MSEL-1) << SYSCON_PLLCFG_MSEL_SHIFT) | \
((BOARD_PLL0CFG_PSEL-1) << SYSCON_PLLCFG_PSEL_SHIFT))
-#ifdef (CONFIG_LPC17_USBHOST || CONFIG_LPC17_USBDEV)
/* PLL1 : PLL1 is used to generate clock for the USB */
#undef CONFIG_LPC17_PLL1
- #define CONFIG_LPC17_PLL1 1
- #define BOARD_PLL1CFG_MSEL 4
- #define BOARD_PLL1CFG_PSEL 2
+ #define CONFIG_LPC17_PLL1 1
+ #define BOARD_PLL1CFG_MSEL 4
+ #define BOARD_PLL1CFG_PSEL 2
#define BOARD_PLL1CFG_VALUE \
(((BOARD_PLL1CFG_MSEL-1) << SYSCON_PLLCFG_MSEL_SHIFT) | \
- ((BOARD_PLL1CFG_NSEL-1) << SYSCON_PLLCFG_PSEL_SHIFT))
+ ((BOARD_PLL1CFG_PSEL-1) << SYSCON_PLLCFG_PSEL_SHIFT))
+
+#if defined(CONFIG_LPC17_USBHOST) || (CONFIG_LPC17_USBDEV)
/* USB divider. The output of the PLL is used as the USB clock
*
@@ -128,8 +130,8 @@
/* FLASH Configuration */
-#undef CONFIG_LP17_FLASH
-#define CONFIG_LP17_FLASH 1
+#undef CONFIG_LPC17_FLASH
+#define CONFIG_LPC17_FLASH 1
/* Flash access use 6 CPU clocks - Safe for any allowed conditions */
@@ -137,8 +139,7 @@
/* Ethernet configuration */
-//#define ETH_MCFG_CLKSEL_DIV ETH_MCFG_CLKSEL_DIV44
-#define ETH_MCFG_CLKSEL_DIV ETH_MCFG_CLKSEL_DIV20
+#define ETH_MCFG_CLKSEL_DIV ETH_MCFG_CLKSEL_DIV20
/* Set EMC delay values:
*
@@ -159,15 +160,15 @@
*/
#if defined(CONFIG_LPC17_EMC_NAND) || defined(CONFIG_LPC17_EMC_SDRAM)
-# define BOARD_CMDDLY 17
-# define BOARD_FBCLKDLY 17
-# define BOARD_CLKOUT0DLY 1
-# define BOARD_CLKOUT1DLY 1
+# define BOARD_CMDDLY 17
+# define BOARD_FBCLKDLY 17
+# define BOARD_CLKOUT0DLY 1
+# define BOARD_CLKOUT1DLY 1
#else
-# define BOARD_CMDDLY 1
-# define BOARD_FBCLKDLY 1
-# define BOARD_CLKOUT0DLY 1
-# define BOARD_CLKOUT1DLY 1
+# define BOARD_CMDDLY 1
+# define BOARD_FBCLKDLY 1
+# define BOARD_CLKOUT0DLY 1
+# define BOARD_CLKOUT1DLY 1
#endif
/* LED definitions ******************************************************************/
@@ -184,18 +185,18 @@
/* LED index values for use with lpc17_setled() */
-#define BOARD_LED1 0
-#define BOARD_LED2 1
-#define BOARD_LED3 2
-#define BOARD_LED4 3
-#define BOARD_NLEDS 4
+#define BOARD_LED1 0
+#define BOARD_LED2 1
+#define BOARD_LED3 2
+#define BOARD_LED4 3
+#define BOARD_NLEDS 4
/* LED bits for use with lpc17_setleds() */
-#define BOARD_LED1_BIT (1 << BOARD_LED1)
-#define BOARD_LED2_BIT (1 << BOARD_LED2)
-#define BOARD_LED3_BIT (1 << BOARD_LED3)
-#define BOARD_LED4_BIT (1 << BOARD_LED4)
+#define BOARD_LED1_BIT (1 << BOARD_LED1)
+#define BOARD_LED2_BIT (1 << BOARD_LED2)
+#define BOARD_LED3_BIT (1 << BOARD_LED3)
+#define BOARD_LED4_BIT (1 << BOARD_LED4)
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the four LEDs
* on the WaveShare Open1788K. The following definitions describe how NuttX
@@ -256,6 +257,10 @@
/* Alternate pin selections *********************************************************/
+#define GPIO_UART0_TXD GPIO_UART0_TXD_1
+#define GPIO_UART0_RXD GPIO_UART0_RXD_1
+
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/configs/open1788/scripts/ld.script b/nuttx/configs/open1788/scripts/ld.script
index a4ca9cf80..8ed9c24c3 100755
--- a/nuttx/configs/open1788/scripts/ld.script
+++ b/nuttx/configs/open1788/scripts/ld.script
@@ -39,8 +39,9 @@
* 0x10000000 and 32Kb of Peripheral SRAM in two banks, 8Kb at addresses
* 0x20000000 bank0 first and 8kb at 0x20020000 at bank0 second. And 16Kb
* at 0x20040000 on bank1.
- * Here we assume that .data and .bss will all fit
- * into the 64Kb CPU SRAM address range.
+ *
+ * Here we assume that .data and .bss will all fit into the 64Kb CPU SRAM
+ * address range.
*/
MEMORY
@@ -55,81 +56,81 @@ OUTPUT_ARCH(arm)
ENTRY(_stext)
SECTIONS
{
- .text : {
- _stext = ABSOLUTE(.);
- *(.vectors)
- *(.text .text.*)
- *(.fixup)
- *(.gnu.warning)
- *(.rodata .rodata.*)
- *(.gnu.linkonce.t.*)
- *(.glue_7)
- *(.glue_7t)
- *(.got)
- *(.gcc_except_table)
- *(.gnu.linkonce.r.*)
- _etext = ABSOLUTE(.);
- } > FLASH
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > FLASH
- .init_section : {
- _sinit = ABSOLUTE(.);
- *(.init_array .init_array.*)
- _einit = ABSOLUTE(.);
- } > FLASH
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ *(.init_array .init_array.*)
+ _einit = ABSOLUTE(.);
+ } > FLASH
- .ARM.extab : {
- *(.ARM.extab*)
- } > FLASH
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > FLASH
- __exidx_start = ABSOLUTE(.);
- .ARM.exidx : {
- *(.ARM.exidx*)
- } > FLASH
- __exidx_end = ABSOLUTE(.);
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > FLASH
+ __exidx_end = ABSOLUTE(.);
- _eronly = ABSOLUTE(.);
+ _eronly = ABSOLUTE(.);
- .data : {
- _sdata = ABSOLUTE(.);
- *(.data .data.*)
- *(.gnu.linkonce.d.*)
- CONSTRUCTORS
- _edata = ABSOLUTE(.);
- } > SRAM AT > FLASH
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > SRAM AT > FLASH
- .bss : {
- _sbss = ABSOLUTE(.);
- *(.bss .bss.*)
- *(.gnu.linkonce.b.*)
- *(COMMON)
- _ebss = ABSOLUTE(.);
- } > SRAM
-
- .psram0 (NOLOAD) :
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > SRAM
+/*
+ .psram0 (NOLOAD) :
{
- *(.psram0)
- . = ALIGN(4)
- } > PSRAM0
+ *(.psram0)
+ . = ALIGN(4)
+ } > PSRAM0
- .psram1 (NOLOAD) :
+ .psram1 (NOLOAD) :
{
- *(.psram0)
- . = ALIGN(4)
- } > PSRAM1
-
- /* Stabs debugging sections */
+ *(.psram1)
+ . = ALIGN(4)
+ } > PSRAM1
+*/
+ /* Stabs debugging sections */
- .stab 0 : { *(.stab) }
- .stabstr 0 : { *(.stabstr) }
- .stab.excl 0 : { *(.stab.excl) }
- .stab.exclstr 0 : { *(.stab.exclstr) }
- .stab.index 0 : { *(.stab.index) }
- .stab.indexstr 0 : { *(.stab.indexstr) }
- .comment 0 : { *(.comment) }
- .debug_abbrev 0 : { *(.debug_abbrev) }
- .debug_info 0 : { *(.debug_info) }
- .debug_line 0 : { *(.debug_line) }
- .debug_pubnames 0 : { *(.debug_pubnames) }
- .debug_aranges 0 : { *(.debug_aranges) }
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
}