aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-18 19:16:44 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-18 19:16:44 +0000
commit40041c8792340b6148338cb3e3a28266fdff7373 (patch)
treee746a348a0a71399c9811f6645e7e4716ac45aee /nuttx
parent3ff155d04803d8b19f0f56602e95b4034bc33820 (diff)
downloadpx4-firmware-40041c8792340b6148338cb3e3a28266fdff7373.tar.gz
px4-firmware-40041c8792340b6148338cb3e3a28266fdff7373.tar.bz2
px4-firmware-40041c8792340b6148338cb3e3a28266fdff7373.zip
Refactor all lpc17xx header files (more like STM32 header file structure now)
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5534 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/include/lpc17xx/irq.h2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip.h4
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc176x_memorymap.h (renamed from nuttx/arch/arm/src/lpc17xx/lpc17_memorymap.h)10
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h234
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h64
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h72
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_adc.h180
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_can.h510
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_dac.h97
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_ethernet.h597
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpdma.h417
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpio.h293
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_i2c.h208
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_i2s.h62
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_mcpwm.h (renamed from nuttx/arch/arm/src/lpc17xx/lpc17_mcpwm.h)12
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_memorymap.h71
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h71
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconn.h (renamed from nuttx/arch/arm/src/lpc17xx/lpc17_pinconn.h)12
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_pwm.h63
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_qei.h190
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_rit.h92
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_rtc.h270
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_spi.h141
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_ssp.h174
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_syscon.h (renamed from nuttx/arch/arm/src/lpc17xx/lpc17_syscon.h)12
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_timer.h250
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_uart.h (renamed from nuttx/arch/arm/src/lpc17xx/lpc17_uart.h)678
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_usb.h (renamed from nuttx/arch/arm/src/lpc17xx/lpc17_usb.h)12
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_wdt.h108
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_adc.c5
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_adc.h268
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_can.c5
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_can.h504
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c4
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.h84
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_clrpend.c2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_clrpend.h84
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_dac.c5
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_dac.h65
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_emacram.h2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c7
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h550
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c4
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h527
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c11
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h284
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpiodbg.c2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c3
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_i2c.c9
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_i2c.h150
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_i2s.h380
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_internal.h854
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_irq.c4
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c8
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.h84
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_ohciram.h2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_qei.h132
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_rit.h34
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_rtc.h332
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_serial.c6
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_serial.h6
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_spi.c5
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_spi.h173
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_ssp.c5
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_ssp.h347
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_start.c3
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_timer.h312
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_timerisr.c2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c9
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c8
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_wdt.h50
-rw-r--r--nuttx/configs/lincoln60/src/up_boot.c1
-rw-r--r--nuttx/configs/lincoln60/src/up_buttons.c4
-rw-r--r--nuttx/configs/lincoln60/src/up_leds.c4
-rw-r--r--nuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h4
-rw-r--r--nuttx/configs/lpcxpresso-lpc1768/src/up_boot.c2
-rw-r--r--nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c4
-rw-r--r--nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c5
-rw-r--r--nuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c13
-rw-r--r--nuttx/configs/mbed/src/up_boot.c2
-rw-r--r--nuttx/configs/mbed/src/up_leds.c4
-rw-r--r--nuttx/configs/nucleus2g/src/up_boot.c2
-rw-r--r--nuttx/configs/nucleus2g/src/up_leds.c4
-rw-r--r--nuttx/configs/nucleus2g/src/up_outputs.c4
-rw-r--r--nuttx/configs/nucleus2g/src/up_ssp.c9
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_boot.c2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_buttons.c2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_can.c1
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_lcd.c2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_leds.c2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_nsh.c4
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_ssp.c3
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c2
95 files changed, 5972 insertions, 4349 deletions
diff --git a/nuttx/arch/arm/include/lpc17xx/irq.h b/nuttx/arch/arm/include/lpc17xx/irq.h
index c058f6367..91875804c 100644
--- a/nuttx/arch/arm/include/lpc17xx/irq.h
+++ b/nuttx/arch/arm/include/lpc17xx/irq.h
@@ -114,7 +114,7 @@ extern "C"
#ifdef __cplusplus
}
#endif
-#endif __ASSEMBLY__
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_INCLUDE_LPC17XX_IRQ_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip.h b/nuttx/arch/arm/src/lpc17xx/chip.h
index 60dda773d..d9b3998fe 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/chip.h
*
- * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,7 +47,7 @@
* file for the proper setup
*/
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_memorymap.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_memorymap.h
index ae66b684c..094a47788 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_memorymap.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_memorymap.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_memorymap.h
+ * arch/arm/src/lpc17xx/lpc176x_memorymap.h
*
- * 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
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LPC17XX_LPC17_MEMORYMAP_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_MEMORYMAP_H
+#ifndef __ARCH_ARM_SRC_LPC17XX_LPC176X_MEMORYMAP_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC176X_MEMORYMAP_H
/************************************************************************************
* Included Files
@@ -133,4 +133,4 @@
* Public Functions
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_MEMORYMAP_H */
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC176X_MEMORYMAP_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h
new file mode 100644
index 000000000..fb0c7c700
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_pinconfig.h
@@ -0,0 +1,234 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lp176x_pinconfig.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC176X_PINCONFIG_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC176X_PINCONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* GPIO pin definitions *************************************************************/
+/* NOTE that functions have a alternate pins that can be selected. These alternates
+ * are identified with a numerica suffix like _1, _2, or _3. Your board.h file
+ * should select the correct alternative for your board by including definitions
+ * such as:
+ *
+ * #define GPIO_UART1_RXD GPIO_UART1_RXD_1
+ *
+ * (without the suffix)
+ */
+
+#define GPIO_CAN1_RD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN0)
+#define GPIO_UART3_TXD_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN0)
+#define GPIO_I2C1_SDA_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN0)
+#define GPIO_CAN1_TD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN1)
+#define GPIO_UART3_RXD_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN1)
+#define GPIO_I2C1_SCL_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN1)
+#define GPIO_UART0_TXD (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN2)
+#define GPIO_AD0p7 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN2)
+#define GPIO_UART0_RXD (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN3)
+#define GPIO_AD0p6 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN3)
+#define GPIO_I2S_RXCLK_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
+#define GPIO_CAN2_RD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
+#define GPIO_CAP2p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
+#define GPIO_I2S_RXWS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
+#define GPIO_CAN2_TD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
+#define GPIO_CAP2p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
+#define GPIO_I2S_RXSDA_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
+#define GPIO_SSP1_SSEL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
+#define GPIO_MAT2p0_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
+#define GPIO_I2S_TXCLK_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
+#define GPIO_SSP1_SCK_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
+#define GPIO_MAT2p1_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
+#define GPIO_I2S_TXWS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
+#define GPIO_SSP1_MISO (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
+#define GPIO_MAT2p2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
+#define GPIO_I2S_TXSDA_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
+#define GPIO_SSP1_MOSI (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
+#define GPIO_MAT2p3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
+#define GPIO_UART2_TXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN10)
+#define GPIO_I2C2_SDA (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN10)
+#define GPIO_MAT3p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN10)
+#define GPIO_UART2_RXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN11)
+#define GPIO_I2C2_SCL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN11)
+#define GPIO_MAT3p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN11)
+#define GPIO_UART1_TXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
+#define GPIO_SSP0_SCK_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
+#define GPIO_SPI_SCK (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
+#define GPIO_UART1_RXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
+#define GPIO_SSP0_SSEL_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
+#define GPIO_SPI_SSEL (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
+#define GPIO_UART1_CTS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
+#define GPIO_SSP0_MISO_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
+#define GPIO_SPI_MISO (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
+#define GPIO_UART1_DCD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
+#define GPIO_SSP0_MOSI_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
+#define GPIO_SPI_MOSI (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
+#define GPIO_UART1_DSR_1 (GPIO_ALT1 | 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_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_CAN1_RD_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
+#define GPIO_UART1_RTS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
+#define GPIO_CAN1_TD_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
+#define GPIO_AD0p0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN23)
+#define GPIO_I2S_RXCLK_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN23)
+#define GPIO_CAP3p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN23)
+#define GPIO_AD0p1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN24)
+#define GPIO_I2S_RXWS_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN24)
+#define GPIO_CAP3p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN24)
+#define GPIO_AD0p2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN25)
+#define GPIO_I2S_RXSDA_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN25)
+#define GPIO_UART3_TXD_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN25)
+#define GPIO_AD0p3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN26)
+#define GPIO_AOUT (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN26)
+#define GPIO_UART3_RXD_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN26)
+#define GPIO_I2C0_SDA (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN27)
+#define GPIO_USB_SDA (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN27)
+#define GPIO_I2C0_SCL (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN28)
+#define GPIO_USB_SCL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN28)
+#define GPIO_USB_DP (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN29)
+#define GPIO_USB_DM (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN30)
+#define GPIO_ENET_TXD0 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN0)
+#define GPIO_ENET_TXD1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN1)
+#define GPIO_ENET_TXEN (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN4)
+#define GPIO_ENET_CRS (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN8)
+#define GPIO_ENET_RXD0 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN9)
+#define GPIO_ENET_RXD1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN10)
+#define GPIO_ENET_RXER (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN14)
+#define GPIO_ENET_REFCLK (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN15)
+#define GPIO_ENET_MDC_1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN16)
+#define GPIO_ENET_MDIO_1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN17)
+#define GPIO_USB_UPLED (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN18)
+#define GPIO_PWM1p1_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN18)
+#define GPIO_CAP1p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN18)
+#define GPIO_MCPWM_MCOA0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
+#define GPIO_USB_PPWR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
+#define GPIO_CAP1p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
+#define GPIO_MCPWM_MCI0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+#define GPIO_PWM1p2_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+#define GPIO_SSP0_SCK_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+#define GPIO_MCPWM_MCABORT (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN21)
+#define GPIO_PWM1p3_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN21)
+#define GPIO_SSP0_SSEL_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN21)
+#define GPIO_MCPWM_MCOB0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
+#define GPIO_USB_PWRD (GPIO_ALT2 | GPIO_PULLDN | GPIO_PORT1 | GPIO_PIN22)
+#define GPIO_MAT1p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
+#define GPIO_MCPWM_MCI1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+#define GPIO_PWM1p4_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+#define GPIO_SSP0_MISO_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+#define GPIO_MCPWM_MCI2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+#define GPIO_PWM1p5_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+#define GPIO_SSP0_MOSI_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+#define GPIO_MCPWM_MCOA1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
+#define GPIO_MAT1p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
+#define GPIO_MCPWM_MCOB1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
+#define GPIO_PWM1p6_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
+#define GPIO_CAP0p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
+#define GPIO_CLKOUT (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
+#define GPIO_USB_OVRCR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
+#define GPIO_CAP0p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
+#define GPIO_MCPWM_MCOA2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
+#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_MCOB2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
+#define GPIO_PCAP1p1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
+#define GPIO_MAT0p1_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
+#define GPIO_USB_VBUS (GPIO_ALT2 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN30)
+#define GPIO_AD0p4 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN30)
+#define GPIO_SSP1_SCK_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN31)
+#define GPIO_AD0p5 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN31)
+#define GPIO_PWM1p1_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN0)
+#define GPIO_UART1_TXD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN0)
+#define GPIO_PWM1p2_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN1)
+#define GPIO_UART1_RXD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN1)
+#define GPIO_PWM1p3_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN2)
+#define GPIO_UART1_CTS_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN2)
+#define GPIO_PWM1p4_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN3)
+#define GPIO_UART1_DCD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN3)
+#define GPIO_PWM1p5_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN4)
+#define GPIO_UART1_DSR_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN4)
+#define GPIO_PWM1p6_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN5)
+#define GPIO_UART1_DTR_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN5)
+#define GPIO_PCAP1p0_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN6)
+#define GPIO_UART1_RI_2 (GPIO_ALT2 | 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_CAN2_TD_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN8)
+#define GPIO_UART2_TXD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN8)
+#define GPIO_ENET_MDC_2 (GPIO_ALT3 | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN8)
+#define GPIO_USB_CONNECT (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
+#define GPIO_UART2_RXD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
+#define GPIO_ENET_MDIO_2 (GPIO_ALT3 | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN9)
+#define GPIO_EINT0 (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_I2S_TXCLK_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
+#define GPIO_PEINT2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define GPIO_I2S_TXWS_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define GPIO_EINT3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+#define GPIO_I2S_TXSDA_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+#define GPIO_MAT0p0_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN25)
+#define GPIO_PWM1p2_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN25)
+#define GPIO_STCLK (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
+#define GPIO_MAT0p1_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
+#define GPIO_PWM1p3_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
+#define GPIO_RXMCLK (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
+#define GPIO_MAT2p0_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
+#define GPIO_UART3_TXD_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
+#define GPIO_TXMCLK (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+#define GPIO_MAT2p1_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+#define GPIO_UART3_RXD_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+ #endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC176X_PINCONFIG_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h
new file mode 100644
index 000000000..21e8e6c33
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h
@@ -0,0 +1,64 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/lpc178x_memorymap.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Authors: Rommel Marcelo
+ * 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_LPC17XX_LPC178X_MEMORYMAP_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC178X_MEMORYMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC178X_MEMORYMAP_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
new file mode 100644
index 000000000..53c2b26a9
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
@@ -0,0 +1,72 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lp178x_pinconfig.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Authors: Rommel Marcelo
+ * 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_LPC17XX_CHIP_LPC178X_PINCONFIG_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC178X_PINCONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* GPIO pin definitions *************************************************************/
+/* NOTE that functions have a alternate pins that can be selected. These alternates
+ * are identified with a numerica suffix like _1, _2, or _3. Your board.h file
+ * should select the correct alternative for your board by including definitions
+ * such as:
+ *
+ * #define GPIO_UART1_RXD GPIO_UART1_RXD_1
+ *
+ * (without the suffix)
+ */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+ #endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC178X_PINCONFIG_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_adc.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_adc.h
new file mode 100644
index 000000000..8cec0d325
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_adc.h
@@ -0,0 +1,180 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_adc.h
+ *
+ * Copyright (C) 2010, 2012, 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_LPC17XX_LPC17_CHIP_ADC_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_CHIP_ADC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_ADC_CR_OFFSET 0x0000 /* A/D Control Register */
+#define LPC17_ADC_GDR_OFFSET 0x0004 /* A/D Global Data Register */
+#define LPC17_ADC_INTEN_OFFSET 0x000c /* A/D Interrupt Enable Register */
+
+#define LPC17_ADC_DR_OFFSET(n) (0x0010+((n) << 2))
+#define LPC17_ADC_DR0_OFFSET 0x0010 /* A/D Channel 0 Data Register */
+#define LPC17_ADC_DR1_OFFSET 0x0014 /* A/D Channel 1 Data Register */
+#define LPC17_ADC_DR2_OFFSET 0x0018 /* A/D Channel 2 Data Register */
+#define LPC17_ADC_DR3_OFFSET 0x001c /* A/D Channel 3 Data Register */
+#define LPC17_ADC_DR4_OFFSET 0x0020 /* A/D Channel 4 Data Register */
+#define LPC17_ADC_DR5_OFFSET 0x0024 /* A/D Channel 5 Data Register */
+#define LPC17_ADC_DR6_OFFSET 0x0028 /* A/D Channel 6 Data Register */
+#define LPC17_ADC_DR7_OFFSET 0x002c /* A/D Channel 7 Data Register */
+
+#define LPC17_ADC_STAT_OFFSET 0x0030 /* A/D Status Register */
+#define LPC17_ADC_TRM_OFFSET 0x0034 /* ADC trim register */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_ADC_CR (LPC17_ADC_BASE+LPC17_ADC_CR_OFFSET)
+#define LPC17_ADC_GDR (LPC17_ADC_BASE+LPC17_ADC_GDR_OFFSET)
+#define LPC17_ADC_INTEN (LPC17_ADC_BASE+LPC17_ADC_INTEN_OFFSET)
+
+#define LPC17_ADC_DR(n) (LPC17_ADC_BASE+LPC17_ADC_DR_OFFSET(n))
+#define LPC17_ADC_DR0 (LPC17_ADC_BASE+LPC17_ADC_DR0_OFFSET)
+#define LPC17_ADC_DR1 (LPC17_ADC_BASE+LPC17_ADC_DR1_OFFSET)
+#define LPC17_ADC_DR2 (LPC17_ADC_BASE+LPC17_ADC_DR2_OFFSET)
+#define LPC17_ADC_DR3 (LPC17_ADC_BASE+LPC17_ADC_DR3_OFFSET)
+#define LPC17_ADC_DR4 (LPC17_ADC_BASE+LPC17_ADC_DR4_OFFSET)
+#define LPC17_ADC_DR5 (LPC17_ADC_BASE+LPC17_ADC_DR5_OFFSET)
+#define LPC17_ADC_DR6 (LPC17_ADC_BASE+LPC17_ADC_DR6_OFFSET)
+#define LPC17_ADC_DR7 (LPC17_ADC_BASE+LPC17_ADC_DR7_OFFSET)
+
+#define LPC17_ADC_STAT (LPC17_ADC_BASE+LPC17_ADC_STAT_OFFSET)
+#define LPC17_ADC_TRM (LPC17_ADC_BASE+LPC17_ADC_TRM_OFFSET)
+
+/* Register bit definitions *********************************************************/
+
+/* A/D Control Register */
+
+#define ADC_CR_SEL_SHIFT (0) /* Bits 0-7: Selects pins to be sampled */
+#define ADC_CR_SEL_MASK (0xff << ADC_CR_SEL_MASK)
+#define ADC_CR_CLKDIV_SHIFT (8) /* Bits 8-15: APB clock (PCLK_ADC0) divisor */
+#define ADC_CR_CLKDIV_MASK (0xff << ADC_CR_CLKDIV_SHIFT)
+#define ADC_CR_BURST (1 << 16) /* Bit 16: A/D Repeated conversions */
+ /* Bits 17-20: Reserved */
+#define ADC_CR_PDN (1 << 21) /* Bit 21: A/D converter power-down mode */
+ /* Bits 22-23: Reserved */
+#define ADC_CR_START_SHIFT (24) /* Bits 24-26: Control A/D conversion start */
+#define ADC_CR_START_MASK (7 << ADC_CR_START_SHIFT)
+# define ADC_CR_START_NOSTART (0 << ADC_CR_START_SHIFT) /* No start */
+# define ADC_CR_START_NOW (1 << ADC_CR_START_SHIFT) /* Start now */
+# define ADC_CR_START_P2p10 (2 << ADC_CR_START_SHIFT) /* Start edge on P2.10/EINT0/NMI */
+# define ADC_CR_START_P1p27 (3 << ADC_CR_START_SHIFT) /* Start edge on P1.27/CLKOUT/USB_OVRCRn/CAP0.1 */
+# define ADC_CR_START_MAT0p1 (4 << ADC_CR_START_SHIFT) /* Start edge on MAT0.1 */
+# define ADC_CR_START_MAT0p3 (5 << ADC_CR_START_SHIFT) /* Start edge on MAT0.3 */
+# define ADC_CR_START_MAT1p0 (6 << ADC_CR_START_SHIFT) /* Start edge on MAT1.0 */
+# define ADC_CR_START_MAT1p1 (7 << ADC_CR_START_SHIFT) /* Start edge on MAT1.1 */
+#define ADC_CR_EDGE (1 << 27) /* Bit 27: Start on falling edge */
+ /* Bits 28-31: Reserved */
+/* A/D Global Data Register AND Channel 0-7 Data Register */
+ /* Bits 0-3: Reserved */
+#define ADC_DR_RESULT_SHIFT (4) /* Bits 4-15: Result of conversion (DONE==1) */
+#define ADC_DR_RESULT_MASK (0x0fff << ADC_DR_RESULT_SHIFT)
+ /* Bits 16-23: Reserved */
+#define ADC_DR_CHAN_SHIFT (24) /* Bits 24-26: Channel converted */
+#define ADC_DR_CHAN_MASK (3 << ADC_DR_CHN_SHIFT)
+ /* Bits 27-29: Reserved */
+#define ADC_DR_OVERRUN (1 << 30) /* Bit 30: Conversion(s) lost/overwritten*/
+#define ADC_DR_DONE (1 << 31) /* Bit 31: A/D conversion complete*/
+
+/* A/D Interrupt Enable Register */
+
+#define ADC_INTEN_CHAN(n) (1 << (n))
+#define ADC_INTEN_CHAN0 (1 << 0) /* Bit 0: Enable ADC chan 0 complete intterrupt */
+#define ADC_INTEN_CHAN1 (1 << 1) /* Bit 1: Enable ADC chan 1 complete interrupt */
+#define ADC_INTEN_CHAN2 (1 << 2) /* Bit 2: Enable ADC chan 2 complete interrupt */
+#define ADC_INTEN_CHAN3 (1 << 3) /* Bit 3: Enable ADC chan 3 complete interrupt */
+#define ADC_INTEN_CHAN4 (1 << 4) /* Bit 4: Enable ADC chan 4 complete interrupt */
+#define ADC_INTEN_CHAN5 (1 << 5) /* Bit 5: Enable ADC chan 5 complete interrupt */
+#define ADC_INTEN_CHAN6 (1 << 6) /* Bit 6: Enable ADC chan 6 complete interrupt */
+#define ADC_INTEN_CHAN7 (1 << 7) /* Bit 7: Enable ADC chan 7 complete interrupt */
+#define ADC_INTEN_GLOBAL (1 << 8) /* Bit 8: Only the global DONE generates interrupt */
+ /* Bits 9-31: Reserved */
+/* A/D Status Register */
+
+#define ADC_STAT_DONE(n) (1 << (n))
+#define ADC_STAT_DONE0 (1 << 0) /* Bit 0: A/D chan 0 DONE */
+#define ADC_STAT_DONE1 (1 << 1) /* Bit 1: A/D chan 1 DONE */
+#define ADC_STAT_DONE2 (1 << 2) /* Bit 2: A/D chan 2 DONE */
+#define ADC_STAT_DONE3 (1 << 3) /* Bit 3: A/D chan 3 DONE */
+#define ADC_STAT_DONE4 (1 << 4) /* Bit 4: A/D chan 4 DONE */
+#define ADC_STAT_DONE5 (1 << 5) /* Bit 5: A/D chan 5 DONE */
+#define ADC_STAT_DONE6 (1 << 6) /* Bit 6: A/D chan 6 DONE */
+#define ADC_STAT_DONE7 (1 << 7) /* Bit 7: A/D chan 7 DONE */
+#define ADC_STAT_OVERRUN(n) ((1 << (n)) + 8)
+#define ADC_STAT_OVERRUN0 (1 << 8) /* Bit 8: A/D chan 0 OVERRUN */
+#define ADC_STAT_OVERRUN1 (1 << 9) /* Bit 9: A/D chan 1 OVERRUN */
+#define ADC_STAT_OVERRUN2 (1 << 10) /* Bit 10: A/D chan 2 OVERRUN */
+#define ADC_STAT_OVERRUN3 (1 << 11) /* Bit 11: A/D chan 3 OVERRUN */
+#define ADC_STAT_OVERRUN4 (1 << 12) /* Bit 12: A/D chan 4 OVERRUN */
+#define ADC_STAT_OVERRUN5 (1 << 13) /* Bit 13: A/D chan 5 OVERRUN */
+#define ADC_STAT_OVERRUN6 (1 << 14) /* Bit 14: A/D chan 6 OVERRUN */
+#define ADC_STAT_OVERRUN7 (1 << 15) /* Bit 15: A/D chan 7 OVERRUN */
+#define ADC_STAT_INT (1 << 16) /* Bit 15: A/D interrupt */
+ /* Bits 17-31: Reserved */
+/* ADC trim register */
+ /* Bits 0-3: Reserved */
+#define ADC_TRM_ADCOFFS_SHIFT (4) /* Bits 4-7: A/D offset trim bits */
+#define ADC_TRM_ADCOFFS_MASK (15 << ADC_TRM_ADCOFFS_SHIFT)
+#define ADC_TRM_TRIM_SHIFT (8) /* Bits 8-11: Written-to by boot code */
+#define ADC_TRM_TRIM_MASK (15 << ADC_TRM_TRIM_SHIFT)
+ /* Bits 12-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_CHIP_ADC_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_can.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_can.h
new file mode 100644
index 000000000..84b019d61
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_can.h
@@ -0,0 +1,510 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_can.h
+ *
+ * Copyright (C) 2010-2012, 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_LPC17XX_LPC17_CHIP_CAN_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_CHIP_CAN_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+/* CAN acceptance filter registers */
+
+#define LPC17_CANAF_AFMR_OFFSET 0x0000 /* Acceptance Filter Register */
+#define LPC17_CANAF_SFFSA_OFFSET 0x0004 /* Standard Frame Individual Start Address Register */
+#define LPC17_CANAF_SFFGRPSA_OFFSET 0x0008 /* Standard Frame Group Start Address Register */
+#define LPC17_CANAF_EFFSA_OFFSET 0x000c /* Extended Frame Start Address Register */
+#define LPC17_CANAF_EFFGRPSA_OFFSET 0x0010 /* Extended Frame Group Start Address Register */
+#define LPC17_CANAF_EOT_OFFSET 0x0014 /* End of AF Tables register */
+#define LPC17_CANAF_LUTERRAD_OFFSET 0x0018 /* LUT Error Address register */
+#define LPC17_CANAF_LUTERR_OFFSET 0x001c /* LUT Error Register */
+#define LPC17_CANAF_FCANIE_OFFSET 0x0020 /* FullCAN interrupt enable register */
+#define LPC17_CANAF_FCANIC0_OFFSET 0x0024 /* FullCAN interrupt and capture register 0 */
+#define LPC17_CANAF_FCANIC1_OFFSET 0x0028 /* FullCAN interrupt and capture register 1 */
+
+/* Central CAN registers */
+
+#define LPC17_CAN_TXSR_OFFSET 0x0000 /* CAN Central Transmit Status Register */
+#define LPC17_CAN_RXSR_OFFSET 0x0004 /* CAN Central Receive Status Register */
+#define LPC17_CAN_MSR_OFFSET 0x0008 /* CAN Central Miscellaneous Register */
+
+/* CAN1/2 registers */
+
+#define LPC17_CAN_MOD_OFFSET 0x0000 /* CAN operating mode */
+#define LPC17_CAN_CMR_OFFSET 0x0004 /* Command bits */
+#define LPC17_CAN_GSR_OFFSET 0x0008 /* Controller Status and Error Counters */
+#define LPC17_CAN_ICR_OFFSET 0x000c /* Interrupt and capure register */
+#define LPC17_CAN_IER_OFFSET 0x0010 /* Interrupt Enable */
+#define LPC17_CAN_BTR_OFFSET 0x0014 /* Bus Timing */
+#define LPC17_CAN_EWL_OFFSET 0x0018 /* Error Warning Limit */
+#define LPC17_CAN_SR_OFFSET 0x001c /* Status Register */
+#define LPC17_CAN_RFS_OFFSET 0x0020 /* Receive frame status */
+#define LPC17_CAN_RID_OFFSET 0x0024 /* Received Identifier */
+#define LPC17_CAN_RDA_OFFSET 0x0028 /* Received data bytes 1-4 */
+#define LPC17_CAN_RDB_OFFSET 0x002c /* Received data bytes 5-8 */
+#define LPC17_CAN_TFI1_OFFSET 0x0030 /* Transmit frame info (Tx Buffer 1) */
+#define LPC17_CAN_TID1_OFFSET 0x0034 /* Transmit Identifier (Tx Buffer 1) */
+#define LPC17_CAN_TDA1_OFFSET 0x0038 /* Transmit data bytes 1-4 (Tx Buffer 1) */
+#define LPC17_CAN_TDB1_OFFSET 0x003c /* Transmit data bytes 5-8 (Tx Buffer 1) */
+#define LPC17_CAN_TFI2_OFFSET 0x0040 /* Transmit frame info (Tx Buffer 2) */
+#define LPC17_CAN_TID2_OFFSET 0x0044 /* Transmit Identifier (Tx Buffer 2) */
+#define LPC17_CAN_TDA2_OFFSET 0x0048 /* Transmit data bytes 1-4 (Tx Buffer 2) */
+#define LPC17_CAN_TDB2_OFFSET 0x004c /* Transmit data bytes 5-8 (Tx Buffer 2) */
+#define LPC17_CAN_TFI3_OFFSET 0x0050 /* Transmit frame info (Tx Buffer 3) */
+#define LPC17_CAN_TID3_OFFSET 0x0054 /* Transmit Identifier (Tx Buffer 3) */
+#define LPC17_CAN_TDA3_OFFSET 0x0058 /* Transmit data bytes 1-4 (Tx Buffer 3) */
+#define LPC17_CAN_TDB3_OFFSET 0x005c /* Transmit data bytes 5-8 (Tx Buffer 3) */
+
+/* Register addresses ***************************************************************/
+/* CAN acceptance filter registers */
+
+#define LPC17_CANAF_AFMR (LPC17_CANAF_BASE+LPC17_CANAF_AFMR_OFFSET)
+#define LPC17_CANAF_SFFSA (LPC17_CANAF_BASE+LPC17_CANAF_SFFSA_OFFSET)
+#define LPC17_CANAF_SFFGRPSA (LPC17_CANAF_BASE+LPC17_CANAF_SFFGRPSA_OFFSET)
+#define LPC17_CANAF_EFFSA (LPC17_CANAF_BASE+LPC17_CANAF_EFFSA_OFFSET)
+#define LPC17_CANAF_EFFGRPSA (LPC17_CANAF_BASE+LPC17_CANAF_EFFGRPSA_OFFSET)
+#define LPC17_CANAF_EOT (LPC17_CANAF_BASE+LPC17_CANAF_EOT_OFFSET)
+#define LPC17_CANAF_LUTERRAD (LPC17_CANAF_BASE+LPC17_CANAF_LUTERRAD_OFFSET)
+#define LPC17_CANAF_LUTERR (LPC17_CANAF_BASE+LPC17_CANAF_LUTERR_OFFSET)
+#define LPC17_CANAF_FCANIE (LPC17_CANAF_BASE+LPC17_CANAF_FCANIE_OFFSET)
+#define LPC17_CANAF_FCANIC0 (LPC17_CANAF_BASE+LPC17_CANAF_FCANIC0_OFFSET)
+#define LPC17_CANAF_FCANIC1 (LPC17_CANAF_BASE+LPC17_CANAF_FCANIC1_OFFSET)
+
+/* Central CAN registers */
+
+#define LPC17_CAN_TXSR (LPC17_CAN_BASE+LPC17_CAN_TXSR_OFFSET)
+#define LPC17_CAN_RXSR (LPC17_CAN_BASE+LPC17_CAN_RXSR_OFFSET)
+#define LPC17_CAN_MSR (LPC17_CAN_BASE+LPC17_CAN_MSR_OFFSET)
+
+/* CAN1/2 registers */
+
+#define LPC17_CAN1_MOD (LPC17_CAN1_BASE+LPC17_CAN_MOD_OFFSET)
+#define LPC17_CAN1_CMR (LPC17_CAN1_BASE+LPC17_CAN_CMR_OFFSET)
+#define LPC17_CAN1_GSR (LPC17_CAN1_BASE+LPC17_CAN_GSR_OFFSET)
+#define LPC17_CAN1_ICR (LPC17_CAN1_BASE+LPC17_CAN_ICR_OFFSET)
+#define LPC17_CAN1_IER (LPC17_CAN1_BASE+LPC17_CAN_IER_OFFSET)
+#define LPC17_CAN1_BTR (LPC17_CAN1_BASE+LPC17_CAN_BTR_OFFSET)
+#define LPC17_CAN1_EWL (LPC17_CAN1_BASE+LPC17_CAN_EWL_OFFSET)
+#define LPC17_CAN1_SR (LPC17_CAN1_BASE+LPC17_CAN_SR_OFFSET)
+#define LPC17_CAN1_RFS (LPC17_CAN1_BASE+LPC17_CAN_RFS_OFFSET)
+#define LPC17_CAN1_RID (LPC17_CAN1_BASE+LPC17_CAN_RID_OFFSET)
+#define LPC17_CAN1_RDA (LPC17_CAN1_BASE+LPC17_CAN_RDA_OFFSET)
+#define LPC17_CAN1_RDB (LPC17_CAN1_BASE+LPC17_CAN_RDB_OFFSET)
+#define LPC17_CAN1_TFI1 (LPC17_CAN1_BASE+LPC17_CAN_TFI1_OFFSET)
+#define LPC17_CAN1_TID1 (LPC17_CAN1_BASE+LPC17_CAN_TID1_OFFSET)
+#define LPC17_CAN1_TDA1 (LPC17_CAN1_BASE+LPC17_CAN_TDA1_OFFSET)
+#define LPC17_CAN1_TDB1 (LPC17_CAN1_BASE+LPC17_CAN_TDB1_OFFSET)
+#define LPC17_CAN1_TFI2 (LPC17_CAN1_BASE+LPC17_CAN_TFI2_OFFSET)
+#define LPC17_CAN1_TID2 (LPC17_CAN1_BASE+LPC17_CAN_TID2_OFFSET)
+#define LPC17_CAN1_TDA2 (LPC17_CAN1_BASE+LPC17_CAN_TDA2_OFFSET)
+#define LPC17_CAN1_TDB2 (LPC17_CAN1_BASE+LPC17_CAN_TDB2_OFFSET)
+#define LPC17_CAN1_TFI3 (LPC17_CAN1_BASE+LPC17_CAN_TFI3_OFFSET)
+#define LPC17_CAN1_TID3 (LPC17_CAN1_BASE+LPC17_CAN_TID3_OFFSET)
+#define LPC17_CAN1_TDA3 (LPC17_CAN1_BASE+LPC17_CAN_TDA3_OFFSET)
+#define LPC17_CAN1_TDB3 (LPC17_CAN1_BASE+LPC17_CAN_TDB3_OFFSET)
+
+#define LPC17_CAN2_MOD (LPC17_CAN2_BASE+LPC17_CAN_MOD_OFFSET)
+#define LPC17_CAN2_CMR (LPC17_CAN2_BASE+LPC17_CAN_CMR_OFFSET)
+#define LPC17_CAN2_GSR (LPC17_CAN2_BASE+LPC17_CAN_GSR_OFFSET)
+#define LPC17_CAN2_ICR (LPC17_CAN2_BASE+LPC17_CAN_ICR_OFFSET)
+#define LPC17_CAN2_IER (LPC17_CAN2_BASE+LPC17_CAN_IER_OFFSET)
+#define LPC17_CAN2_BTR (LPC17_CAN2_BASE+LPC17_CAN_BTR_OFFSET)
+#define LPC17_CAN2_EWL (LPC17_CAN2_BASE+LPC17_CAN_EWL_OFFSET)
+#define LPC17_CAN2_SR (LPC17_CAN2_BASE+LPC17_CAN_SR_OFFSET)
+#define LPC17_CAN2_RFS (LPC17_CAN2_BASE+LPC17_CAN_RFS_OFFSET)
+#define LPC17_CAN2_RID (LPC17_CAN2_BASE+LPC17_CAN_RID_OFFSET)
+#define LPC17_CAN2_RDA (LPC17_CAN2_BASE+LPC17_CAN_RDA_OFFSET)
+#define LPC17_CAN2_RDB (LPC17_CAN2_BASE+LPC17_CAN_RDB_OFFSET)
+#define LPC17_CAN2_TFI1 (LPC17_CAN2_BASE+LPC17_CAN_TFI1_OFFSET)
+#define LPC17_CAN2_TID1 (LPC17_CAN2_BASE+LPC17_CAN_TID1_OFFSET)
+#define LPC17_CAN2_TDA1 (LPC17_CAN2_BASE+LPC17_CAN_TDA1_OFFSET)
+#define LPC17_CAN2_TDB1 (LPC17_CAN2_BASE+LPC17_CAN_TDB1_OFFSET)
+#define LPC17_CAN2_TFI2 (LPC17_CAN2_BASE+LPC17_CAN_TFI2_OFFSET)
+#define LPC17_CAN2_TID2 (LPC17_CAN2_BASE+LPC17_CAN_TID2_OFFSET)
+#define LPC17_CAN2_TDA2 (LPC17_CAN2_BASE+LPC17_CAN_TDA2_OFFSET)
+#define LPC17_CAN2_TDB2 (LPC17_CAN2_BASE+LPC17_CAN_TDB2_OFFSET)
+#define LPC17_CAN2_TFI3 (LPC17_CAN2_BASE+LPC17_CAN_TFI3_OFFSET)
+#define LPC17_CAN2_TID3 (LPC17_CAN2_BASE+LPC17_CAN_TID3_OFFSET)
+#define LPC17_CAN2_TDA3 (LPC17_CAN2_BASE+LPC17_CAN_TDA3_OFFSET)
+#define LPC17_CAN2_TDB3 (LPC17_CAN2_BASE+LPC17_CAN_TDB3_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* CAN acceptance filter registers */
+/* Acceptance Filter Register */
+
+#define CANAF_AFMR_ACCOFF (1 << 0) /* Bit 0: AF non-operational; All RX messages ignored */
+#define CANAF_AFMR_ACCBP (1 << 1) /* Bit 1: AF bypass: All RX messages accepted */
+#define CANAF_AFMR_EFCAN (1 << 2) /* Bit 2: Enable Full CAN mode */
+ /* Bits 3-31: Reserved */
+/* Standard Frame Individual Start Address Register */
+ /* Bits 0-1: Reserved */
+#define CANAF_SFFSA_SHIFT (2) /* Bits 2-10: Address of Standard Identifiers in AF Lookup RAM */
+#define CANAF_SFFSA_MASK (0x01ff << CANAF_SFFSA_SHIFT)
+ /* Bits 11-31: Reserved */
+/* Standard Frame Group Start Address Register */
+ /* Bits 0-1: Reserved */
+#define CANAF_SFFGRPSA_SHIFT (2) /* Bits 2-10: Address of grouped Standard Identifiers in AF Lookup RAM */
+#define CANAF_SFFGRPSA_MASK (0x01ff << CANAF_SFFGRPSA_SHIFT)
+ /* Bits 11-31: Reserved */
+/* Extended Frame Start Address Register */
+ /* Bits 0-1: Reserved */
+#define CANAF_EFFSA_SHIFT (2) /* Bits 2-10: Address of Extended Identifiers in AF Lookup RAM */
+#define CANAF_EFFSA_MASK (0x01ff << CANAF_EFFSA_SHIFT)
+ /* Bits 11-31: Reserved */
+/* Extended Frame Group Start Address Register */
+ /* Bits 0-1: Reserved */
+#define CANAF_EFFGRPSA_SHIFT (2) /* Bits 2-10: Address of grouped Extended Identifiers in AF Lookup RAM */
+#define CANAF_EFFGRPSA_MASK (0x01ff << CANAF_EFFGRPSA_SHIFT)
+ /* Bits 11-31: Reserved */
+/* End of AF Tables register */
+ /* Bits 0-1: Reserved */
+#define CANAF_EOT_SHIFT (2) /* Bits 2-10: Last active address in last active AF table */
+#define CANAF_EOT_MASK (0x01ff << CANAF_EOT_SHIFT)
+ /* Bits 11-31: Reserved */
+/* LUT Error Address register */
+ /* Bits 0-1: Reserved */
+#define CANAF_LUTERRAD_SHIFT (2) /* Bits 2-10: Address in AF Lookup RAM of error */
+#define CANAF_LUTERRAD_MASK (0x01ff << CANAF_EOT_SHIFT)
+ /* Bits 11-31: Reserved */
+/* LUT Error Register */
+
+#define CANAF_LUTERR_LUTERR (1 << 0) /* Bit 0: AF error in AF RAM tables */
+ /* Bits 1-31: Reserved */
+/* FullCAN interrupt enable register */
+
+#define CANAF_FCANIE_FCANIE (1 << 0) /* Bit 0: Global FullCAN Interrupt Enable */
+ /* Bits 1-31: Reserved */
+
+/* FullCAN interrupt and capture register 0 */
+
+#define CANAF_FCANIC0_INTPND(n) (1 << (n)) /* n=0,1,2,... 31 */
+
+/* FullCAN interrupt and capture register 1 */
+
+#define CANAF_FCANIC1_INTPND(n) (1 << ((n)-32)) /* n=32,33,...63 */
+
+/* Central CAN registers */
+/* CAN Central Transmit Status Register */
+
+#define CAN_TXSR_TS1 (1 << 0) /* Bit 0: CAN1 sending */
+#define CAN_TXSR_TS2 (1 << 1) /* Bit 1: CAN2 sending */
+ /* Bits 2-7: Reserved */
+#define CAN_TXSR_TBS1 (1 << 8) /* Bit 8: All 3 CAN1 TX buffers available */
+#define CAN_TXSR_TBS2 (1 << 9) /* Bit 9: All 3 CAN2 TX buffers available */
+ /* Bits 10-15: Reserved */
+#define CAN_TXSR_TCS1 (1 << 16) /* Bit 16: All CAN1 xmissions completed */
+#define CAN_TXSR_TCS2 (1 << 17) /* Bit 17: All CAN2 xmissions completed */
+ /* Bits 18-31: Reserved */
+/* CAN Central Receive Status Register */
+
+#define CAN_RXSR_RS1 (1 << 0) /* Bit 0: CAN1 receiving */
+#define CAN_RXSR_RS2 (1 << 1) /* Bit 1: CAN2 receiving */
+ /* Bits 2-7: Reserved */
+#define CAN_RXSR_RB1 (1 << 8) /* Bit 8: CAN1 received message available */
+#define CAN_RXSR_RB2 (1 << 9) /* Bit 9: CAN2 received message available */
+ /* Bits 10-15: Reserved */
+#define CAN_RXSR_DOS1 (1 << 16) /* Bit 16: All CAN1 message lost */
+#define CAN_RXSR_DOS2 (1 << 17) /* Bit 17: All CAN2 message lost */
+ /* Bits 18-31: Reserved */
+/* CAN Central Miscellaneous Register */
+
+#define CAN_MSR_E1 (1 << 0) /* Bit 0: CAN1 error counters at limit */
+#define CAN_MSR_E2 (1 << 1) /* Bit 1: CAN2 error counters at limit */
+ /* Bits 2-7: Reserved */
+#define CAN_MSR_BS1 (1 << 8) /* Bit 8: CAN1 busy */
+#define CAN_MSR_BS2 (1 << 9) /* Bit 7: CAN2 busy */
+ /* Bits 10-31: Reserved */
+/* CAN1/2 registers */
+/* CAN operating mode */
+
+#define CAN_MOD_RM (1 << 0) /* Bit 0: Reset Mode */
+#define CAN_MOD_LOM (1 << 1) /* Bit 1: Listen Only Mode */
+#define CAN_MOD_STM (1 << 2) /* Bit 2: Self Test Mode */
+#define CAN_MOD_TPM (1 << 3) /* Bit 3: Transmit Priority Mode */
+#define CAN_MOD_SM (1 << 4) /* Bit 4: Sleep Mode */
+#define CAN_MOD_RPM (1 << 5) /* Bit 5: Receive Polarity Mode */
+ /* Bit 6: Reserved */
+#define CAN_MOD_TM (1 << 7) /* Bit 7: Test Mode */
+ /* Bits 8-31: Reserved */
+/* Command bits */
+
+#define CAN_CMR_TR (1 << 0) /* Bit 0: Transmission Request */
+#define CAN_CMR_AT (1 << 1) /* Bit 1: Abort Transmission */
+#define CAN_CMR_RRB (1 << 2) /* Bit 2: Release Receive Buffer */
+#define CAN_CMR_CDO (1 << 3) /* Bit 3: Clear Data Overrun */
+#define CAN_CMR_SRR (1 << 4) /* Bit 4: Self Reception Request */
+#define CAN_CMR_STB1 (1 << 5) /* Bit 5: Select Tx Buffer 1 */
+#define CAN_CMR_STB2 (1 << 6) /* Bit 6: Select Tx Buffer 2 */
+#define CAN_CMR_STB3 (1 << 7) /* Bit 7: Select Tx Buffer 3 */
+ /* Bits 8-31: Reserved */
+/* Controller Status and Error Counters */
+
+#define CAN_GSR_RBS (1 << 0) /* Bit 0: Receive Buffer Status */
+#define CAN_GSR_DOS (1 << 1) /* Bit 1: Data Overrun Status */
+#define CAN_GSR_TBS (1 << 2) /* Bit 2: Transmit Buffer Status */
+#define CAN_GSR_TCS (1 << 3) /* Bit 3: Transmit Complete Status */
+#define CAN_GSR_RS (1 << 4) /* Bit 4: Receive Status */
+#define CAN_GSR_TS (1 << 5) /* Bit 5: Transmit Status */
+#define CAN_GSR_ES (1 << 6) /* Bit 6: Error Status */
+#define CAN_GSR_BS (1 << 7) /* Bit 7: Bus Status */
+ /* Bits 8-15: Reserved */
+#define CAN_GSR_RXERR_SHIFT (16) /* Bits 16-23: Rx Error Counter */
+#define CAN_GSR_RXERR_MASK (0xff << CAN_GSR_RXERR_SHIFT)
+#define CAN_GSR_TXERR_SHIFT (24) /* Bits 24-31: Tx Error Counter */
+#define CAN_GSR_TXERR_MASK (0xff << CAN_GSR_TXERR_SHIFT)
+
+/* Interrupt and capture register */
+
+#define CAN_ICR_RI (1 << 0) /* Bit 0: Receive Interrupt */
+#define CAN_ICR_TI1 (1 << 1) /* Bit 1: Transmit Interrupt 1 */
+#define CAN_ICR_EI (1 << 2) /* Bit 2: Error Warning Interrupt */
+#define CAN_ICR_DOI (1 << 3) /* Bit 3: Data Overrun Interrupt */
+#define CAN_ICR_WUI (1 << 4) /* Bit 4: Wake-Up Interrupt */
+#define CAN_ICR_EPI (1 << 5) /* Bit 5: Error Passive Interrupt */
+#define CAN_ICR_ALI (1 << 6) /* Bit 6: Arbitration Lost Interrupt */
+#define CAN_ICR_BEI (1 << 7) /* Bit 7: Bus Error Interrupt */
+#define CAN_ICR_IDI (1 << 8) /* Bit 8: ID Ready Interrupt */
+#define CAN_ICR_TI2 (1 << 9) /* Bit 9: Transmit Interrupt 2 */
+#define CAN_ICR_TI3 (1 << 10) /* Bit 10: Transmit Interrupt 3 */
+ /* Bits 11-15: Reserved */
+#define CAN_ICR_ERRBIT_SHIFT (16) /* Bits 16-20: Error Code Capture */
+#define CAN_ICR_ERRBIT_MASK (0x1f << CAN_ICR_ERRBIT_SHIFT)
+# define CAN_ICR_ERRBIT_SOF (3 << CAN_ICR_ERRBIT_SHIFT) /* Start of Frame */
+# define CAN_ICR_ERRBIT_ID28 (2 << CAN_ICR_ERRBIT_SHIFT) /* ID28 ... ID21 */
+# define CAN_ICR_ERRBIT_SRTR (4 << CAN_ICR_ERRBIT_SHIFT) /* SRTR Bit */
+# define CAN_ICR_ERRBIT_IDE (5 << CAN_ICR_ERRBIT_SHIFT) /* DE bit */
+# define CAN_ICR_ERRBIT_ID20 (6 << CAN_ICR_ERRBIT_SHIFT) /* ID20 ... ID18 */
+# define CAN_ICR_ERRBIT_ID17 (7 << CAN_ICR_ERRBIT_SHIFT) /* ID17 ... 13 */
+# define CAN_ICR_ERRBIT_CRC (8 << CAN_ICR_ERRBIT_SHIFT) /* CRC Sequence */
+# define CAN_ICR_ERRBIT_DATA (10 << CAN_ICR_ERRBIT_SHIFT) /* Data Field */
+# define CAN_ICR_ERRBIT_LEN (11 << CAN_ICR_ERRBIT_SHIFT) /* Data Length Code */
+# define CAN_ICR_ERRBIT_ RTR (12 << CAN_ICR_ERRBIT_SHIFT) /* RTR Bit */
+# define CAN_ICR_ERRBIT_ID4 (14 << CAN_ICR_ERRBIT_SHIFT) /* ID4 ... ID0 */
+# define CAN_ICR_ERRBIT_ID12 (15 << CAN_ICR_ERRBIT_SHIFT) /* ID12 ... ID5 */
+# define CAN_ICR_ERRBIT_AERR (17 << CAN_ICR_ERRBIT_SHIFT) /* Active Error Flag */
+# define CAN_ICR_ERRBIT_INTERMSN (18 << CAN_ICR_ERRBIT_SHIFT) /* Intermission */
+# define CAN_ICR_ERRBIT_DOM (19 << CAN_ICR_ERRBIT_SHIFT) /* Tolerate Dominant Bits */
+# define CAN_ICR_ERRBIT_PERR (22 << CAN_ICR_ERRBIT_SHIFT) /* Passive Error Flag */
+# define CAN_ICR_ERRBIT_ERRDLM (23 << CAN_ICR_ERRBIT_SHIFT) /* Error Delimiter */
+# define CAN_ICR_ERRBIT_CRCDLM (24 << CAN_ICR_ERRBIT_SHIFT) /* CRC Delimiter */
+# define CAN_ICR_ERRBIT_ACKSLT (25 << CAN_ICR_ERRBIT_SHIFT) /* Acknowledge Slot */
+# define CAN_ICR_ERRBIT_EOF (26 << CAN_ICR_ERRBIT_SHIFT) /* End of Frame */
+# define CAN_ICR_ERRBIT_ACKDLM (27 << CAN_ICR_ERRBIT_SHIFT) /* Acknowledge Delimiter */
+# define CAN_ICR_ERRBIT_OVLD (28 << CAN_ICR_ERRBIT_SHIFT) /* Overload flag */
+#define CAN_ICR_ERRDIR (1 << 21) /* Bit 21: Direction bit at time of error */
+#define CAN_ICR_ERRC_SHIFT (22) /* Bits 22-23: Type of error */
+#define CAN_ICR_ERRC_MASK (3 << CAN_ICR_ERRC_SHIFT)
+# define CAN_ICR_ERRC_BIT (0 << CAN_ICR_ERRC_SHIFT)
+# define CAN_ICR_ERRC_FORM (1 << CAN_ICR_ERRC_SHIFT)
+# define CAN_ICR_ERRC_STUFF (2 << CAN_ICR_ERRC_SHIFT)
+# define CAN_ICR_ERRC_OTHER (3 << CAN_ICR_ERRC_SHIFT)
+#define CAN_ICR_ALCBIT_SHIFT (24) /* Bits 24-31: Bit number within frame */
+#define CAN_ICR_ALCBIT_MASK (0xff << CAN_ICR_ALCBIT_SHIFT)
+
+/* Interrupt Enable */
+
+#define CAN_IER_RIE (1 << 0) /* Bit 0: Receiver Interrupt Enable */
+#define CAN_IER_TIE1 (1 << 1) /* Bit 1: Transmit Interrupt Enable for Buffer1 */
+#define CAN_IER_EIE (1 << 2) /* Bit 2: Error Warning Interrupt Enable */
+#define CAN_IER_DOIE (1 << 3) /* Bit 3: Data Overrun Interrupt Enable */
+#define CAN_IER_WUIE (1 << 4) /* Bit 4: Wake-Up Interrupt Enable */
+#define CAN_IER_EPIE (1 << 5) /* Bit 5: Error Passive Interrupt Enable */
+#define CAN_IER_ALIE (1 << 6) /* Bit 6: Arbitration Lost Interrupt Enable */
+#define CAN_IER_BEIE (1 << 7) /* Bit 7: Bus Error Interrupt */
+#define CAN_IER_IDIE (1 << 8) /* Bit 8: ID Ready Interrupt Enable */
+#define CAN_IER_TIE2 (1 << 9) /* Bit 9: Transmit Interrupt Enable for Buffer2 */
+#define CAN_IER_TIE3 (1 << 10) /* Bit 10: Transmit Interrupt Enable for Buffer3 */
+ /* Bits 11-31: Reserved */
+/* Bus Timing */
+
+#define CAN_BTR_BRP_SHIFT (0) /* Bits 0-9: Baud Rate Prescaler */
+#define CAN_BTR_BRP_MASK (0x3ff << CAN_BTR_BRP_SHIFT)
+ /* Bits 10-13: Reserved */
+#define CAN_BTR_SJW_SHIFT (14) /* Bits 14-15: Synchronization Jump Width */
+#define CAN_BTR_SJW_MASK (3 << CAN_BTR_SJW_SHIFT)
+#define CAN_BTR_TSEG1_SHIFT (16) /* Bits 16-19: Sync to sample delay */
+#define CAN_BTR_TSEG1_MASK (15 << CAN_BTR_TSEG1_SHIFT)
+#define CAN_BTR_TSEG2_SHIFT (20) /* Bits 20-22: smaple to next delay */
+#define CAN_BTR_TSEG2_MASK (7 << CAN_BTR_TSEG2_SHIFT)
+#define CAN_BTR_SAM (1 << 23) /* Bit 23: Sampling */
+ /* Bits 24-31: Reserved */
+
+#define CAN_BTR_BRP_MAX (1024) /* Maximum BTR value (without decrement) */
+#define CAN_BTR_TSEG1_MAX (16) /* Maximum TSEG1 value (without decrement) */
+#define CAN_BTR_TSEG2_MAX (8) /* Maximum TSEG2 value (without decrement) */
+
+/* Error Warning Limit */
+
+#define CAN_EWL_SHIFT (0) /* Bits 0-7: Error warning limit */
+#define CAN_EWL_MASK (0xff << CAN_EWL_SHIFT)
+ /* Bits 8-31: Reserved */
+/* Status Register */
+
+#define CAN_SR_RBS1 (1 << 0) /* Bit 0: Receive Buffer Status */
+#define CAN_SR_DOS1 (1 << 1) /* Bit 1: Data Overrun Status */
+#define CAN_SR_TBS1 (1 << 2) /* Bit 2: Transmit Buffer Status 1 */
+#define CAN_SR_TCS1 (1 << 3) /* Bit 3: Transmission Complete Status */
+#define CAN_SR_RS1 (1 << 4) /* Bit 4: Receive Status */
+#define CAN_SR_TS1 (1 << 5) /* Bit 5: Transmit Status 1 */
+#define CAN_SR_ES1 (1 << 6) /* Bit 6: Error Status */
+#define CAN_SR_BS1 (1 << 7) /* Bit 7: Bus Status */
+#define CAN_SR_RBS2 (1 << 8) /* Bit 8: Receive Buffer Status */
+#define CAN_SR_DOS2 (1 << 9) /* Bit 9: Data Overrun Status */
+#define CAN_SR_TBS2 (1 << 10) /* Bit 10: Transmit Buffer Status 2 */
+#define CAN_SR_TCS2 (1 << 11) /* Bit 11: Transmission Complete Status */
+#define CAN_SR_RS2 (1 << 12) /* Bit 12: Receive Status */
+#define CAN_SR_TS2 (1 << 13) /* Bit 13: Transmit Status 2 */
+#define CAN_SR_ES2 (1 << 14) /* Bit 14: Error Status */
+#define CAN_SR_BS2 (1 << 15) /* Bit 15: Bus Status */
+#define CAN_SR_RBS3 (1 << 16) /* Bit 16: Receive Buffer Status */
+#define CAN_SR_DOS3 (1 << 17) /* Bit 17: Data Overrun Status */
+#define CAN_SR_TBS3 (1 << 18) /* Bit 18: Transmit Buffer Status 3 */
+#define CAN_SR_TCS3 (1 << 19) /* Bit 19: Transmission Complete Status */
+#define CAN_SR_RS3 (1 << 20) /* Bit 20: Receive Status */
+#define CAN_SR_TS3 (1 << 21) /* Bit 21: Transmit Status 3 */
+#define CAN_SR_ES3 (1 << 22) /* Bit 22: Error Status */
+#define CAN_SR_BS3 (1 << 23) /* Bit 23: Bus Status */
+ /* Bits 24-31: Reserved */
+/* Receive frame status */
+
+#define CAN_RFS_ID_SHIFT (0) /* Bits 0-9: ID Index */
+#define CAN_RFS_ID_MASK (0x03ff << CAN_RFS_ID_SHIFT)
+#define CAN_RFS_BP (1 << 10) /* Bit 10: Received in AF Bypass mode */
+ /* Bits 11-15: Reserved */
+#define CAN_RFS_DLC_SHIFT (16) /* Bits 16-19: Message Data Length Code (DLC) */
+#define CAN_RFS_DLC_MASK (15 << CAN_RFS_DLC_SHIFT)
+ /* Bits 20-29: Reserved */
+#define CAN_RFS_RTR (1 << 30) /* Bit 30: Message Remote Transmission Request */
+#define CAN_RFS_FF (1 << 31) /* Bit 31: Message 29-bit vs 11-bit ID */
+
+/* Received Identifier */
+
+#define CAN_RID_ID11_MASK (0x7ff) /* Bits 0-10: 11-bit Identifier (FF=0) */
+ /* Bits 11-31: Reserved */
+#define CAN_RID_ID29_MASK (0x1fffffff) /* Bits 0-28: 29-bit Identifiter (FF=1) */
+ /* Bits 29-31: Reserved */
+/* Received data bytes 1-4 */
+
+#define CAN_RDA_DATA1_SHIFT (0) /* Bits 0-7: If CANRFS >= 1 */
+#define CAN_RDA_DATA1_MASK (0x0ff << CAN_RDA_DATA1_SHIFT)
+#define CAN_RDA_DATA2_SHIFT (8) /* Bits 8-15: If CANRFS >= 2 */
+#define CAN_RDA_DATA2_MASK (0x0ff << CAN_RDA_DATA2_SHIFT)
+#define CAN_RDA_DATA3_SHIFT (16) /* Bits 16-23: If CANRFS >= 3 */
+#define CAN_RDA_DATA3_MASK (0x0ff << CAN_RDA_DATA3_SHIFT)
+#define CAN_RDA_DATA4_SHIFT (24) /* Bits 24-31: If CANRFS >= 4 */
+#define CAN_RDA_DATA4_MASK (0x0ff << CAN_RDA_DATA4_SHIFT)
+
+/* Received data bytes 5-8 */
+
+#define CAN_RDB_DATA5_SHIFT (0) /* Bits 0-7: If CANRFS >= 5 */
+#define CAN_RDB_DATA5_MASK (0x0ff << CAN_RDB_DATA5_SHIFT)
+#define CAN_RDB_DATA6_SHIFT (8) /* Bits 8-15: If CANRFS >= 6 */
+#define CAN_RDB_DATA6_MASK (0x0ff << CAN_RDB_DATA6_SHIFT)
+#define CAN_RDB_DATA7_SHIFT (16) /* Bits 16-23: If CANRFS >= 7 */
+#define CAN_RDB_DATA7_MASK (0x0ff << CAN_RDB_DATA7_SHIFT)
+#define CAN_RDB_DATA8_SHIFT (24) /* Bits 24-31: If CANRFS >= 8 */
+#define CAN_RDB_DATA8_MASK (0x0ff << CAN_RDB_DATA8_SHIFT)
+
+/* Transmit frame info (Tx Buffer 1), Transmit frame info (Tx Buffer 2), and
+ * Transmit frame info (Tx Buffer 3) common bit field definitions
+ */
+
+#define CAN_TFI_PRIO_SHIFT (0) /* Bits 0-7: TX buffer priority */
+#define CAN_TFI_PRIO_MASK (0xff << CAN_TFI_PRIO_SHIFT)
+ /* Bits 8-15: Reserved */
+#define CAN_TFI_DLC_SHIFT (16) /* Bits 16-19: TX Data Length Code */
+#define CAN_TFI_DLC_MASK (15 << CAN_TFI_DLC_SHIFT)
+ /* Bits 20-29: Reserved */
+#define CAN_TFI_RTR (1 << 30) /* Bit 30: TX RTR bit */
+#define CAN_TFI_FF (1 << 31) /* Bit 31: Message 29-bit vs 11-bit ID */
+
+/* Transmit Identifier (Tx Buffer 1), Transmit Identifier (Tx Buffer 2), and
+ * Transmit Identifier (Tx Buffer 3) common bit field definitions.
+ */
+
+#define CAN_TID_ID11_MASK (0x7ff) /* Bits 0-10: 11-bit Identifier (FF=0) */
+ /* Bits 11-31: Reserved */
+#define CAN_TID_ID29_MASK (0x1fffffff) /* Bits 0-28: 29-bit Identifiter (FF=1) */
+ /* Bits 29-31: Reserved */
+
+/* Transmit data bytes 1-4 (Tx Buffer 1), Transmit data bytes 1-4 (Tx Buffer 2), and
+ * Transmit data bytes 1-4 (Tx Buffer 3) common bit field definitions.
+ */
+
+#define CAN_TDA_DATA1_SHIFT (0) /* Bits 0-7: RTR=0 && DLC >= 1 */
+#define CAN_TDA_DATA1_MASK (0x0ff << CAN_TDA_DATA1_SHIFT)
+#define CAN_TDA_DATA2_SHIFT (8) /* Bits 8-15: RTR=0 && DLC >= 2 */
+#define CAN_TDA_DATA2_MASK (0x0ff << CAN_TDA_DATA2_SHIFT)
+#define CAN_TDA_DATA3_SHIFT (16) /* Bits 16-23: RTR=0 && DLC >= 3 */
+#define CAN_TDA_DATA3_MASK (0x0ff << CAN_TDA_DATA3_SHIFT)
+#define CAN_TDA_DATA4_SHIFT (24) /* Bits 24-31: RTR=0 && DLC >= 4 */
+#define CAN_TDA_DATA4_MASK (0x0ff << CAN_TDA_DATA4_SHIFT)
+
+/* Transmit data bytes 5-8 (Tx Buffer 1), Transmit data bytes 5-8 (Tx Buffer 2), and
+ * Transmit data bytes 5-8 (Tx Buffer 3) common bit field definitions.
+ */
+
+#define CAN_RDB_DATA5_SHIFT (0) /* Bits 0-7: RTR=0 && DLC >= 5 */
+#define CAN_RDB_DATA5_MASK (0x0ff << CAN_RDB_DATA5_SHIFT)
+#define CAN_RDB_DATA6_SHIFT (8) /* Bits 8-15: RTR=0 && DLC >= 6 */
+#define CAN_RDB_DATA6_MASK (0x0ff << CAN_RDB_DATA6_SHIFT)
+#define CAN_RDB_DATA7_SHIFT (16) /* Bits 16-23: RTR=0 && DLC >= 7 */
+#define CAN_RDB_DATA7_MASK (0x0ff << CAN_RDB_DATA7_SHIFT)
+#define CAN_RDB_DATA8_SHIFT (24) /* Bits 24-31: RTR=0 && DLC >= 8 */
+#define CAN_RDB_DATA8_MASK (0x0ff << CAN_RDB_DATA8_SHIFT)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_CHIP_CAN_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_dac.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_dac.h
new file mode 100644
index 000000000..be78bef05
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_dac.h
@@ -0,0 +1,97 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_dac.h
+ *
+ * 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
+ * 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_LPC17XX_LPC17_CHIP_DAC_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_CHIP_DAC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_DAC_CR_OFFSET 0x0000 /* D/A Converter Register */
+#define LPC17_DAC_CTRL_OFFSET 0x0004 /* DAC Control register */
+#define LPC17_DAC_CNTVAL_OFFSET 0x0008 /* DAC Counter Value register */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_DAC_CR (LPC17_DAC_BASE+LPC17_DAC_CR_OFFSET)
+#define LPC17_DAC_CTRL (LPC17_DAC_BASE+LPC17_DAC_CTRL_OFFSET)
+#define LPC17_DAC_CNTVAL (LPC17_DAC_BASE+LPC17_DAC_CNTVAL_OFFSET)
+
+/* Register bit definitions *********************************************************/
+
+/* D/A Converter Register */
+ /* Bits 0-5: Reserved */
+#define DAC_CR_VALUE_SHIFT (6) /* Bits 6-15: Controls voltage on the AOUT pin */
+#define DAC_CR_VALUE_MASK (0x3ff << DAC_CR_VALUE_SHIFT)
+#define DAC_CR_BIAS (1 << 16) /* Bit 16: Controls DAC settling time */
+ /* Bits 17-31: Reserved */
+/* DAC Control register */
+
+#define DAC_CTRL_INTDMAREQ (1 << 0) /* Bit 0: Timer timed out */
+#define DAC_CTRL_DBLBUFEN (1 << 1) /* Bit 1: Enable DACR double-buffering */
+#define DAC_CTRL_CNTEN (1 << 2) /* Bit 2: Enable timeout counter */
+#define DAC_CTRL_DMAEN (1 << 3) /* Bit 3: Enable DMA access */
+ /* Bits 4-31: Reserved */
+/* DAC Counter Value register */
+
+#define DAC_CNTVAL_SHIFT (0) /* Bits 0-15: Reload value for DAC interrupt/DMA timer */
+#define DAC_CNTVAL_MASK (0xffff << DAC_CNTVAL_SHIFT)
+ /* Bits 8-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_CHIP_DAC_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_ethernet.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_ethernet.h
new file mode 100644
index 000000000..b0791ced9
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_ethernet.h
@@ -0,0 +1,597 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_ethernet.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC17_ETHERNET_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_ETHERNET_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+/* MAC registers */
+
+#define LPC17_ETH_MAC1_OFFSET 0x0000 /* MAC configuration register 1 */
+#define LPC17_ETH_MAC2_OFFSET 0x0004 /* MAC configuration register 2 */
+#define LPC17_ETH_IPGT_OFFSET 0x0008 /* Back-to-Back Inter-Packet-Gap register */
+#define LPC17_ETH_IPGR_OFFSET 0x000c /* Non Back-to-Back Inter-Packet-Gap register */
+#define LPC17_ETH_CLRT_OFFSET 0x0010 /* Collision window / Retry register */
+#define LPC17_ETH_MAXF_OFFSET 0x0014 /* Maximum Frame register */
+#define LPC17_ETH_SUPP_OFFSET 0x0018 /* PHY Support register */
+#define LPC17_ETH_TEST_OFFSET 0x001c /* Test register */
+#define LPC17_ETH_MCFG_OFFSET 0x0020 /* MII Mgmt Configuration register */
+#define LPC17_ETH_MCMD_OFFSET 0x0024 /* MII Mgmt Command register */
+#define LPC17_ETH_MADR_OFFSET 0x0028 /* MII Mgmt Address register */
+#define LPC17_ETH_MWTD_OFFSET 0x002c /* MII Mgmt Write Data register */
+#define LPC17_ETH_MRDD_OFFSET 0x0030 /* MII Mgmt Read Data register */
+#define LPC17_ETH_MIND_OFFSET 0x0034 /* MII Mgmt Indicators register */
+#define LPC17_ETH_SA0_OFFSET 0x0040 /* Station Address 0 register */
+#define LPC17_ETH_SA1_OFFSET 0x0044 /* Station Address 1 register */
+#define LPC17_ETH_SA2_OFFSET 0x0048 /* Station Address 2 register */
+
+/* Control registers */
+
+#define LPC17_ETH_CMD_OFFSET 0x0100 /* Command register */
+#define LPC17_ETH_STAT_OFFSET 0x0104 /* Status register */
+#define LPC17_ETH_RXDESC_OFFSET 0x0108 /* Receive descriptor base address register */
+#define LPC17_ETH_RXSTAT_OFFSET 0x010c /* Receive status base address register */
+#define LPC17_ETH_RXDESCNO_OFFSET 0x0110 /* Receive number of descriptors register */
+#define LPC17_ETH_RXPRODIDX_OFFSET 0x0114 /* Receive produce index register */
+#define LPC17_ETH_RXCONSIDX_OFFSET 0x0118 /* Receive consume index register */
+#define LPC17_ETH_TXDESC_OFFSET 0x011c /* Transmit descriptor base address register */
+#define LPC17_ETH_TXSTAT_OFFSET 0x0120 /* Transmit status base address register */
+#define LPC17_ETH_TXDESCRNO_OFFSET 0x0124 /* Transmit number of descriptors register */
+#define LPC17_ETH_TXPRODIDX_OFFSET 0x0128 /* Transmit produce index register */
+#define LPC17_ETH_TXCONSIDX_OFFSET 0x012c /* Transmit consume index register */
+#define LPC17_ETH_TSV0_OFFSET 0x0158 /* Transmit status vector 0 register */
+#define LPC17_ETH_TSV1_OFFSET 0x015c /* Transmit status vector 1 register */
+#define LPC17_ETH_RSV_OFFSET 0x0160 /* Receive status vector register */
+#define LPC17_ETH_FCCNTR_OFFSET 0x0170 /* Flow control counter register */
+#define LPC17_ETH_FCSTAT_OFFSET 0x0174 /* Flow control status register */
+
+/* Rx filter registers */
+
+#define LPC17_ETH_RXFLCTRL_OFFSET 0x0200 /* Receive filter control register */
+#define LPC17_ETH_RXFLWOLST_OFFSET 0x0204 /* Receive filter WoL status register */
+#define LPC17_ETH_RXFLWOLCLR_OFFSET 0x0208 /* Receive filter WoL clear register */
+#define LPC17_ETH_HASHFLL_OFFSET 0x0210 /* Hash filter table LSBs register */
+#define LPC17_ETH_HASHFLH_OFFSET 0x0214 /* Hash filter table MSBs register */
+
+/* Module control registers */
+
+#define LPC17_ETH_INTST_OFFSET 0x0fe0 /* Interrupt status register */
+#define LPC17_ETH_INTEN_OFFSET 0x0fe4 /* Interrupt enable register */
+#define LPC17_ETH_INTCLR_OFFSET 0x0fe8 /* Interrupt clear register */
+#define LPC17_ETH_INTSET_OFFSET 0x0fec /* Interrupt set register */
+#define LPC17_ETH_PWRDOWN_OFFSET 0x0ff4 /* Power-down register */
+
+/* Register addresses ***************************************************************/
+/* MAC registers */
+
+#define LPC17_ETH_MAC1 (LPC17_ETH_BASE+LPC17_ETH_MAC1_OFFSET)
+#define LPC17_ETH_MAC2 (LPC17_ETH_BASE+LPC17_ETH_MAC2_OFFSET)
+#define LPC17_ETH_IPGT (LPC17_ETH_BASE+LPC17_ETH_IPGT_OFFSET)
+#define LPC17_ETH_IPGR (LPC17_ETH_BASE+LPC17_ETH_IPGR_OFFSET)
+#define LPC17_ETH_CLRT (LPC17_ETH_BASE+LPC17_ETH_CLRT_OFFSET)
+#define LPC17_ETH_MAXF (LPC17_ETH_BASE+LPC17_ETH_MAXF_OFFSET)
+#define LPC17_ETH_SUPP (LPC17_ETH_BASE+LPC17_ETH_SUPP_OFFSET)
+#define LPC17_ETH_TEST (LPC17_ETH_BASE+LPC17_ETH_TEST_OFFSET)
+#define LPC17_ETH_MCFG (LPC17_ETH_BASE+LPC17_ETH_MCFG_OFFSET)
+#define LPC17_ETH_MCMD (LPC17_ETH_BASE+LPC17_ETH_MCMD_OFFSET)
+#define LPC17_ETH_MADR (LPC17_ETH_BASE+LPC17_ETH_MADR_OFFSET)
+#define LPC17_ETH_MWTD (LPC17_ETH_BASE+LPC17_ETH_MWTD_OFFSET)
+#define LPC17_ETH_MRDD (LPC17_ETH_BASE+LPC17_ETH_MRDD_OFFSET)
+#define LPC17_ETH_MIND (LPC17_ETH_BASE+LPC17_ETH_MIND_OFFSET)
+#define LPC17_ETH_SA0 (LPC17_ETH_BASE+LPC17_ETH_SA0_OFFSET)
+#define LPC17_ETH_SA1 (LPC17_ETH_BASE+LPC17_ETH_SA1_OFFSET)
+#define LPC17_ETH_SA2 (LPC17_ETH_BASE+LPC17_ETH_SA2_OFFSET)
+
+/* Control registers */
+
+#define LPC17_ETH_CMD (LPC17_ETH_BASE+LPC17_ETH_CMD_OFFSET)
+#define LPC17_ETH_STAT (LPC17_ETH_BASE+LPC17_ETH_STAT_OFFSET)
+#define LPC17_ETH_RXDESC (LPC17_ETH_BASE+LPC17_ETH_RXDESC_OFFSET)
+#define LPC17_ETH_RXSTAT (LPC17_ETH_BASE+LPC17_ETH_RXSTAT_OFFSET)
+#define LPC17_ETH_RXDESCNO (LPC17_ETH_BASE+LPC17_ETH_RXDESCNO_OFFSET)
+#define LPC17_ETH_RXPRODIDX (LPC17_ETH_BASE+LPC17_ETH_RXPRODIDX_OFFSET)
+#define LPC17_ETH_RXCONSIDX (LPC17_ETH_BASE+LPC17_ETH_RXCONSIDX_OFFSET)
+#define LPC17_ETH_TXDESC (LPC17_ETH_BASE+LPC17_ETH_TXDESC_OFFSET)
+#define LPC17_ETH_TXSTAT (LPC17_ETH_BASE+LPC17_ETH_TXSTAT_OFFSET)
+#define LPC17_ETH_TXDESCRNO (LPC17_ETH_BASE+LPC17_ETH_TXDESCRNO_OFFSET)
+#define LPC17_ETH_TXPRODIDX (LPC17_ETH_BASE+LPC17_ETH_TXPRODIDX_OFFSET)
+#define LPC17_ETH_TXCONSIDX (LPC17_ETH_BASE+LPC17_ETH_TXCONSIDX_OFFSET)
+#define LPC17_ETH_TSV0 (LPC17_ETH_BASE+LPC17_ETH_TSV0_OFFSET)
+#define LPC17_ETH_TSV1 (LPC17_ETH_BASE+LPC17_ETH_TSV1_OFFSET)
+#define LPC17_ETH_RSV (LPC17_ETH_BASE+LPC17_ETH_RSV_OFFSET)
+#define LPC17_ETH_FCCNTR (LPC17_ETH_BASE+LPC17_ETH_FCCNTR_OFFSET)
+#define LPC17_ETH_FCSTAT (LPC17_ETH_BASE+LPC17_ETH_FCSTAT_OFFSET)
+
+/* Rx filter registers */
+
+#define LPC17_ETH_RXFLCTRL (LPC17_ETH_BASE+LPC17_ETH_RXFLCTRL_OFFSET)
+#define LPC17_ETH_RXFLWOLST (LPC17_ETH_BASE+LPC17_ETH_RXFLWOLST_OFFSET)
+#define LPC17_ETH_RXFLWOLCLR (LPC17_ETH_BASE+LPC17_ETH_RXFLWOLCLR_OFFSET)
+#define LPC17_ETH_HASHFLL (LPC17_ETH_BASE+LPC17_ETH_HASHFLL_OFFSET)
+#define LPC17_ETH_HASHFLH (LPC17_ETH_BASE+LPC17_ETH_HASHFLH_OFFSET)
+
+/* Module control registers */
+
+#define LPC17_ETH_INTST (LPC17_ETH_BASE+LPC17_ETH_INTST_OFFSET)
+#define LPC17_ETH_INTEN (LPC17_ETH_BASE+LPC17_ETH_INTEN_OFFSET)
+#define LPC17_ETH_INTCLR (LPC17_ETH_BASE+LPC17_ETH_INTCLR_OFFSET)
+#define LPC17_ETH_INTSET (LPC17_ETH_BASE+LPC17_ETH_INTSET_OFFSET)
+#define LPC17_ETH_PWRDOWN (LPC17_ETH_BASE+LPC17_ETH_PWRDOWN_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* MAC registers */
+/* MAC configuration register 1 (MAC1) */
+
+#define ETH_MAC1_RE (1 << 0) /* Bit 0: Receive enable */
+#define ETH_MAC1_PARF (1 << 1) /* Bit 1: Passall all receive frames */
+#define ETH_MAC1_RFC (1 << 2) /* Bit 2: RX flow control */
+#define ETH_MAC1_TFC (1 << 3) /* Bit 3: TX flow control */
+#define ETH_MAC1_LPBK (1 << 4) /* Bit 4: Loopback */
+ /* Bits 5-7: Reserved */
+#define ETH_MAC1_TXRST (1 << 8) /* Bit 8: Reset TX */
+#define ETH_MAC1_MCSTXRST (1 << 9) /* Bit 9: Reset MCS/TX */
+#define ETH_MAC1_RXRST (1 << 10) /* Bit 10: Reset RX */
+#define ETH_MAC1_MCSRXRST (1 << 11) /* Bit 11: Reset MCS/RX */
+ /* Bits 12-13: Reserved */
+#define ETH_MAC1_SIMRST (1 << 14) /* Bit 14: Simulation reset */
+#define ETH_MAC1_SOFTRST (1 << 15) /* Bit 15: Soft reset */
+ /* Bits 16-31: Reserved */
+/* MAC configuration register 2 (MAC2) */
+
+#define ETH_MAC2_FD (1 << 0) /* Bit 0: Full duplex */
+#define ETH_MAC2_FLC (1 << 1) /* Bit 1: Frame length checking */
+#define ETH_MAC2_HFE (1 << 2) /* Bit 2: Huge frame enable */
+#define ETH_MAC2_DCRC (1 << 3) /* Bit 3: Delayed CRC */
+#define ETH_MAC2_CRCEN (1 << 4) /* Bit 4: CRC enable */
+#define ETH_MAC2_PADCRCEN (1 << 5) /* Bit 5: Pad/CRC enable */
+#define ETH_MAC2_VLANPADEN (1 << 6) /* Bit 6: VLAN pad enable */
+#define ETH_MAC2_AUTOPADEN (1 << 7) /* Bit 7: Auto detect pad enable */
+#define ETH_MAC2_PPE (1 << 8) /* Bit 8: Pure preamble enforcement */
+#define ETH_MAC2_LPE (1 << 9) /* Bit 9: Long preamble enforcement */
+ /* Bits 10-11: Reserved */
+#define ETH_MAC2_NBKOFF (1 << 12) /* Bit 12: No backoff */
+#define ETH_MAC2_BPNBKOFF (1 << 13) /* Bit 13: Back pressure/no backoff */
+#define ETH_MAC2_EXDEF (1 << 14) /* Bit 14: Excess defer */
+ /* Bits 15-31: Reserved */
+/* Back-to-Back Inter-Packet-Gap register (IPGT) */
+
+#define ETH_IPGT_SHIFT (0) /* Bits 0-6 */
+#define ETH_IPGT_MASK (0x7f << ETH_IPGT_SHIFT)
+ /* Bits 7-31: Reserved */
+/* Non Back-to-Back Inter-Packet-Gap register (IPGR) */
+
+#define ETH_IPGR_GAP2_SHIFT (0) /* Bits 0-6: Gap part 2 */
+#define ETH_IPGR_GAP2_MASK (0x7f << ETH_IPGR_GAP2_SHIFT)
+ /* Bit 7: Reserved */
+#define ETH_IPGR_GAP1_SHIFT (8) /* Bits 8-18: Gap part 1 */
+#define ETH_IPGR_GAP1_MASK (0x7f << ETH_IPGR_GAP2_SHIFT)
+ /* Bits 15-31: Reserved */
+/* Collision window / Retry register (CLRT) */
+
+#define ETH_CLRT_RMAX_SHIFT (0) /* Bits 0-3: Retransmission maximum */
+#define ETH_CLRT_RMAX_MASK (15 << ETH_CLRT_RMAX_SHIFT)
+ /* Bits 4-7: Reserved */
+#define ETH_CLRT_COLWIN_SHIFT (8) /* Bits 8-13: Collision window */
+#define ETH_CLRT_COLWIN_MASK (0x3f << ETH_CLRT_COLWIN_SHIFT)
+ /* Bits 14-31: Reserved */
+/* Maximum Frame register (MAXF) */
+
+#define ETH_MAXF_SHIFT (0) /* Bits 0-15 */
+#define ETH_MAXF_MASK (0xffff << ETH_MAXF_SHIFT)
+ /* Bits 16-31: Reserved */
+/* PHY Support register (SUPP) */
+ /* Bits 0-7: Reserved */
+#define ETH_SUPP_SPEED (1 << 8) /* Bit 8: 0=10Bps 1=100Bps */
+ /* Bits 9-31: Reserved */
+/* Test register (TEST) */
+
+#define ETH_TEST_SPQ (1 << 0) /* Bit 0: Shortcut pause quanta */
+#define ETH_TEST_TP (1 << 1) /* Bit 1: Test pause */
+#define ETH_TEST_TBP (1 << 2) /* Bit 2: Test packpressure */
+ /* Bits 3-31: Reserved */
+/* MII Mgmt Configuration register (MCFG) */
+
+#define ETH_MCFG_SCANINC (1 << 0) /* Bit 0: Scan increment */
+#define ETH_MCFG_SUPPRE (1 << 1) /* Bit 1: Suppress preamble */
+#define ETH_MCFG_CLKSEL_SHIFT (2) /* Bits 2-5: Clock select */
+#define ETH_MCFG_CLKSEL_MASK (15 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV4 (0 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV6 (2 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV8 (3 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV10 (4 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV14 (5 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV20 (6 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV28 (7 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV36 (8 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV40 (9 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV44 (10 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV48 (11 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV52 (12 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV56 (13 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV60 (14 << ETH_MCFG_CLKSEL_SHIFT)
+# define ETH_MCFG_CLKSEL_DIV64 (15 << ETH_MCFG_CLKSEL_SHIFT)
+ /* Bits 6-14: Reserved */
+#define ETH_MCFG_MIIRST (1 << 15) /* Bit 15: Reset MII mgmt */
+ /* Bits 16-31: Reserved */
+/* MII Mgmt Command register (MCMD) */
+
+#define ETH_MCMD_READ (1 << 0) /* Bit 0: Single read cycle */
+#define ETH_MCMD_SCAN (1 << 1) /* Bit 1: Continuous read cycles */
+ /* Bits 2-31: Reserved */
+#define ETH_MCMD_WRITE (0)
+
+/* MII Mgmt Address register (MADR) */
+
+#define ETH_MADR_REGADDR_SHIFT (0) /* Bits 0-4: Register address */
+#define ETH_MADR_REGADDR_MASK (31 << ETH_MADR_REGADDR_SHIFT)
+ /* Bits 7-5: Reserved */
+#define ETH_MADR_PHYADDR_SHIFT (8) /* Bits 8-12: PHY address */
+#define ETH_MADR_PHYADDR_MASK (31 << ETH_MADR_PHYADDR_SHIFT)
+ /* Bits 13-31: Reserved */
+/* MII Mgmt Write Data register (MWTD) */
+
+#define ETH_MWTD_SHIFT (0) /* Bits 0-15 */
+#define ETH_MWTD_MASK (0xffff << ETH_MWTD_SHIFT)
+ /* Bits 16-31: Reserved */
+/* MII Mgmt Read Data register (MRDD) */
+
+#define ETH_MRDD_SHIFT (0) /* Bits 0-15 */
+#define ETH_MRDD_MASK (0xffff << ETH_MRDD_SHIFT)
+ /* Bits 16-31: Reserved */
+/* MII Mgmt Indicators register (MIND) */
+
+#define ETH_MIND_BUSY (1 << 0) /* Bit 0: Busy */
+#define ETH_MIND_SCANNING (1 << 1) /* Bit 1: Scanning */
+#define ETH_MIND_NVALID (1 << 2) /* Bit 2: Not valid */
+#define ETH_MIND_MIIFAIL (1 << 3) /* Bit 3: MII link fail */
+ /* Bits 4-31: Reserved */
+/* Station Address 0 register (SA0) */
+
+#define ETH_SA0_OCTET2_SHIFT (0) /* Bits 0-7: Station address 2nd octet */
+#define ETH_SA0_OCTET2_MASK (0xff << ETH_SA0_OCTET2_SHIFT)
+#define ETH_SA0_OCTET1_SHIFT (8) /* Bits 8-15: Station address 1st octet */
+#define ETH_SA0_OCTET1_MASK (0xff << ETH_SA0_OCTET1_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Station Address 1 register (SA1) */
+
+#define ETH_SA1_OCTET4_SHIFT (0) /* Bits 0-7: Station address 4th octet */
+#define ETH_SA1_OCTET4_MASK (0xff << ETH_SA0_OCTET4_SHIFT)
+#define ETH_SA1_OCTET3_SHIFT (8) /* Bits 8-15: Station address 3rd octet */
+#define ETH_SA1_OCTET3_MASK (0xff << ETH_SA0_OCTET3_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Station Address 2 register (SA2) */
+
+#define ETH_SA2_OCTET6_SHIFT (0) /* Bits 0-7: Station address 5th octet */
+#define ETH_SA2_OCTET6_MASK (0xff << ETH_SA0_OCTET6_SHIFT)
+#define ETH_SA2_OCTET5_SHIFT (8) /* Bits 8-15: Station address 6th octet */
+#define ETH_SA2_OCTET5_MASK (0xff << ETH_SA0_OCTET5_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Control registers */
+/* Command register (CMD) */
+
+#define ETH_CMD_RXEN (1 << 0) /* Bit 0: Receive enable */
+#define ETH_CMD_TXEN (1 << 1) /* Bit 1: Transmit enable */
+ /* Bit 2: Reserved */
+#define ETH_CMD_REGRST (1 << 3) /* Bit 3: Reset host registers */
+#define ETH_CMD_TXRST (1 << 4) /* Bit 4: Reset transmit datapath */
+#define ETH_CMD_RXRST (1 << 5) /* Bit 5: Reset receive datapath */
+#define ETH_CMD_PRFRAME (1 << 6) /* Bit 6: Pass run frame */
+#define ETH_CMD_PRFILTER (1 << 7) /* Bit 7: Pass RX filter */
+#define ETH_CMD_TXFC (1 << 8) /* Bit 8: TX flow control */
+#define ETH_CMD_RMII (1 << 9) /* Bit 9: RMII mode */
+#define ETH_CMD_FD (1 << 10) /* Bit 10: Full duplex */
+ /* Bits 11-31: Reserved */
+/* Status register */
+
+#define ETH_STAT_RX (1 << 0) /* Bit 0: RX status */
+#define ETH_STAT_TX (1 << 1) /* Bit 1: TX status */
+ /* Bits 2-31: Reserved */
+/* Receive descriptor base address register (RXDESC)
+ *
+ * The receive descriptor base address is a byte address aligned to a word
+ * boundary i.e. LSB 1:0 are fixed to 00. The register contains the lowest
+ * address in the array of descriptors.
+ */
+
+/* Receive status base address register (RXSTAT)
+ *
+ * The receive status base address is a byte address aligned to a double word
+ * boundary i.e. LSB 2:0 are fixed to 000.
+ */
+
+/* Receive number of descriptors register (RXDESCNO) */
+
+#define ETH_RXDESCNO_SHIFT (0) /* Bits 0-15 */
+#define ETH_RXDESCNO_MASK (0xffff << ETH_RXDESCNO_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Receive produce index register (RXPRODIDX) */
+
+#define ETH_RXPRODIDX_SHIFT (0) /* Bits 0-15 */
+#define ETH_RXPRODIDX_MASK (0xffff << ETH_RXPRODIDX_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Receive consume index register (RXCONSIDX) */
+
+#define ETH_RXCONSIDX_SHIFT (0) /* Bits 0-15 */
+#define ETH_RXCONSIDX_MASK (0xffff << ETH_RXPRODIDX_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Transmit descriptor base address register (TXDESC)
+ *
+ * The transmit descriptor base address is a byte address aligned to a word
+ * boundary i.e. LSB 1:0 are fixed to 00. The register contains the lowest
+ * address in the array of descriptors.
+ */
+
+/* Transmit status base address register (TXSTAT)
+ *
+ * The transmit status base address is a byte address aligned to a word
+ * boundary i.e. LSB1:0 are fixed to 00. The register contains the lowest
+ * address in the array of statuses.
+ */
+
+/* Transmit number of descriptors register (TXDESCRNO) */
+
+#define ETH_TXDESCRNO_SHIFT (0) /* Bits 0-15 */
+#define ETH_TXDESCRNO_MASK (0xffff << ETH_TXDESCRNO_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Transmit produce index register (TXPRODIDX) */
+
+#define ETH_TXPRODIDX_SHIFT (0) /* Bits 0-15 */
+#define ETH_TXPRODIDX_MASK (0xffff << ETH_TXPRODIDX_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Transmit consume index register (TXCONSIDX) */
+
+#define ETH_TXCONSIDX_SHIFT (0) /* Bits 0-15 */
+#define ETH_TXCONSIDX_MASK (0xffff << ETH_TXPRODIDX_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Transmit status vector 0 register (TSV0) */
+
+#define ETH_TSV0_CRCERR (1 << 0) /* Bit 0: CRC error */
+#define ETH_TSV0_LENCHKERR (1 << 1) /* Bit 1: Length check error */
+#define ETH_TSV0_LENOOR (1 << 2) /* Bit 2: Length out of range */
+#define ETH_TSV0_DONE (1 << 3) /* Bit 3: Done */
+#define ETH_TSV0_MCAST (1 << 4) /* Bit 4: Multicast */
+#define ETH_TSV0_BCAST (1 << 5) /* Bit 5: Broadcast */
+#define ETH_TSV0_PKTDEFER (1 << 6) /* Bit 6: Packet Defer */
+#define ETH_TSV0_EXCDEFER (1 << 7) /* Bit 7: Excessive Defer */
+#define ETH_TSV0_EXCCOL (1 << 8) /* Bit 8: Excessive Collision */
+#define ETH_TSV0_LATECOL (1 << 9) /* Bit 9: Late Collision */
+#define ETH_TSV0_GIANT (1 << 10) /* Bit 10: Giant */
+#define ETH_TSV0_UNDRUN (1 << 11) /* Bit 11: Underrun */
+#define ETH_TSV0_TOTBYTES_SHIFT (12) /* Bits 12-27:Total bytes */
+#define ETH_TSV0_TOTBYTES_MASK (0xffff << ETH_TSV0_TOTBYTES_SHIFT)
+#define ETH_TSV0_CTLFRAME (1 << 28) /* Bit 28: Control frame */
+#define ETH_TSV0_PAUSE (1 << 29) /* Bit 29: Pause */
+#define ETH_TSV0_BP (1 << 30) /* Bit 30: Backpressure */
+#define ETH_TSV0_VLAN (1 << 31) /* Bit 31: VLAN */
+
+/* Transmit status vector 1 register (TSV1) */
+
+#define ETH_TSV1_TXCNT_SHIFT (0) /* Bits 0-15: Transmit byte count */
+#define ETH_TSV1_TXCNT_MASK (0xffff << ETH_TSV1_TXCNT_SHIFT)
+#define ETH_TSV1_COLCNT_SHIFT (16) /* Bits 16-19: Transmit collision count */
+#define ETH_TSV1_COLCNT_MASK (15 << ETH_TSV1_COLCNT_SHIFT)
+ /* Bits 20-31: Reserved */
+/* Receive status vector register (RSV) */
+
+#define ETH_RSV_RXCNT_SHIFT (0) /* Bits 0-15: Received byte count */
+#define ETH_RSV_RXCNT_MASK (0xffff << ETH_RSV_RXCNT_SHIFT)
+#define ETH_RSV_PKTPI (1 << 16) /* Bit 16: Packet previously ignored */
+#define ETH_RSV_RXEPS (1 << 17) /* Bit 17: RXDV event previously seen */
+#define ETH_RSV_CEPS (1 << 18) /* Bit 18: Carrier event previously seen */
+#define ETH_RSV_RXCV (1 << 19) /* Bit 19: Receive code violation */
+#define ETH_RSV_CRCERR (1 << 20) /* Bit 20: CRC error */
+#define ETH_RSV_LENCHKERR (1 << 21) /* Bit 21: Length check error */
+#define ETH_RSV_LENOOR (1 << 22) /* Bit 22: Length out of range */
+#define ETH_RSV_RXOK (1 << 23) /* Bit 23: Receive OK */
+#define ETH_RSV_MCAST (1 << 24) /* Bit 24: Multicast */
+#define ETH_RSV_BCAST (1 << 25) /* Bit 25: Broadcast */
+#define ETH_RSV_DRIBNIB (1 << 26) /* Bit 26: Dribble Nibble */
+#define ETH_RSV_CTLFRAME (1 << 27) /* Bit 27: Control frame */
+#define ETH_RSV_PAUSE (1 << 28) /* Bit 28: Pause */
+#define ETH_RSV_UNSUPOP (1 << 29) /* Bit 29: Unsupported Opcode */
+#define ETH_RSV_VLAN (1 << 30) /* Bit 30: VLAN */
+ /* Bit 31: Reserved */
+/* Flow control counter register (FCCNTR) */
+
+#define ETH_FCCNTR_MCOUNT_SHIFT (0) /* Bits 0-15: Mirror count */
+#define ETH_FCCNTR_MCOUNT_MASK (0xffff << ETH_FCCNTR_MCOUNT_SHIFT)
+#define ETH_FCCNTR_PTMR_SHIFT (16) /* Bits 16-31: Pause timer */
+#define ETH_FCCNTR_PTMR_MASK (0xffff << ETH_FCCNTR_PTMR_SHIFT)
+
+/* Flow control status register (FCSTAT) */
+
+#define ETH_FCSTAT_MCOUNT_SHIFT (0) /* Bits 0-15: Current mirror count */
+#define ETH_FCSTAT_MCOUNT_MASK (0xffff << ETH_FCSTAT_MCOUNT_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Rx filter registers */
+/* Receive filter control register (RXFLCTRL) */
+
+#define ETH_RXFLCTRL_UCASTEN (1 << 0) /* Bit 0: Accept all unicast frames */
+#define ETH_RXFLCTRL_BCASTEN (1 << 1) /* Bit 1: Accept all broadcast frames */
+#define ETH_RXFLCTRL_MCASTEN (1 << 2) /* Bit 2: Accept all multicast frames */
+#define ETH_RXFLCTRL_UCASTHASHEN (1 << 3) /* Bit 3: Accept hashed unicast */
+#define ETH_RXFLCTRL_MCASTHASHEN (1 << 4) /* Bit 4: Accect hashed multicast */
+#define ETH_RXFLCTRL_PERFEN (1 << 5) /* Bit 5: Accept perfect dest match */
+ /* Bits 6-11: Reserved */
+#define ETH_RXFLCTRL_MPKTEN (1 << 12) /* Bit 12: Magic pkt filter WoL int */
+#define ETH_RXFLCTRL_RXFILEN (1 << 13) /* Bit 13: Perfect match WoL interrupt */
+ /* Bits 14-31: Reserved */
+/* Receive filter WoL status register (RXFLWOLST) AND
+ * Receive filter WoL clear register (RXFLWOLCLR)
+ */
+
+#define ETH_RXFLWOL_UCAST (1 << 0) /* Bit 0: Unicast frame WoL */
+#define ETH_RXFLWOL_BCAST (1 << 1) /* Bit 1: Broadcast frame WoL */
+#define ETH_RXFLWOL_MCAST (1 << 2) /* Bit 2: Multicast frame WoL */
+#define ETH_RXFLWOL_UCASTHASH (1 << 3) /* Bit 3: Unicast hash filter WoL */
+#define ETH_RXFLWOL_MCASTHASH (1 << 4) /* Bit 4: Multiicast hash filter WoL */
+#define ETH_RXFLWOL_PERF (1 << 5) /* Bit 5: Perfect addr match WoL */
+ /* Bit 6: Reserved */
+#define ETH_RXFLWOL_RXFIL (1 << 7) /* Bit 7: Receive filter WoL */
+#define ETH_RXFLWOL_MPKT (1 << 8) /* Bit 8: Magic pkt filter WoL */
+ /* Bits 9-31: Reserved */
+/* Hash filter table LSBs register (HASHFLL) AND Hash filter table MSBs register
+* (HASHFLH) Are registers containing a 32-bit value with no bitfield.
+ */
+
+/* Module control registers */
+/* Interrupt status register (INTST), Interrupt enable register (INTEN), Interrupt
+ * clear register (INTCLR), and Interrupt set register (INTSET) common bit field
+ * definition:
+ */
+
+#define ETH_INT_RXOVR (1 << 0) /* Bit 0: RX overrun interrupt */
+#define ETH_INT_RXERR (1 << 1) /* Bit 1: RX error interrupt */
+#define ETH_INT_RXFIN (1 << 2) /* Bit 2: RX finished interrupt */
+#define ETH_INT_RXDONE (1 << 3) /* Bit 3: RX done interrupt */
+#define ETH_INT_TXUNR (1 << 4) /* Bit 4: TX underrun interrupt */
+#define ETH_INT_TXERR (1 << 5) /* Bit 5: TX error interrupt */
+#define ETH_INT_TXFIN (1 << 6) /* Bit 6: TX finished interrupt */
+#define ETH_INT_TXDONE (1 << 7) /* Bit 7: TX done interrupt */
+ /* Bits 8-11: Reserved */
+#define ETH_INT_SOFT (1 << 12) /* Bit 12: Soft interrupt */
+#define ETH_INT_WKUP (1 << 13) /* Bit 13: Wakeup interrupt */
+ /* Bits 14-31: Reserved */
+/* Power-down register */
+ /* Bits 0-30: Reserved */
+#define ETH_PWRDOWN_MACAHB (1 << 31) /* Power down MAC/AHB */
+
+/* Descriptors Offsets **************************************************************/
+
+/* Tx descriptor offsets */
+
+#define LPC17_TXDESC_PACKET 0x00 /* Base address of the Tx data buffer */
+#define LPC17_TXDESC_CONTROL 0x04 /* Control Information */
+#define LPC17_TXDESC_SIZE 0x08 /* Size in bytes of one Tx descriptor */
+
+/* Tx status offsets */
+
+#define LPC17_TXSTAT_INFO 0x00 /* Transmit status return flags */
+#define LPC17_TXSTAT_SIZE 0x04 /* Size in bytes of one Tx status */
+
+/* Rx descriptor offsets */
+
+#define LPC17_RXDESC_PACKET 0x00 /* Base address of the Rx data buffer */
+#define LPC17_RXDESC_CONTROL 0x04 /* Control Information */
+#define LPC17_RXDESC_SIZE 0x08 /* Size in bytes of one Rx descriptor */
+
+/* Rx status offsets */
+
+#define LPC17_RXSTAT_INFO 0x00 /* Receive status return flags */
+#define LPC17_RXSTAT_HASHCRC 0x04 /* Dest and source hash CRC */
+#define LPC17_RXSTAT_SIZE 0x08 /* Size in bytes of one Rx status */
+
+/* Descriptor Bit Definitions *******************************************************/
+
+/* Tx descriptor bit definitions */
+
+#define TXDESC_CONTROL_SIZE_SHIFT (0) /* Bits 0-10: Size of data buffer */
+#define TXDESC_CONTROL_SIZE_MASK (0x7ff << RXDESC_CONTROL_SIZE_SHIFT)
+
+#define TXDESC_CONTROL_OVERRIDE (1 << 26 /* Bit 26: Per-frame override */
+#define TXDESC_CONTROL_HUGE (1 << 27) /* Bit 27: Enable huge frame size */
+#define TXDESC_CONTROL_PAD (1 << 28) /* Bit 28: Pad short frames */
+#define TXDESC_CONTROL_CRC (1 << 29) /* Bit 29: Append CRC */
+#define TXDESC_CONTROL_LAST (1 << 30) /* Bit 30: Last descriptor of a fragment */
+#define TXDESC_CONTROL_INT (1 << 31) /* Bit 31: Generate TxDone interrupt */
+
+/* Tx status bit definitions */
+
+#define TXSTAT_INFO_COLCNT_SHIFT (21) /* Bits 21-24: Number of collisions */
+#define TXSTAT_INFO_COLCNT_MASK (15 << TXSTAT_INFO_COLCNT_SHIFT)
+#define TXSTAT_INFO_DEFER (1 << 25) /* Bit 25: Packet deffered */
+#define TXSTAT_INFO_EXCESSDEFER (1 << 26) /* Bit 26: Excessive packet defferals */
+#define TXSTAT_INFO_EXCESSCOL (1 << 27) /* Bit 27: Excessive packet collisions */
+#define TXSTAT_INFO_LATECOL (1 << 28) /* Bit 28: Out of window collision */
+#define TXSTAT_INFO_UNDERRUN (1 << 29) /* Bit 29: Tx underrun */
+#define TXSTAT_INFO_NODESC (1 << 30) /* Bit 29: No Tx descriptor available */
+#define TXSTAT_INFO_ERROR (1 << 31) /* Bit 31: OR of other error conditions */
+
+/* Rx descriptor bit definitions */
+
+#define RXDESC_CONTROL_SIZE_SHIFT (0) /* Bits 0-10: Size of data buffer */
+#define RXDESC_CONTROL_SIZE_MASK (0x7ff << RXDESC_CONTROL_SIZE_SHIFT)
+#define RXDESC_CONTROL_INT (1 << 31) /* Bit 31: Generate RxDone interrupt */
+
+/* Rx status bit definitions */
+
+#define RXSTAT_SAHASHCRC_SHIFT (0) /* Bits 0-8: Hash CRC calculated from the source address */
+#define RXSTAT_SAHASHCRC_MASK (0x1ff << RXSTAT_SAHASHCRC_SHIFT)
+#define RXSTAT_DAHASHCRC_SHIFT (16) /* Bits 16-24: Hash CRC calculated from the dest address */
+#define RXSTAT_DAHASHCRC_MASK (0x1ff << RXSTAT_DAHASHCRC_SHIFT)
+
+#define RXSTAT_INFO_RXSIZE_SHIFT (0) /* Bits 0-10: Size of actual data transferred */
+#define RXSTAT_INFO_RXSIZE_MASK (0x7ff << RXSTAT_INFO_RXSIZE_SHIFT)
+#define RXSTAT_INFO_CONTROL (1 << 18) /* Bit 18: This is a control frame */
+#define RXSTAT_INFO_VLAN (1 << 19) /* Bit 19: This is a VLAN frame */
+#define RXSTAT_INFO_FAILFILTER (1 << 20) /* Bit 20: Frame failed Rx filter */
+#define RXSTAT_INFO_MULTICAST (1 << 21) /* Bit 21: This is a multicast frame */
+#define RXSTAT_INFO_BROADCAST (1 << 22) /* Bit 22: This is a broadcast frame */
+#define RXSTAT_INFO_CRCERROR (1 << 23) /* Bit 23: Received frame had a CRC error */
+#define RXSTAT_INFO_SYMBOLERROR (1 << 24) /* Bit 24: PHY reported bit error */
+#define RXSTAT_INFO_LENGTHERROR (1 << 25) /* Bit 25: Invalid frame length */
+#define RXSTAT_INFO_RANGEERROR (1 << 26) /* Bit 26: Exceeds maximum packet size */
+#define RXSTAT_INFO_ALIGNERROR (1 << 27) /* Bit 27: Alignment error */
+#define RXSTAT_INFO_OVERRUN (1 << 28) /* Bit 28: Receive overrun error */
+#define RXSTAT_INFO_NODESC (1 << 29) /* Bit 29: No Rx descriptor available */
+#define RXSTAT_INFO_LASTFLAG (1 << 30) /* Bit 30: Last fragment of a frame */
+#define RXSTAT_INFO_ERROR (1 << 31) /* Bit 31: OR of other error conditions */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_ETHERNET_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpdma.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpdma.h
new file mode 100644
index 000000000..4a14c1853
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpdma.h
@@ -0,0 +1,417 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_gpdma.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC17_GPDMA_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_GPDMA_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+/* General registers (see also LPC17_SYSCON_DMAREQSEL_OFFSET in lpc17_syscon.h) */
+
+#define LPC17_DMA_INTST_OFFSET 0x0000 /* DMA Interrupt Status Register */
+#define LPC17_DMA_INTTCST_OFFSET 0x0004 /* DMA Interrupt Terminal Count Request Status Register */
+#define LPC17_DMA_INTTCCLR_OFFSET 0x0008 /* DMA Interrupt Terminal Count Request Clear Register */
+#define LPC17_DMA_INTERRST_OFFSET 0x000c /* DMA Interrupt Error Status Register */
+#define LPC17_DMA_INTERRCLR_OFFSET 0x0010 /* DMA Interrupt Error Clear Register */
+#define LPC17_DMA_RAWINTTCST_OFFSET 0x0014 /* DMA Raw Interrupt Terminal Count Status Register */
+#define LPC17_DMA_RAWINTERRST_OFFSET 0x0018 /* DMA Raw Error Interrupt Status Register */
+#define LPC17_DMA_ENBLDCHNS_OFFSET 0x001c /* DMA Enabled Channel Register */
+#define LPC17_DMA_SOFTBREQ_OFFSET 0x0020 /* DMA Software Burst Request Register */
+#define LPC17_DMA_SOFTSREQ_OFFSET 0x0024 /* DMA Software Single Request Register */
+#define LPC17_DMA_SOFTLBREQ_OFFSET 0x0028 /* DMA Software Last Burst Request Register */
+#define LPC17_DMA_SOFTLSREQ_OFFSET 0x002c /* DMA Software Last Single Request Register */
+#define LPC17_DMA_CONFIG_OFFSET 0x0030 /* DMA Configuration Register */
+#define LPC17_DMA_SYNC_OFFSET 0x0034 /* DMA Synchronization Register */
+
+/* Channel Registers */
+
+#define LPC17_DMA_CHAN_OFFSET(n) (0x0100 + ((n) << 5)) /* n=0,1,...7 */
+
+#define LPC17_DMACH_SRCADDR_OFFSET 0x0000 /* DMA Channel Source Address Register */
+#define LPC17_DMACH_DESTADDR_OFFSET 0x0004 /* DMA Channel Destination Address Register */
+#define LPC17_DMACH_LLI_OFFSET 0x0008 /* DMA Channel Linked List Item Register */
+#define LPC17_DMACH_CONTROL_OFFSET 0x000c /* DMA Channel Control Register */
+#define LPC17_DMACH_CONFIG_OFFSET 0x0010 /* DMA Channel Configuration Register */
+
+#define LPC17_DMACH0_SRCADDR_OFFSET (0x100+LPC17_DMACH_SRCADDR_OFFSET)
+#define LPC17_DMACH0_DESTADDR_OFFSET (0x100+LPC17_DMACH_DESTADDR_OFFSET)
+#define LPC17_DMACH0_LLI_OFFSET (0x100+LPC17_DMACH_LLI_OFFSET)
+#define LPC17_DMACH0_CONTROL_OFFSET (0x100+LPC17_DMACH_CONTROL_OFFSET)
+#define LPC17_DMACH0_CONFIG_OFFSET (0x100+LPC17_DMACH_CONFIG_OFFSET)
+
+#define LPC17_DMACH1_SRCADDR_OFFSET (0x120+LPC17_DMACH_SRCADDR_OFFSET)
+#define LPC17_DMACH1_DESTADDR_OFFSET (0x120+LPC17_DMACH_DESTADDR_OFFSET)
+#define LPC17_DMACH1_LLI_OFFSET (0x120+LPC17_DMACH_LLI_OFFSET)
+#define LPC17_DMACH1_CONTROL_OFFSET (0x120+LPC17_DMACH_CONTROL_OFFSET)
+#define LPC17_DMACH1_CONFIG_OFFSET (0x120+LPC17_DMACH_CONFIG_OFFSET)
+
+#define LPC17_DMACH2_SRCADDR_OFFSET (0x140+LPC17_DMACH_SRCADDR_OFFSET)
+#define LPC17_DMACH2_DESTADDR_OFFSET (0x140+LPC17_DMACH_DESTADDR_OFFSET)
+#define LPC17_DMACH2_LLI_OFFSET (0x140+LPC17_DMACH_LLI_OFFSET)
+#define LPC17_DMACH2_CONTROL_OFFSET (0x140+LPC17_DMACH_CONTROL_OFFSET)
+#define LPC17_DMACH2_CONFIG_OFFSET (0x140+LPC17_DMACH_CONFIG_OFFSET)
+
+#define LPC17_DMACH3_SRCADDR_OFFSET (0x160+LPC17_DMACH_SRCADDR_OFFSET)
+#define LPC17_DMACH3_DESTADDR_OFFSET (0x160+LPC17_DMACH_DESTADDR_OFFSET)
+#define LPC17_DMACH3_LLI_OFFSET (0x160+LPC17_DMACH_LLI_OFFSET)
+#define LPC17_DMACH3_CONTROL_OFFSET (0x160+LPC17_DMACH_CONTROL_OFFSET)
+#define LPC17_DMACH3_CONFIG_OFFSET (0x160+LPC17_DMACH_CONFIG_OFFSET)
+
+#define LPC17_DMACH4_SRCADDR_OFFSET (0x180+LPC17_DMACH_SRCADDR_OFFSET)
+#define LPC17_DMACH4_DESTADDR_OFFSET (0x180+LPC17_DMACH_DESTADDR_OFFSET)
+#define LPC17_DMACH4_LLI_OFFSET (0x180+LPC17_DMACH_LLI_OFFSET)
+#define LPC17_DMACH4_CONTROL_OFFSET (0x180+LPC17_DMACH_CONTROL_OFFSET)
+#define LPC17_DMACH4_CONFIG_OFFSET (0x180+LPC17_DMACH_CONFIG_OFFSET)
+
+#define LPC17_DMACH5_SRCADDR_OFFSET (0x1a0+LPC17_DMACH_SRCADDR_OFFSET)
+#define LPC17_DMACH5_DESTADDR_OFFSET (0x1a0+LPC17_DMACH_DESTADDR_OFFSET)
+#define LPC17_DMACH5_LLI_OFFSET (0x1a0+LPC17_DMACH_LLI_OFFSET)
+#define LPC17_DMACH5_CONTROL_OFFSET (0x1a0+LPC17_DMACH_CONTROL_OFFSET)
+#define LPC17_DMACH5_CONFIG_OFFSET (0x1a0+LPC17_DMACH_CONFIG_OFFSET)
+
+#define LPC17_DMACH6_SRCADDR_OFFSET (0x1c0+LPC17_DMACH_SRCADDR_OFFSET)
+#define LPC17_DMACH6_DESTADDR_OFFSET (0x1c0+LPC17_DMACH_DESTADDR_OFFSET)
+#define LPC17_DMACH6_LLI_OFFSET (0x1c0+LPC17_DMACH_LLI_OFFSET)
+#define LPC17_DMACH6_CONTROL_OFFSET (0x1c0+LPC17_DMACH_CONTROL_OFFSET)
+#define LPC17_DMACH6_CONFIG_OFFSET (0x1c0+LPC17_DMACH_CONFIG_OFFSET)
+
+#define LPC17_DMACH7_SRCADDR_OFFSET (0x1e0+LPC17_DMACH_SRCADDR_OFFSET)
+#define LPC17_DMACH7_DESTADDR_OFFSET (0x1e0+LPC17_DMACH_DESTADDR_OFFSET)
+#define LPC17_DMACH7_LLI_OFFSET (0x1e0+LPC17_DMACH_LLI_OFFSET)
+#define LPC17_DMACH7_CONTROL_OFFSET (0x1e0+LPC17_DMACH_CONTROL_OFFSET)
+#define LPC17_DMACH7_CONFIG_OFFSET (0x1e0+LPC17_DMACH_CONFIG_OFFSET)
+
+/* Register addresses ***************************************************************/
+/* General registers (see also LPC17_SYSCON_DMAREQSEL in lpc17_syscon.h) */
+
+#define LPC17_DMA_INTST (LPC17_GPDMA_BASE+LPC17_DMA_INTST_OFFSET)
+#define LPC17_DMA_INTTCST (LPC17_GPDMA_BASE+LPC17_DMA_INTTCST_OFFSET)
+#define LPC17_DMA_INTTCCLR (LPC17_GPDMA_BASE+LPC17_DMA_INTTCCLR_OFFSET)
+#define LPC17_DMA_INTERRST (LPC17_GPDMA_BASE+LPC17_DMA_INTERRST_OFFSET)
+#define LPC17_DMA_INTERRCLR (LPC17_GPDMA_BASE+LPC17_DMA_INTERRCLR_OFFSET)
+#define LPC17_DMA_RAWINTTCST (LPC17_GPDMA_BASE+LPC17_DMA_RAWINTTCST_OFFSET)
+#define LPC17_DMA_RAWINTERRST (LPC17_GPDMA_BASE+LPC17_DMA_RAWINTERRST_OFFSET)
+#define LPC17_DMA_ENBLDCHNS (LPC17_GPDMA_BASE+LPC17_DMA_ENBLDCHNS_OFFSET)
+#define LPC17_DMA_SOFTBREQ (LPC17_GPDMA_BASE+LPC17_DMA_SOFTBREQ_OFFSET)
+#define LPC17_DMA_SOFTSREQ (LPC17_GPDMA_BASE+LPC17_DMA_SOFTSREQ_OFFSET)
+#define LPC17_DMA_SOFTLBREQ (LPC17_GPDMA_BASE+LPC17_DMA_SOFTLBREQ_OFFSET)
+#define LPC17_DMA_SOFTLSREQ (LPC17_GPDMA_BASE+LPC17_DMA_SOFTLSREQ_OFFSET)
+#define LPC17_DMA_CONFIG (LPC17_GPDMA_BASE+LPC17_DMA_CONFIG_OFFSET)
+#define LPC17_DMA_SYNC (LPC17_GPDMA_BASE+LPC17_DMA_SYNC_OFFSET)
+
+/* Channel Registers */
+
+#define LPC17_DMACH_BASE(n) (LPC17_GPDMA_BASE+LPC17_DMA_CHAN_OFFSET(n))
+
+#define LPC17_DMACH_SRCADDR(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_SRCADDR_OFFSET)
+#define LPC17_DMACH_DESTADDR(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_DESTADDR_OFFSET)
+#define LPC17_DMACH_LLI(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_LLI_OFFSET)
+#define LPC17_DMACH_CONTROL(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_CONTROL_OFFSET)
+#define LPC17_DMACH_CONFIG(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_CONFIG_OFFSET)
+
+#define LPC17_DMACH0_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH0_SRCADDR_OFFSET)
+#define LPC17_DMACH0_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH0_DESTADDR_OFFSET)
+#define LPC17_DMACH0_LLI (LPC17_GPDMA_BASE+LPC17_DMACH0_LLI_OFFSET)
+#define LPC17_DMACH0_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH0_CONTROL_OFFSET)
+#define LPC17_DMACH0_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH0_CONFIG_OFFSET)
+
+#define LPC17_DMACH1_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH1_SRCADDR_OFFSET)
+#define LPC17_DMACH1_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH1_DESTADDR_OFFSET)
+#define LPC17_DMACH1_LLI (LPC17_GPDMA_BASE+LPC17_DMACH1_LLI_OFFSET)
+#define LPC17_DMACH1_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH1_CONTROL_OFFSET)
+#define LPC17_DMACH1_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH1_CONFIG_OFFSET)
+
+#define LPC17_DMACH2_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH2_SRCADDR_OFFSET)
+#define LPC17_DMACH2_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH2_DESTADDR_OFFSET)
+#define LPC17_DMACH2_LLI (LPC17_GPDMA_BASE+LPC17_DMACH2_LLI_OFFSET)
+#define LPC17_DMACH2_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH2_CONTROL_OFFSET)
+#define LPC17_DMACH2_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH2_CONFIG_OFFSET)
+
+#define LPC17_DMACH3_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH3_SRCADDR_OFFSET)
+#define LPC17_DMACH3_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH3_DESTADDR_OFFSET)
+#define LPC17_DMACH3_LLI (LPC17_GPDMA_BASE+LPC17_DMACH3_LLI_OFFSET)
+#define LPC17_DMACH3_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH3_CONTROL_OFFSET)
+#define LPC17_DMACH3_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH3_CONFIG_OFFSET)
+
+#define LPC17_DMACH4_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH4_SRCADDR_OFFSET)
+#define LPC17_DMACH4_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH4_DESTADDR_OFFSET)
+#define LPC17_DMACH4_LLI (LPC17_GPDMA_BASE+LPC17_DMACH4_LLI_OFFSET)
+#define LPC17_DMACH4_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH4_CONTROL_OFFSET)
+#define LPC17_DMACH4_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH4_CONFIG_OFFSET)
+
+#define LPC17_DMACH5_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH5_SRCADDR_OFFSET)
+#define LPC17_DMACH5_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH5_DESTADDR_OFFSET)
+#define LPC17_DMACH5_LLI (LPC17_GPDMA_BASE+LPC17_DMACH5_LLI_OFFSET)
+#define LPC17_DMACH5_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH5_CONTROL_OFFSET)
+#define LPC17_DMACH5_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH5_CONFIG_OFFSET)
+
+#define LPC17_DMACH6_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH6_SRCADDR_OFFSET)
+#define LPC17_DMACH6_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH6_DESTADDR_OFFSET)
+#define LPC17_DMACH6_LLI (LPC17_GPDMA_BASE+LPC17_DMACH6_LLI_OFFSET)
+#define LPC17_DMACH6_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH6_CONTROL_OFFSET)
+#define LPC17_DMACH6_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH6_CONFIG_OFFSET)
+
+#define LPC17_DMACH7_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH7_SRCADDR_OFFSET)
+#define LPC17_DMACH7_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH7_DESTADDR_OFFSET)
+#define LPC17_DMACH7_LLI (LPC17_GPDMA_BASE+LPC17_DMACH7_LLI_OFFSET)
+#define LPC17_DMACH7_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH7_CONTROL_OFFSET)
+#define LPC17_DMACH7_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH7_CONFIG_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* DMA request connections */
+
+#define DMA_REQ_SSP0TX (0)
+#define DMA_REQ_SSP0RX (1)
+#define DMA_REQ_SSP1TX (2)
+#define DMA_REQ_SSP1RX (3)
+#define DMA_REQ_ADC (4)
+#define DMA_REQ_I2SCH0 (5)
+#define DMA_REQ_I2SCH1 (6)
+#define DMA_REQ_DAC (7)
+
+#define DMA_REQ_UART0TX (8)
+#define DMA_REQ_UART0RX (9)
+#define DMA_REQ_UART1TX (10)
+#define DMA_REQ_UART1RX (11)
+#define DMA_REQ_UART2TX (12)
+#define DMA_REQ_UART2RX (13)
+#define DMA_REQ_UART3TX (14)
+#define DMA_REQ_UART3RX (15)
+
+#define DMA_REQ_MAT0p0 (8)
+#define DMA_REQ_MAT0p1 (9)
+#define DMA_REQ_MAT1p0 (10)
+#define DMA_REQ_MAT1p1 (11)
+#define DMA_REQ_MAT2p0 (12)
+#define DMA_REQ_MAT2p1 (13)
+#define DMA_REQ_MAT3p0 (14)
+#define DMA_REQ_MAT3p1 (15)
+
+/* General registers (see also LPC17_SYSCON_DMAREQSEL in lpc17_syscon.h) */
+/* Fach of the following registers, bits 0-7 controls DMA channels 9-7,
+ * respectively. Bits 8-31 are reserved.
+ *
+ * DMA Interrupt Status Register
+ * DMA Interrupt Terminal Count Request Status Register
+ * DMA Interrupt Terminal Count Request Clear Register
+ * DMA Interrupt Error Status Register
+ * DMA Interrupt Error Clear Register
+ * DMA Raw Interrupt Terminal Count Status Register
+ * DMA Raw Error Interrupt Status Register
+ * DMA Enabled Channel Register
+ */
+
+#define DMACH(n) (1 << (n)) /* n=0,1,...7 */
+
+/* For each of the following registers, bits 0-15 represent a set of encoded
+ * DMA sources. Bits 16-31 are reserved in each case.
+ *
+ * DMA Software Burst Request Register
+ * DMA Software Single Request Register
+ * DMA Software Last Burst Request Register
+ * DMA Software Last Single Request Register
+ * DMA Synchronization Register
+ */
+
+#define DMA_REQ_SSP0TX_BIT (1 << DMA_REQ_SSP0TX)
+#define DMA_REQ_SSP0RX_BIT (1 << DMA_REQ_SSP0RX)
+#define DMA_REQ_SSP1TX_BIT (1 << DMA_REQ_SSP1TX)
+#define DMA_REQ_SSP1RX_BIT (1 << DMA_REQ_SSP0RX)
+#define DMA_REQ_ADC_BIT (1 << DMA_REQ_ADC)
+#define DMA_REQ_I2SCH0_BIT (1 << DMA_REQ_I2SCH0)
+#define DMA_REQ_I2SCH1_BIT (1 << DMA_REQ_I2SCH1)
+#define DMA_REQ_DAC_BIT (1 << DMA_REQ_DAC)
+
+#define DMA_REQ_UART0TX_BIT (1 << DMA_REQ_UART0TX)
+#define DMA_REQ_UART0RX_BIT (1 << DMA_REQ_UART0RX)
+#define DMA_REQ_UART1TX_BIT (1 << DMA_REQ_UART1TX)
+#define DMA_REQ_UART1RX_BIT (1 << DMA_REQ_UART1RX)
+#define DMA_REQ_UART2TX_BIT (1 << DMA_REQ_UART2TX)
+#define DMA_REQ_UART2RX_BIT (1 << DMA_REQ_UART2RX)
+#define DMA_REQ_UART3TX_BIT (1 << DMA_REQ_UART3TX)
+#define DMA_REQ_UART3RX_BIT (1 << DMA_REQ_UART3RX)
+
+#define DMA_REQ_MAT0p0_BIT (1 << DMA_REQ_MAT0p0)
+#define DMA_REQ_MAT0p1_BIT (1 << DMA_REQ_MAT0p1)
+#define DMA_REQ_MAT1p0_BIT (1 << DMA_REQ_MAT1p0)
+#define DMA_REQ_MAT1p1_BIT (1 << DMA_REQ_MAT1p1)
+#define DMA_REQ_MAT2p0_BIT (1 << DMA_REQ_MAT2p0)
+#define DMA_REQ_MAT2p1_BIT (1 << DMA_REQ_MAT2p1)
+#define DMA_REQ_MAT3p0_BIT (1 << DMA_REQ_MAT3p0)
+#define DMA_REQ_MAT3p1_BIT (1 << DMA_REQ_MAT3p1)
+
+/* DMA Configuration Register */
+
+#define DMA_CONFIG_E (1 << 0) /* Bit 0: DMA Controller enable */
+#define DMA_CONFIG_M (1 << 1) /* Bit 1: AHB Master endianness configuration */
+ /* Bits 2-31: Reserved */
+/* Channel Registers */
+
+/* DMA Channel Source Address Register (Bits 0-31: Source Address) */
+/* DMA Channel Destination Address Register Bits 0-31: Destination Address) */
+/* DMA Channel Linked List Item Register (Bits 0-31: Address of next link list
+ * item. Bits 0-1 must be zero.
+ */
+
+/* DMA Channel Control Register */
+
+#define DMACH_CONTROL_XFRSIZE_SHIFT (0) /* Bits 0-11: Transfer size */
+#define DMACH_CONTROL_XFRSIZE_MASK (0x0fff << DMACH_CONTROL_XFRSIZE_SHIFT)
+#define DMACH_CONTROL_SBSIZE_SHIFT (12) /* Bits 12-14: Source burst size */
+#define DMACH_CONTROL_SBSIZE_MASK (7 << DMACH_CONTROL_SBSIZE_SHIFT)
+# define DMACH_CONTROL_SBSIZE_1 (0 << DMACH_CONTROL_SBSIZE_SHIFT)
+# define DMACH_CONTROL_SBSIZE_4 (1 << DMACH_CONTROL_SBSIZE_SHIFT)
+# define DMACH_CONTROL_SBSIZE_8 (2 << DMACH_CONTROL_SBSIZE_SHIFT)
+# define DMACH_CONTROL_SBSIZE_16 (3 << DMACH_CONTROL_SBSIZE_SHIFT)
+# define DMACH_CONTROL_SBSIZE_32 (4 << DMACH_CONTROL_SBSIZE_SHIFT)
+# define DMACH_CONTROL_SBSIZE_64 (5 << DMACH_CONTROL_SBSIZE_SHIFT)
+# define DMACH_CONTROL_SBSIZE_128 (6 << DMACH_CONTROL_SBSIZE_SHIFT)
+# define DMACH_CONTROL_SBSIZE_256 (7 << DMACH_CONTROL_SBSIZE_SHIFT)
+#define DMACH_CONTROL_DBSIZE_SHIFT (15) /* Bits 15-17: Destination burst size */
+#define DMACH_CONTROL_DBSIZE_MASK (7 << DMACH_CONTROL_DBSIZE_SHIFT)
+# define DMACH_CONTROL_DBSIZE_1 (0 << DMACH_CONTROL_DBSIZE_SHIFT)
+# define DMACH_CONTROL_DBSIZE_4 (1 << DMACH_CONTROL_DBSIZE_SHIFT)
+# define DMACH_CONTROL_DBSIZE_8 (2 << DMACH_CONTROL_DBSIZE_SHIFT)
+# define DMACH_CONTROL_DBSIZE_16 (3 << DMACH_CONTROL_DBSIZE_SHIFT)
+# define DMACH_CONTROL_DBSIZE_32 (4 << DMACH_CONTROL_DBSIZE_SHIFT)
+# define DMACH_CONTROL_DBSIZE_64 (5 << DMACH_CONTROL_DBSIZE_SHIFT)
+# define DMACH_CONTROL_DBSIZE_128 (6 << DMACH_CONTROL_DBSIZE_SHIFT)
+# define DMACH_CONTROL_DBSIZE_256 (7 << DMACH_CONTROL_DBSIZE_SHIFT)
+#define DMACH_CONTROL_SWIDTH_SHIFT (18) /* Bits 18-20: Source transfer width */
+#define DMACH_CONTROL_SWIDTH_MASK (7 << DMACH_CONTROL_SWIDTH_SHIFT)
+#define DMACH_CONTROL_DWIDTH_SHIFT (21) /* Bits 21-23: Destination transfer width */
+#define DMACH_CONTROL_DWIDTH_MASK (7 << DMACH_CONTROL_DWIDTH_SHIFT)
+#define DMACH_CONTROL_SI (1 << 26) /* Bit 26: Source increment */
+#define DMACH_CONTROL_DI (1 << 27) /* Bit 27: Destination increment */
+#define DMACH_CONTROL_PROT1 (1 << 28) /* Bit 28: User/priviledged mode */
+#define DMACH_CONTROL_PROT2 (1 << 29) /* Bit 29: Bufferable */
+#define DMACH_CONTROL_PROT3 (1 << 30) /* Bit 30: Cacheable */
+#define DMACH_CONTROL_I (1 << 31) /* Bit 31: Terminal count interrupt enable */
+
+/* DMA Channel Configuration Register */
+
+
+#define DMACH_CONFIG_E (1 << 0) /* Bit 0: Channel enable */
+#define DMACH_CONFIG_SRCPER_SHIFT (1) /* Bits 1-5: Source peripheral */
+#define DMACH_CONFIG_SRCPER_MASK (31 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_SSP0TX (DMA_REQ_SSP0TX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_SSP0RX (DMA_REQ_SSP0RX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_SSP1TX (DMA_REQ_SSP1TX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_SSP1RX (DMA_REQ_SSP0RX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_ADC (DMA_REQ_ADC << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_I2SCH0 (DMA_REQ_I2SCH0 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_I2SCH1 (DMA_REQ_I2SCH1 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_DAC (DMA_REQ_DAC << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_UART0TX (DMA_REQ_UART0TX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_UART0RX (DMA_REQ_UART0RX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_UART1TX (DMA_REQ_UART1TX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_UART1RX (DMA_REQ_UART1RX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_UART2TX (DMA_REQ_UART2TX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_UART2RX (DMA_REQ_UART2RX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_UART3TX (DMA_REQ_UART3TX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_UART3RX (DMA_REQ_UART3RX << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_MAT0p0 (DMA_REQ_MAT0p0 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_MAT0p1 (DMA_REQ_MAT0p1 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_MAT1p0 (DMA_REQ_MAT1p0 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_MAT1p1 (DMA_REQ_MAT1p1 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_MAT2p0 (DMA_REQ_MAT2p0 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_MAT2p1 (DMA_REQ_MAT2p1 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_MAT3p0 (DMA_REQ_MAT3p0 << DMACH_CONFIG_SRCPER_SHIFT)
+# define DMACH_CONFIG_SRCPER_MAT3p1 (DMA_REQ_MAT3p1 << DMACH_CONFIG_SRCPER_SHIFT)
+#define DMACH_CONFIG_DSTPER_SHIFT (6) /* Bits 6-10: Source peripheral */
+#define DMACH_CONFIG_DSTPER_MASK (31 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_SSP0TX (DMA_REQ_SSP0TX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_SSP0RX (DMA_REQ_SSP0RX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_SSP1TX (DMA_REQ_SSP1TX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_SSP1RX (DMA_REQ_SSP0RX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_ADC (DMA_REQ_ADC << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_I2SCH0 (DMA_REQ_I2SCH0 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_I2SCH1 (DMA_REQ_I2SCH1 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_DAC (DMA_REQ_DAC << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_UART0TX (DMA_REQ_UART0TX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_UART0RX (DMA_REQ_UART0RX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_UART1TX (DMA_REQ_UART1TX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_UART1RX (DMA_REQ_UART1RX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_UART2TX (DMA_REQ_UART2TX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_UART2RX (DMA_REQ_UART2RX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_UART3TX (DMA_REQ_UART3TX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_UART3RX (DMA_REQ_UART3RX << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_MAT0p0 (DMA_REQ_MAT0p0 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_MAT0p1 (DMA_REQ_MAT0p1 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_MAT1p0 (DMA_REQ_MAT1p0 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_MAT1p1 (DMA_REQ_MAT1p1 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_MAT2p0 (DMA_REQ_MAT2p0 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_MAT2p1 (DMA_REQ_MAT2p1 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_MAT3p0 (DMA_REQ_MAT3p0 << DMACH_CONFIG_DSTPER_SHIFT)
+# define DMACH_CONFIG_DSTPER_MAT3p1 (DMA_REQ_MAT3p1 << DMACH_CONFIG_DSTPER_SHIFT)
+#define DMACH_CONFIG_XFRTYPE_SHIFT (11) /* Bits 11-13: Type of transfer */
+#define DMACH_CONFIG_XFRTYPE_MASK (7 << DMACH_CONFIG_XFRTYPE_SHIFT)
+# define DMACH_CONFIG_XFRTYPE_M2M (0 << DMACH_CONFIG_XFRTYPE_SHIFT) /* Memory to memory DMA */
+# define DMACH_CONFIG_XFRTYPE_M2P (1 << DMACH_CONFIG_XFRTYPE_SHIFT) /* Memory to peripheral DMA */
+# define DMACH_CONFIG_XFRTYPE_P2M (2 << DMACH_CONFIG_XFRTYPE_SHIFT) /* Peripheral to memory DMA */
+# define DMACH_CONFIG_XFRTYPE_P2P (3 << DMACH_CONFIG_XFRTYPE_SHIFT) /* Peripheral to peripheral DMA */
+#define DMACH_CONFIG_IE (1 << 14) /* Bit 14: Interrupt error mask */
+#define DMACH_CONFIG_ ITC (1 << 15) /* Bit 15: Terminal count interrupt mask */
+#define DMACH_CONFIG_L (1 << 16) /* Bit 16: Lock */
+#define DMACH_CONFIG_A (1 << 17) /* Bit 17: Active */
+#define DMACH_CONFIG_H (1 << 18) /* Bit 18: Halt */
+ /* Bits 19-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_GPDMA_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpio.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpio.h
new file mode 100644
index 000000000..20b4ae380
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpio.h
@@ -0,0 +1,293 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_gpio.h
+ *
+ * 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
+ * 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_LPC17XX_LPC17_CHIP_GPIO_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_CHIP_GPIO_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+/* GPIO block register offsets ******************************************************/
+
+#define LPC17_FIO0_OFFSET 0x0000
+#define LPC17_FIO1_OFFSET 0x0020
+#define LPC17_FIO2_OFFSET 0x0040
+#define LPC17_FIO3_OFFSET 0x0060
+#define LPC17_FIO4_OFFSET 0x0080
+
+#define LPC17_FIO_DIR_OFFSET 0x0000 /* Fast GPIO Port Direction control */
+#define LPC17_FIO_MASK_OFFSET 0x0010 /* Fast Mask register for ports */
+#define LPC17_FIO_PIN_OFFSET 0x0014 /* Fast Port Pin value registers */
+#define LPC17_FIO_SET_OFFSET 0x0018 /* Fast Port Output Set registers */
+#define LPC17_FIO_CLR_OFFSET 0x001c /* Fast Port Output Clear register */
+
+/* GPIO interrupt block register offsets ********************************************/
+
+#define LPC17_GPIOINT_OFFSET(n) (0x10*(n) + 0x80)
+#define LPC17_GPIOINT0_OFFSET 0x0080
+#define LPC17_GPIOINT2_OFFSET 0x00a0
+
+#define LPC17_GPIOINT_IOINTSTATUS_OFFSET 0x0000 /* GPIO overall Interrupt Status */
+#define LPC17_GPIOINT_INTSTATR_OFFSET 0x0004 /* GPIO Interrupt Status Rising edge */
+#define LPC17_GPIOINT_INTSTATF_OFFSET 0x0008 /* GPIO Interrupt Status Falling edge */
+#define LPC17_GPIOINT_INTCLR_OFFSET 0x000c /* GPIO Interrupt Clear */
+#define LPC17_GPIOINT_INTENR_OFFSET 0x0010 /* GPIO Interrupt Enable Rising edge */
+#define LPC17_GPIOINT_INTENF_OFFSET 0x0014 /* GPIO Interrupt Enable Falling edge */
+
+/* Register addresses ***************************************************************/
+/* GPIO block register addresses ****************************************************/
+
+#define LPC17_FIO_BASE(n) (LPC17_GPIO_BASE+LPC17_GPIOINT_OFFSET(n))
+#define LPC17_FIO0_BASE (LPC17_GPIO_BASE+LPC17_FIO0_OFFSET)
+#define LPC17_FIO1_BASE (LPC17_GPIO_BASE+LPC17_FIO1_OFFSET)
+#define LPC17_FIO2_BASE (LPC17_GPIO_BASE+LPC17_FIO2_OFFSET)
+#define LPC17_FIO3_BASE (LPC17_GPIO_BASE+LPC17_FIO3_OFFSET)
+#define LPC17_FIO4_BASE (LPC17_GPIO_BASE+LPC17_FIO4_OFFSET)
+
+#define LPC17_FIO_DIR(n) (LPC17_FIO_BASE(n)+LPC17_FIO_DIR_OFFSET)
+#define LPC17_FIO_MASK(n) (LPC17_FIO_BASE(n)+LPC17_FIO_MASK_OFFSET)
+#define LPC17_FIO_PIN(n) (LPC17_FIO_BASE(n)+LPC17_FIO_PIN_OFFSET)
+#define LPC17_FIO_SET(n) (LPC17_FIO_BASE(n)+LPC17_FIO_SET_OFFSET)
+#define LPC17_FIO_CLR(n) (LPC17_FIO_BASE(n)+LPC17_FIO_CLR_OFFSET)
+
+#define LPC17_FIO0_DIR (LPC17_FIO0_BASE+LPC17_FIO_DIR_OFFSET)
+#define LPC17_FIO0_MASK (LPC17_FIO0_BASE+LPC17_FIO_MASK_OFFSET)
+#define LPC17_FIO0_PIN (LPC17_FIO0_BASE+LPC17_FIO_PIN_OFFSET)
+#define LPC17_FIO0_SET (LPC17_FIO0_BASE+LPC17_FIO_SET_OFFSET)
+#define LPC17_FIO0_CLR (LPC17_FIO0_BASE+LPC17_FIO_CLR_OFFSET)
+
+#define LPC17_FIO1_DIR (LPC17_FIO1_BASE+LPC17_FIO_DIR_OFFSET)
+#define LPC17_FIO1_MASK (LPC17_FIO1_BASE+LPC17_FIO_MASK_OFFSET)
+#define LPC17_FIO1_PIN (LPC17_FIO1_BASE+LPC17_FIO_PIN_OFFSET)
+#define LPC17_FIO1_SET (LPC17_FIO1_BASE+LPC17_FIO_SET_OFFSET)
+#define LPC17_FIO1_CLR (LPC17_FIO1_BASE+LPC17_FIO_CLR_OFFSET)
+
+#define LPC17_FIO2_DIR (LPC17_FIO2_BASE+LPC17_FIO_DIR_OFFSET)
+#define LPC17_FIO2_MASK (LPC17_FIO2_BASE+LPC17_FIO_MASK_OFFSET)
+#define LPC17_FIO2_PIN (LPC17_FIO2_BASE+LPC17_FIO_PIN_OFFSET)
+#define LPC17_FIO2_SET (LPC17_FIO2_BASE+LPC17_FIO_SET_OFFSET)
+#define LPC17_FIO2_CLR (LPC17_FIO2_BASE+LPC17_FIO_CLR_OFFSET)
+
+#define LPC17_FIO3_DIR (LPC17_FIO3_BASE+LPC17_FIO_DIR_OFFSET)
+#define LPC17_FIO3_MASK (LPC17_FIO3_BASE+LPC17_FIO_MASK_OFFSET)
+#define LPC17_FIO3_PIN (LPC17_FIO3_BASE+LPC17_FIO_PIN_OFFSET)
+#define LPC17_FIO3_SET (LPC17_FIO3_BASE+LPC17_FIO_SET_OFFSET)
+#define LPC17_FIO3_CLR (LPC17_FIO3_BASE+LPC17_FIO_CLR_OFFSET)
+
+#define LPC17_FIO4_DIR (LPC17_FIO4_BASE+LPC17_FIO_DIR_OFFSET)
+#define LPC17_FIO4_MASK (LPC17_FIO4_BASE+LPC17_FIO_MASK_OFFSET)
+#define LPC17_FIO4_PIN (LPC17_FIO4_BASE+LPC17_FIO_PIN_OFFSET)
+#define LPC17_FIO4_SET (LPC17_FIO4_BASE+LPC17_FIO_SET_OFFSET)
+#define LPC17_FIO4_CLR (LPC17_FIO4_BASE+LPC17_FIO_CLR_OFFSET)
+
+/* GPIO interrupt block register addresses ******************************************/
+
+#define LPC17_GPIOINTn_BASE(n) (LPC17_GPIOINT_BASE+LPC17_GPIOINT_OFFSET(n))
+#define LPC17_GPIOINT0_BASE (LPC17_GPIOINT_BASE+LPC17_GPIOINT0_OFFSET)
+#define LPC17_GPIOINT2_BASE (LPC17_GPIOINT_BASE+LPC17_GPIOINT2_OFFSET)
+
+#define LPC17_GPIOINT_IOINTSTATUS (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_IOINTSTATUS_OFFSET)
+
+#define LPC17_GPIOINT_INTSTATR(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTSTATR_OFFSET)
+#define LPC17_GPIOINT_INTSTATF(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTSTATF_OFFSET)
+#define LPC17_GPIOINT_INTCLR(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTCLR_OFFSET)
+#define LPC17_GPIOINT_INTENR(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTENR_OFFSET)
+#define LPC17_GPIOINT_INTENF(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTENF_OFFSET)
+
+/* Pins P0.0-31 (P0.12-14 nad P0.31 are reserved) */
+
+#define LPC17_GPIOINT0_INTSTATR (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTSTATR_OFFSET)
+#define LPC17_GPIOINT0_INTSTATF (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTSTATF_OFFSET)
+#define LPC17_GPIOINT0_INTCLR (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTCLR_OFFSET)
+#define LPC17_GPIOINT0_INTENR (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTENR_OFFSET)
+#define LPC17_GPIOINT0_INTENF (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTENF_OFFSET)
+
+/* Pins P2.0-13 (P0.14-31 are reserved) */
+
+#define LPC17_GPIOINT2_INTSTATR (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTSTATR_OFFSET)
+#define LPC17_GPIOINT2_INTSTATF (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTSTATF_OFFSET)
+#define LPC17_GPIOINT2_INTCLR (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTCLR_OFFSET)
+#define LPC17_GPIOINT2_INTENR (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTENR_OFFSET)
+#define LPC17_GPIOINT2_INTENF (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTENF_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* GPIO block register bit definitions **********************************************/
+
+/* Fast GPIO Port Direction control registers (FIODIR) */
+/* Fast Mask register for ports (FIOMASK) */
+/* Fast Port Pin value registers using FIOMASK (FIOPIN) */
+/* Fast Port Output Set registers using FIOMASK (FIOSET) */
+/* Fast Port Output Clear register using FIOMASK (FIOCLR) */
+
+#define FIO(n) (1 << (n)) /* n=0,1,..31 */
+
+/* GPIO interrupt block register bit definitions ************************************/
+
+/* GPIO overall Interrupt Status (IOINTSTATUS) */
+#define GPIOINT_IOINTSTATUS_P0INT (1 << 0) /* Bit 0: Port 0 GPIO interrupt pending */
+ /* Bit 1: Reserved */
+#define GPIOINT_IOINTSTATUS_P2INT (1 << 2) /* Bit 2: Port 2 GPIO interrupt pending */
+ /* Bits 3-31: Reserved */
+
+/* GPIO Interrupt Status for Rising edge (INTSTATR)
+ * GPIO Interrupt Status for Falling edge (INTSTATF)
+ * GPIO Interrupt Clear (INTCLR)
+ * GPIO Interrupt Enable for Rising edge (INTENR)
+ * GPIO Interrupt Enable for Falling edge (INTENF)
+ */
+
+#define GPIOINT(n) (1 << (n)) /* n=0,1,..31 */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc17_gpioirqinitialize
+ *
+ * Description:
+ * Initialize logic to support a second level of interrupt decoding for GPIO pins.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_GPIO_IRQ
+void lpc17_gpioirqinitialize(void);
+#else
+# define lpc17_gpioirqinitialize()
+#endif
+
+/************************************************************************************
+ * Name: lpc17_configgpio
+ *
+ * Description:
+ * Configure a GPIO pin based on bit-encoded description of the pin.
+ *
+ ************************************************************************************/
+
+int lpc17_configgpio(uint16_t cfgset);
+
+/************************************************************************************
+ * Name: lpc17_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ************************************************************************************/
+
+void lpc17_gpiowrite(uint16_t pinset, bool value);
+
+/************************************************************************************
+ * Name: lpc17_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ************************************************************************************/
+
+bool lpc17_gpioread(uint16_t pinset);
+
+/************************************************************************************
+ * Name: lpc17_gpioirqenable
+ *
+ * Description:
+ * Enable the interrupt for specified GPIO IRQ
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_GPIO_IRQ
+void lpc17_gpioirqenable(int irq);
+#else
+# define lpc17_gpioirqenable(irq)
+#endif
+
+/************************************************************************************
+ * Name: lpc17_gpioirqdisable
+ *
+ * Description:
+ * Disable the interrupt for specified GPIO IRQ
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_GPIO_IRQ
+void lpc17_gpioirqdisable(int irq);
+#else
+# define lpc17_gpioirqdisable(irq)
+#endif
+
+/************************************************************************************
+ * Function: lpc17_dumpgpio
+ *
+ * Description:
+ * Dump all GPIO registers associated with the base address of the provided pinset.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_DEBUG_GPIO
+int lpc17_dumpgpio(uint16_t pinset, const char *msg);
+#else
+# define lpc17_dumpgpio(p,m)
+#endif
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_CHIP_GPIO_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_i2c.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_i2c.h
new file mode 100644
index 000000000..96b6f19b1
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_i2c.h
@@ -0,0 +1,208 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_i2c.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC17_I2C_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_I2C_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_I2C_CONSET_OFFSET 0x0000 /* I2C Control Set Register */
+#define LPC17_I2C_STAT_OFFSET 0x0004 /* I2C Status Register */
+#define LPC17_I2C_DAT_OFFSET 0x0008 /* I2C Data Register */
+#define LPC17_I2C_ADR0_OFFSET 0x000c /* I2C Slave Address Register 0 */
+#define LPC17_I2C_SCLH_OFFSET 0x0010 /* SCH Duty Cycle Register High Half Word */
+#define LPC17_I2C_SCLL_OFFSET 0x0014 /* SCL Duty Cycle Register Low Half Word */
+#define LPC17_I2C_CONCLR_OFFSET 0x0018 /* I2C Control Clear Register */
+#define LPC17_I2C_MMCTRL_OFFSET 0x001c /* Monitor mode control register */
+#define LPC17_I2C_ADR1_OFFSET 0x0020 /* I2C Slave Address Register 1 */
+#define LPC17_I2C_ADR2_OFFSET 0x0024 /* I2C Slave Address Register 2 */
+#define LPC17_I2C_ADR3_OFFSET 0x0028 /* I2C Slave Address Register 3 */
+#define LPC17_I2C_BUFR_OFFSET 0x002c /* Data buffer register */
+#define LPC17_I2C_MASK0_OFFSET 0x0030 /* I2C Slave address mask register 0 */
+#define LPC17_I2C_MASK1_OFFSET 0x0034 /* I2C Slave address mask register 1 */
+#define LPC17_I2C_MASK2_OFFSET 0x0038 /* I2C Slave address mask register 2 */
+#define LPC17_I2C_MASK3_OFFSET 0x003c /* I2C Slave address mask register */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_I2C0_CONSET (LPC17_I2C0_BASE+LPC17_I2C_CONSET_OFFSET)
+#define LPC17_I2C0_STAT (LPC17_I2C0_BASE+LPC17_I2C_STAT_OFFSET)
+#define LPC17_I2C0_DAT (LPC17_I2C0_BASE+LPC17_I2C_DAT_OFFSET)
+#define LPC17_I2C0_ADR0 (LPC17_I2C0_BASE+LPC17_I2C_ADR0_OFFSET)
+#define LPC17_I2C0_SCLH (LPC17_I2C0_BASE+LPC17_I2C_SCLH_OFFSET)
+#define LPC17_I2C0_SCLL (LPC17_I2C0_BASE+LPC17_I2C_SCLL_OFFSET)
+#define LPC17_I2C0_CONCLR (LPC17_I2C0_BASE+LPC17_I2C_CONCLR_OFFSET)
+#define LPC17_I2C0_MMCTRL (LPC17_I2C0_BASE+LPC17_I2C_MMCTRL_OFFSET)
+#define LPC17_I2C0_ADR1 (LPC17_I2C0_BASE+LPC17_I2C_ADR1_OFFSET)
+#define LPC17_I2C0_ADR2 (LPC17_I2C0_BASE+LPC17_I2C_ADR2_OFFSET)
+#define LPC17_I2C0_ADR3 (LPC17_I2C0_BASE+LPC17_I2C_ADR3_OFFSET)
+#define LPC17_I2C0_BUFR (LPC17_I2C0_BASE+LPC17_I2C_BUFR_OFFSET)
+#define LPC17_I2C0_MASK0 (LPC17_I2C0_BASE+LPC17_I2C_MASK0_OFFSET)
+#define LPC17_I2C0_MASK1 (LPC17_I2C0_BASE+LPC17_I2C_MASK1_OFFSET)
+#define LPC17_I2C0_MASK2 (LPC17_I2C0_BASE+LPC17_I2C_MASK2_OFFSET)
+#define LPC17_I2C0_MASK3 (LPC17_I2C0_BASE+LPC17_I2C_MASK3_OFFSET)
+
+#define LPC17_I2C1_CONSET (LPC17_I2C1_BASE+LPC17_I2C_CONSET_OFFSET)
+#define LPC17_I2C1_STAT (LPC17_I2C1_BASE+LPC17_I2C_STAT_OFFSET)
+#define LPC17_I2C1_DAT (LPC17_I2C1_BASE+LPC17_I2C_DAT_OFFSET)
+#define LPC17_I2C1_ADR0 (LPC17_I2C1_BASE+LPC17_I2C_ADR0_OFFSET)
+#define LPC17_I2C1_SCLH (LPC17_I2C1_BASE+LPC17_I2C_SCLH_OFFSET)
+#define LPC17_I2C1_SCLL (LPC17_I2C1_BASE+LPC17_I2C_SCLL_OFFSET)
+#define LPC17_I2C1_CONCLR (LPC17_I2C1_BASE+LPC17_I2C_CONCLR_OFFSET)
+#define LPC17_I2C1_MMCTRL (LPC17_I2C1_BASE+LPC17_I2C_MMCTRL_OFFSET)
+#define LPC17_I2C1_ADR1 (LPC17_I2C1_BASE+LPC17_I2C_ADR1_OFFSET)
+#define LPC17_I2C1_ADR2 (LPC17_I2C1_BASE+LPC17_I2C_ADR2_OFFSET)
+#define LPC17_I2C1_ADR3 (LPC17_I2C1_BASE+LPC17_I2C_ADR3_OFFSET)
+#define LPC17_I2C1_BUFR (LPC17_I2C1_BASE+LPC17_I2C_BUFR_OFFSET)
+#define LPC17_I2C1_MASK0 (LPC17_I2C1_BASE+LPC17_I2C_MASK0_OFFSET)
+#define LPC17_I2C1_MASK1 (LPC17_I2C1_BASE+LPC17_I2C_MASK1_OFFSET)
+#define LPC17_I2C1_MASK2 (LPC17_I2C1_BASE+LPC17_I2C_MASK2_OFFSET)
+#define LPC17_I2C1_MASK3 (LPC17_I2C1_BASE+LPC17_I2C_MASK3_OFFSET)
+
+#define LPC17_I2C2_CONSET (LPC17_I2C2_BASE+LPC17_I2C_CONSET_OFFSET)
+#define LPC17_I2C2_STAT (LPC17_I2C2_BASE+LPC17_I2C_STAT_OFFSET)
+#define LPC17_I2C2_DAT (LPC17_I2C2_BASE+LPC17_I2C_DAT_OFFSET)
+#define LPC17_I2C2_ADR0 (LPC17_I2C2_BASE+LPC17_I2C_ADR0_OFFSET)
+#define LPC17_I2C2_SCLH (LPC17_I2C2_BASE+LPC17_I2C_SCLH_OFFSET)
+#define LPC17_I2C2_SCLL (LPC17_I2C2_BASE+LPC17_I2C_SCLL_OFFSET)
+#define LPC17_I2C2_CONCLR (LPC17_I2C2_BASE+LPC17_I2C_CONCLR_OFFSET)
+#define LPC17_I2C2_MMCTRL (LPC17_I2C2_BASE+LPC17_I2C_MMCTRL_OFFSET)
+#define LPC17_I2C2_ADR1 (LPC17_I2C2_BASE+LPC17_I2C_ADR1_OFFSET)
+#define LPC17_I2C2_ADR2 (LPC17_I2C2_BASE+LPC17_I2C_ADR2_OFFSET)
+#define LPC17_I2C2_ADR3 (LPC17_I2C2_BASE+LPC17_I2C_ADR3_OFFSET)
+#define LPC17_I2C2_BUFR (LPC17_I2C2_BASE+LPC17_I2C_BUFR_OFFSET)
+#define LPC17_I2C2_MASK0 (LPC17_I2C2_BASE+LPC17_I2C_MASK0_OFFSET)
+#define LPC17_I2C2_MASK1 (LPC17_I2C2_BASE+LPC17_I2C_MASK1_OFFSET)
+#define LPC17_I2C2_MASK2 (LPC17_I2C2_BASE+LPC17_I2C_MASK2_OFFSET)
+#define LPC17_I2C2_MASK3 (LPC17_I2C2_BASE+LPC17_I2C_MASK3_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* I2C Control Set Register */
+ /* Bits 0-1: Reserved */
+#define I2C_CONSET_AA (1 << 2) /* Bit 2: Assert acknowledge flag */
+#define I2C_CONSET_SI (1 << 3) /* Bit 3: I2C interrupt flag */
+#define I2C_CONSET_STO (1 << 4) /* Bit 4: STOP flag */
+#define I2C_CONSET_STA (1 << 5) /* Bit 5: START flag */
+#define I2C_CONSET_I2EN (1 << 6) /* Bit 6: I2C interface enable */
+ /* Bits 7-31: Reserved */
+/* I2C Control Clear Register */
+ /* Bits 0-1: Reserved */
+#define I2C_CONCLR_AAC (1 << 2) /* Bit 2: Assert acknowledge Clear bit */
+#define I2C_CONCLR_SIC (1 << 3) /* Bit 3: I2C interrupt Clear bit */
+ /* Bit 4: Reserved */
+#define I2C_CONCLR_STAC (1 << 5) /* Bit 5: START flag Clear bit */
+#define I2C_CONCLRT_I2ENC (1 << 6) /* Bit 6: I2C interface Disable bit */
+ /* Bits 7-31: Reserved */
+/* I2C Status Register
+ *
+ * See tables 399-402 in the "LPC17xx User Manual" (UM10360), Rev. 01, 4 January
+ * 2010, NXP for definitions of status codes.
+ */
+
+#define I2C_STAT_MASK (0xff) /* Bits 0-7: I2C interface status
+ * Bits 0-1 always zero */
+ /* Bits 8-31: Reserved */
+/* I2C Data Register */
+
+#define I2C_DAT_MASK (0xff) /* Bits 0-7: I2C data */
+ /* Bits 8-31: Reserved */
+/* Monitor mode control register */
+
+#define I2C_MMCTRL_MMENA (1 << 0) /* Bit 0: Monitor mode enable */
+#define I2C_MMCTRL_ENASCL (1 << 1) /* Bit 1: SCL output enable */
+#define I2C_MMCTRL_MATCHALL (1 << 2) /* Bit 2: Select interrupt register match */
+ /* Bits 3-31: Reserved */
+/* Data buffer register */
+
+#define I2C_BUFR_MASK (0xff) /* Bits 0-7: 8 MSBs of the I2DAT shift register */
+ /* Bits 8-31: Reserved */
+/* I2C Slave address registers:
+ *
+ * I2C Slave Address Register 0
+ * I2C Slave Address Register 1
+ * I2C Slave Address Register 2
+ * I2C Slave Address Register 3
+ */
+
+#define I2C_ADR_GC (1 << 0) /* Bit 0: GC General Call enable bit */
+#define I2C_ADR_ADDR_SHIFT (1) /* Bits 1-7: I2C slave address */
+#define I2C_ADR_ADDR_MASK (0x7f << I2C_ADR_ADDR_SHIFT)
+ /* Bits 8-31: Reserved */
+/* I2C Slave address mask registers:
+ *
+ * I2C Slave address mask register 0
+ * I2C Slave address mask register 1
+ * I2C Slave address mask register 2
+ * I2C Slave address mask register 3
+ */
+ /* Bit 0: Reserved */
+#define I2C_MASK_SHIFT (1) /* Bits 1-7: I2C mask bits */
+#define I2C_MASK_MASK (0x7f << I2C_ADR_ADDR_SHIFT)
+ /* Bits 8-31: Reserved */
+/* SCH Duty Cycle Register High Half Word */
+
+#define I2C_SCLH_MASK (0xffff) /* Bit 0-15: Count for SCL HIGH time period selection */
+ /* Bits 16-31: Reserved */
+/* SCL Duty Cycle Register Low Half Word */
+
+#define I2C_SCLL_MASK (0xffff) /* Bit 0-15: Count for SCL LOW time period selection */
+ /* Bits 16-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_I2C_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_i2s.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_i2s.h
new file mode 100644
index 000000000..ab9a30425
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_i2s.h
@@ -0,0 +1,62 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_i2s
+ *
+ * Copyright (C) 2010, 2012-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_LPC17XX_CHIP_LPC17_I2S_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_I2S_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/lpc17_i2s.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_I2S_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_mcpwm.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_mcpwm.h
index 370aa42de..6ec4a6b20 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_mcpwm.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_mcpwm.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_mcpwm.h
+ * arch/arm/src/lpc17xx/chip/lpc17_mcpwm.h
*
- * 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
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LPC17XX_LPC17_MCPWM_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_MCPWM_H
+#ifndef __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_MCPWM_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_MCPWM_H
/************************************************************************************
* Included Files
@@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
@@ -277,4 +277,4 @@
* Public Functions
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_MCPWM_H */
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_MCPWM_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_memorymap.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_memorymap.h
new file mode 100644
index 000000000..d3bdf79ab
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_memorymap.h
@@ -0,0 +1,71 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lp17_memorymap.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC17_MEMORYMAP_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_MEMORYMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <arch/lpc17xx/chip.h>
+
+#if defined(LPC176x)
+# include "chip/lpc176x_memorymap.h"
+#elif defined(LPC178x)
+# include "chip/lpc178x_memorymap.h"
+#else
+# error "Unrecognized LPC17xx family"
+#endif
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+ #endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_MEMORYMAP_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h
new file mode 100644
index 000000000..fb4a487c2
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconfig.h
@@ -0,0 +1,71 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lp17_pinconfig.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC17_PINCONFIG_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_PINCONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <arch/lpc17xx/chip.h>
+
+#if defined(LPC176x)
+# include "chip/lpc176x_pinconfig.h"
+#elif defined(LPC178x)
+# include "chip/lpc178x_pinconfig.h"
+#else
+# error "Unrecognized LPC17xx family"
+#endif
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+ #endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_PINCONFIG_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_pinconn.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconn.h
index c0e0ec916..d8b8e0d37 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_pinconn.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pinconn.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_pinconn.h
+ * arch/arm/src/lpc17xx/chip/lpc17_pinconn.h
*
- * 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
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LPC17XX_LPC17_PINCONN_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_PINCONN_H
+#ifndef __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_PINCONN_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_PINCONN_H
/************************************************************************************
* Included Files
@@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
@@ -632,4 +632,4 @@
* Public Functions
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_PINCONN_H */
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_PINCONN_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pwm.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pwm.h
new file mode 100644
index 000000000..8a7931104
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pwm.h
@@ -0,0 +1,63 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_pwm.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC17_PWM_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_PWM_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/lpc17_pwm.h"
+#include "chip/lpc17_mcpwm.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_PWM_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_qei.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_qei.h
new file mode 100644
index 000000000..4179ac965
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_qei.h
@@ -0,0 +1,190 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_qei.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC17_QEI_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_QEI_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+/* Control registers */
+
+#define LPC17_QEI_CON_OFFSET 0x0000 /* Control register */
+#define LPC17_QEI_STAT_OFFSET 0x0004 /* Encoder status register */
+#define LPC17_QEI_CONF_OFFSET 0x0008 /* Configuration register */
+
+/* Position, index, and timer registers */
+
+#define LPC17_QEI_POS_OFFSET 0x000c /* Position register */
+#define LPC17_QEI_MAXPOS_OFFSET 0x0010 /* Maximum position register */
+#define LPC17_QEI_CMPOS0_OFFSET 0x0014 /* Position compare register */
+#define LPC17_QEI_CMPOS1_OFFSET 0x0018 /* Position compare register */
+#define LPC17_QEI_CMPOS2_OFFSET 0x001c /* Position compare register */
+#define LPC17_QEI_INXCNT_OFFSET 0x0020 /* Index count register */
+#define LPC17_QEI_INXCMP_OFFSET 0x0024 /* Index compare register */
+#define LPC17_QEI_LOAD_OFFSET 0x0028 /* Velocity timer reload register */
+#define LPC17_QEI_TIME_OFFSET 0x002c /* Velocity timer register */
+#define LPC17_QEI_VEL_OFFSET 0x0030 /* Velocity counter register */
+#define LPC17_QEI_CAP_OFFSET 0x0034 /* Velocity capture register */
+#define LPC17_QEI_VELCOMP_OFFSET 0x0038 /* Velocity compare register */
+#define LPC17_QEI_FILTER_OFFSET 0x003c /* Digital filter register */
+
+/* Interrupt registers */
+
+#define LPC17_QEI_IEC_OFFSET 0x0fd8 /* Interrupt enable clear register */
+#define LPC17_QEI_IES_OFFSET 0x0fdc /* Interrupt enable set register */
+#define LPC17_QEI_INTSTAT_OFFSET 0x0fe0 /* Interrupt status register */
+#define LPC17_QEI_IE_OFFSET 0x0fe4 /* Interrupt enable register */
+#define LPC17_QEI_CLR_OFFSET 0x0fe8 /* Interrupt status clear register */
+#define LPC17_QEI_SET_OFFSET 0x0fec /* Interrupt status set register */
+
+/* Register addresses ***************************************************************/
+/* Control registers */
+
+#define LPC17_QEI_CON (LPC17_QEI_BASE+LPC17_QEI_CON_OFFSET)
+#define LPC17_QEI_STAT (LPC17_QEI_BASE+LPC17_QEI_STAT_OFFSET)
+#define LPC17_QEI_CONF (LPC17_QEI_BASE+LPC17_QEI_CONF_OFFSET)
+
+/* Position, index, and timer registers */
+
+#define LPC17_QEI_POS (LPC17_QEI_BASE+LPC17_QEI_POS_OFFSET)
+#define LPC17_QEI_MAXPOS (LPC17_QEI_BASE+LPC17_QEI_MAXPOS_OFFSET)
+#define LPC17_QEI_CMPOS0 (LPC17_QEI_BASE+LPC17_QEI_CMPOS0_OFFSET)
+#define LPC17_QEI_CMPOS1 (LPC17_QEI_BASE+LPC17_QEI_CMPOS1_OFFSET)
+#define LPC17_QEI_CMPOS2 (LPC17_QEI_BASE+LPC17_QEI_CMPOS2_OFFSET)
+#define LPC17_QEI_INXCNT (LPC17_QEI_BASE+LPC17_QEI_INXCNT_OFFSET)
+#define LPC17_QEI_INXCMP (LPC17_QEI_BASE+LPC17_QEI_INXCMP_OFFSET)
+#define LPC17_QEI_LOAD (LPC17_QEI_BASE+LPC17_QEI_LOAD_OFFSET)
+#define LPC17_QEI_TIME (LPC17_QEI_BASE+LPC17_QEI_TIME_OFFSET)
+#define LPC17_QEI_VEL (LPC17_QEI_BASE+LPC17_QEI_VEL_OFFSET)
+#define LPC17_QEI_CAP (LPC17_QEI_BASE+LPC17_QEI_CAP_OFFSET)
+#define LPC17_QEI_VELCOMP (LPC17_QEI_BASE+LPC17_QEI_VELCOMP_OFFSET)
+#define LPC17_QEI_FILTER (LPC17_QEI_BASE+LPC17_QEI_FILTER_OFFSET)
+
+/* Interrupt registers */
+
+#define LPC17_QEI_IEC (LPC17_QEI_BASE+LPC17_QEI_IEC_OFFSET)
+#define LPC17_QEI_IES (LPC17_QEI_BASE+LPC17_QEI_IES_OFFSET)
+#define LPC17_QEI_INTSTAT (LPC17_QEI_BASE+LPC17_QEI_INTSTAT_OFFSET)
+#define LPC17_QEI_IE (LPC17_QEI_BASE+LPC17_QEI_IE_OFFSET)
+#define LPC17_QEI_CLR (LPC17_QEI_BASE+LPC17_QEI_CLR_OFFSET)
+#define LPC17_QEI_SET (LPC17_QEI_BASE+LPC17_QEI_SET_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* The following registers hold 32-bit integer values and have no bit fields defined
+ * in this section:
+ *
+ * Position register (POS)
+ * Maximum position register (MAXPOS)
+ * Position compare register 0 (CMPOS0)
+ * Position compare register 1 (CMPOS)
+ * Position compare register 2 (CMPOS2)
+ * Index count register (INXCNT)
+ * Index compare register (INXCMP)
+ * Velocity timer reload register (LOAD)
+ * Velocity timer register (TIME)
+ * Velocity counter register (VEL)
+ * Velocity capture register (CAP)
+ * Velocity compare register (VELCOMP)
+ * Digital filter register (FILTER)
+ */
+
+/* Control registers */
+/* Control register */
+
+#define QEI_CON_RESP (1 << 0) /* Bit 0: Reset position counter */
+#define QEI_CON_RESPI (1 << 1) /* Bit 1: Reset position counter on index */
+#define QEI_CON_RESV (1 << 2) /* Bit 2: Reset velocity */
+#define QEI_CON_RESI (1 << 3) /* Bit 3: Reset index counter */
+ /* Bits 4-31: reserved */
+/* Encoder status register */
+
+#define QEI_STAT_DIR (1 << 0) /* Bit 0: Direction bit */
+ /* Bits 1-31: reserved */
+/* Configuration register */
+
+#define QEI_CONF_DIRINV (1 << 0) /* Bit 0: Direction invert */
+#define QEI_CONF_SIGMODE (1 << 1) /* Bit 1: Signal Mode */
+#define QEI_CONF_CAPMODE (1 << 2) /* Bit 2: Capture Mode */
+#define QEI_CONF_INVINX (1 << 3) /* Bit 3: Invert Index */
+ /* Bits 4-31: reserved */
+/* Position, index, and timer registers (all 32-bit integer values with not bit fields */
+
+/* Interrupt registers */
+/* Interrupt enable clear register (IEC), Interrupt enable set register (IES),
+ * Interrupt status register (INTSTAT), Interrupt enable register (IE), Interrupt
+ * status clear register (CLR), and Interrupt status set register (SET) common
+ * bit definitions.
+ */
+
+#define QEI_INT_INX (1 << 0) /* Bit 0: Index pulse detected */
+#define QEI_INT_TIM (1 << 1) /* Bit 1: Velocity timer overflow occurred */
+#define QEI_INT_VELC (1 << 2) /* Bit 2: Captured velocity less than compare velocity */
+#define QEI_INT_DIR (1 << 3) /* Bit 3: Change of direction detected */
+#define QEI_INT_ERR (1 << 4) /* Bit 4: Encoder phase error detected */
+#define QEI_INT_ENCLK (1 << 5) /* Bit 5: Eencoder clock pulse detected */
+#define QEI_INT_POS0 (1 << 6) /* Bit 6: Position 0 compare equal to current position */
+#define QEI_INT_POS1 (1 << 7) /* Bit 7: Position 1 compare equal to current position */
+#define QEI_INT_POS2 (1 << 8) /* Bit 8: Position 2 compare equal to current position */
+#define QEI_INT_REV (1 << 9) /* Bit 9: Index compare value equal to current index count */
+#define QEI_INT_POS0REV (1 << 10) /* Bit 10: Combined position 0 and revolution count interrupt */
+#define QEI_INT_POS1REV (1 << 11) /* Bit 11: Position 1 and revolution count interrupt */
+#define QEI_INT_POS2REV (1 << 12) /* Bit 12: Position 2 and revolution count interrupt */
+ /* Bits 13-31: reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_QEI_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_rit.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_rit.h
new file mode 100644
index 000000000..00029f8fe
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_rit.h
@@ -0,0 +1,92 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_rit.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC17_RIT_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_RIT_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_RIT_COMPVAL_OFFSET 0x0000 /* Compare register */
+#define LPC17_RIT_MASK_OFFSET 0x0004 /* Mask register */
+#define LPC17_RIT_CTRL_OFFSET 0x0008 /* Control register */
+#define LPC17_RIT_COUNTER_OFFSET 0x000c /* 32-bit counter */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_RIT_COMPVAL (LPC17_RIT_BASE+LPC17_RIT_COMPVAL_OFFSET)
+#define LPC17_RIT_MASK (LPC17_RIT_BASE+LPC17_RIT_MASK_OFFSET)
+#define LPC17_RIT_CTRL (LPC17_RIT_BASE+LPC17_RIT_CTRL_OFFSET)
+#define LPC17_RIT_COUNTER (LPC17_RIT_BASE+LPC17_RIT_COUNTER_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* Compare register (Bits 0-31: value compared to the counter) */
+
+/* Mask register (Bits 0-31: 32-bit mask value) */
+
+/* Control register */
+
+#define RIT_CTRL_INT (1 << 0) /* Bit 0: Interrupt flag */
+#define RIT_CTRL_ENCLR (1 << 1) /* Bit 1: Timer enable clear */
+#define RIT_CTRL_ENBR (1 << 2) /* Bit 2: Timer enable for debug */
+#define RIT_CTRL_EN (1 << 3) /* Bit 3: Timer enable */
+ /* Bits 4-31: Reserved */
+/* 32-bit counter (Bits 0-31: 32-bit up counter) */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_RIT_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_rtc.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_rtc.h
new file mode 100644
index 000000000..ddc44d59f
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_rtc.h
@@ -0,0 +1,270 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_rtc.h
+ *
+ * Copyright (C) 2010, 2012-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_LPC17XX_CHIP_LPC17_RTC_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_RTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+/* Miscellaneous registers */
+
+#define LPC17_RTC_ILR_OFFSET 0x0000 /* Interrupt Location Register */
+#define LPC17_RTC_CCR_OFFSET 0x0008 /* Clock Control Register */
+#define LPC17_RTC_CIIR_OFFSET 0x000c /* Counter Increment Interrupt Register */
+#define LPC17_RTC_AMR_OFFSET 0x0010 /* Alarm Mask Register */
+#define LPC17_RTC_AUXEN_OFFSET 0x0058 /* RTC Auxiliary Enable register */
+#define LPC17_RTC_AUX_OFFSET 0x005c /* RTC Auxiliary control register */
+
+/* Consolidated time registers */
+
+#define LPC17_RTC_CTIME0_OFFSET 0x0014 /* Consolidated Time Register 0 */
+#define LPC17_RTC_CTIME1_OFFSET 0x0018 /* Consolidated Time Register 1 */
+#define LPC17_RTC_CTIME2_OFFSET 0x001c /* Consolidated Time Register 2 */
+
+/* Time counter registers */
+
+#define LPC17_RTC_SEC_OFFSET 0x0020 /* Seconds Counter */
+#define LPC17_RTC_MIN_OFFSET 0x0024 /* Minutes Register */
+#define LPC17_RTC_HOUR_OFFSET 0x0028 /* Hours Register */
+#define LPC17_RTC_DOM_OFFSET 0x002c /* Day of Month Register */
+#define LPC17_RTC_DOW_OFFSET 0x0030 /* Day of Week Register */
+#define LPC17_RTC_DOY_OFFSET 0x0034 /* Day of Year Register */
+#define LPC17_RTC_MONTH_OFFSET 0x0038 /* Months Register */
+#define LPC17_RTC_YEAR_OFFSET 0x003c /* Years Register */
+#define LPC17_RTC_CALIB_OFFSET 0x0040 /* Calibration Value Register */
+
+/* General purpose registers */
+
+#define LPC17_RTC_GPREG0_OFFSET 0x0044 /* General Purpose Register 0 */
+#define LPC17_RTC_GPREG1_OFFSET 0x0048 /* General Purpose Register 1 */
+#define LPC17_RTC_GPREG2_OFFSET 0x004c /* General Purpose Register 2 */
+#define LPC17_RTC_GPREG3_OFFSET 0x0050 /* General Purpose Register 3 */
+#define LPC17_RTC_GPREG4_OFFSET 0x0054 /* General Purpose Register 4 */
+
+/* Alarm register group */
+
+#define LPC17_RTC_ALSEC_OFFSET 0x0060 /* Alarm value for Seconds */
+#define LPC17_RTC_ALMIN_OFFSET 0x0064 /* Alarm value for Minutes */
+#define LPC17_RTC_ALHOUR_OFFSET 0x0068 /* Alarm value for Hours */
+#define LPC17_RTC_ALDOM_OFFSET 0x006c /* Alarm value for Day of Month */
+#define LPC17_RTC_ALDOW_OFFSET 0x0070 /* Alarm value for Day of Week */
+#define LPC17_RTC_ALDOY_OFFSET 0x0074 /* Alarm value for Day of Year */
+#define LPC17_RTC_ALMON_OFFSET 0x0078 /* Alarm value for Months */
+#define LPC17_RTC_ALYEAR_OFFSET 0x007c /* Alarm value for Year */
+
+/* Register addresses ***************************************************************/
+/* Miscellaneous registers */
+
+#define LPC17_RTC_ILR (LPC17_RTC_BASE+LPC17_RTC_ILR_OFFSET)
+#define LPC17_RTC_CCR (LPC17_RTC_BASE+LPC17_RTC_CCR_OFFSET)
+#define LPC17_RTC_CIIR (LPC17_RTC_BASE+LPC17_RTC_CIIR_OFFSET)
+#define LPC17_RTC_AMR (LPC17_RTC_BASE+LPC17_RTC_AMR_OFFSET)
+#define LPC17_RTC_AUXEN (LPC17_RTC_BASE+LPC17_RTC_AUXEN_OFFSET)
+#define LPC17_RTC_AUX (LPC17_RTC_BASE+LPC17_RTC_AUX_OFFSET)
+
+/* Consolidated time registers */
+
+#define LPC17_RTC_CTIME0 (LPC17_RTC_BASE+LPC17_RTC_CTIME0_OFFSET)
+#define LPC17_RTC_CTIME1 (LPC17_RTC_BASE+LPC17_RTC_CTIME1_OFFSET)
+#define LPC17_RTC_CTIME2 (LPC17_RTC_BASE+LPC17_RTC_CTIME2_OFFSET)
+
+/* Time counter registers */
+
+#define LPC17_RTC_SEC (LPC17_RTC_BASE+LPC17_RTC_SEC_OFFSET)
+#define LPC17_RTC_MIN (LPC17_RTC_BASE+LPC17_RTC_MIN_OFFSET)
+#define LPC17_RTC_HOUR (LPC17_RTC_BASE+LPC17_RTC_HOUR_OFFSET)
+#define LPC17_RTC_DOM (LPC17_RTC_BASE+LPC17_RTC_DOM_OFFSET)
+#define LPC17_RTC_DOW (LPC17_RTC_BASE+LPC17_RTC_DOW_OFFSET)
+#define LPC17_RTC_DOY (LPC17_RTC_BASE+LPC17_RTC_DOY_OFFSET)
+#define LPC17_RTC_MONTH (LPC17_RTC_BASE+LPC17_RTC_MONTH_OFFSET)
+#define LPC17_RTC_YEAR (LPC17_RTC_BASE+LPC17_RTC_YEAR_OFFSET)
+#define LPC17_RTC_CALIB (LPC17_RTC_BASE+LPC17_RTC_CALIB_OFFSET)
+
+/* General purpose registers */
+
+#define LPC17_RTC_GPREG0 (LPC17_RTC_BASE+LPC17_RTC_GPREG0_OFFSET)
+#define LPC17_RTC_GPREG1 (LPC17_RTC_BASE+LPC17_RTC_GPREG1_OFFSET)
+#define LPC17_RTC_GPREG2 (LPC17_RTC_BASE+LPC17_RTC_GPREG2_OFFSET)
+#define LPC17_RTC_GPREG3 (LPC17_RTC_BASE+LPC17_RTC_GPREG3_OFFSET)
+#define LPC17_RTC_GPREG4 (LPC17_RTC_BASE+LPC17_RTC_GPREG4_OFFSET)
+
+/* Alarm register group */
+
+#define LPC17_RTC_ALSEC (LPC17_RTC_BASE+LPC17_RTC_ALSEC_OFFSET)
+#define LPC17_RTC_ALMIN (LPC17_RTC_BASE+LPC17_RTC_ALMIN_OFFSET)
+#define LPC17_RTC_ALHOUR (LPC17_RTC_BASE+LPC17_RTC_ALHOUR_OFFSET)
+#define LPC17_RTC_ALDOM (LPC17_RTC_BASE+LPC17_RTC_ALDOM_OFFSET)
+#define LPC17_RTC_ALDOW (LPC17_RTC_BASE+LPC17_RTC_ALDOW_OFFSET)
+#define LPC17_RTC_ALDOY (LPC17_RTC_BASE+LPC17_RTC_ALDOY_OFFSET)
+#define LPC17_RTC_ALMON (LPC17_RTC_BASE+LPC17_RTC_ALMON_OFFSET)
+#define LPC17_RTC_ALYEAR (LPC17_RTC_BASE+LPC17_RTC_ALYEAR_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* The following registers hold 32-bit values and have no bit fields to be defined:
+ *
+ * General Purpose Register 0
+ * General Purpose Register 1
+ * General Purpose Register 2
+ * General Purpose Register 3
+ * General Purpose Register 4
+ */
+
+/* Miscellaneous registers */
+/* Interrupt Location Register */
+
+#define RTC_ILR_RTCCIF (1 << 0) /* Bit 0: Counter Increment Interrupt */
+#define RTC_ILR_RTCALF (1 << 1) /* Bit 1: Alarm interrupt */
+ /* Bits 2-31: Reserved */
+/* Clock Control Register */
+
+#define RTC_CCR_CLKEN (1 << 0) /* Bit 0: Clock Enable */
+#define RTC_CCR_CTCRST (1 << 1) /* Bit 1: CTC Reset */
+ /* Bits 2-3: Internal test mode controls */
+#define RTC_CCR_CCALEN (1 << 4) /* Bit 4: Calibration counter enable */
+ /* Bits 5-31: Reserved */
+/* Counter Increment Interrupt Register */
+
+#define RTC_CIIR_IMSEC (1 << 0) /* Bit 0: Second interrupt */
+#define RTC_CIIR_IMMIN (1 << 1) /* Bit 1: Minute interrupt */
+#define RTC_CIIR_IMHOUR (1 << 2) /* Bit 2: Hour interrupt */
+#define RTC_CIIR_IMDOM (1 << 3) /* Bit 3: Day of Month value interrupt */
+#define RTC_CIIR_IMDOW (1 << 4) /* Bit 4: Day of Week value interrupt */
+#define RTC_CIIR_IMDOY (1 << 5) /* Bit 5: Day of Year interrupt */
+#define RTC_CIIR_IMMON (1 << 6) /* Bit 6: Month interrupt */
+#define RTC_CIIR_IMYEAR (1 << 7) /* Bit 7: Yearinterrupt */
+ /* Bits 8-31: Reserved */
+/* Alarm Mask Register */
+
+#define RTC_AMR_SEC (1 << 0) /* Bit 0: Second not compared for alarm */
+#define RTC_AMR_MIN (1 << 1) /* Bit 1: Minutes not compared for alarm */
+#define RTC_AMR_HOUR (1 << 2) /* Bit 2: Hour not compared for alarm */
+#define RTC_AMR_DOM (1 << 3) /* Bit 3: Day of Monthnot compared for alarm */
+#define RTC_AMR_DOW (1 << 4) /* Bit 4: Day of Week not compared for alarm */
+#define RTC_AMR_DOY (1 << 5) /* Bit 5: Day of Year not compared for alarm */
+#define RTC_AMR_MON (1 << 6) /* Bit 6: Month not compared for alarm */
+#define RTC_AMR_YEAR (1 << 7) /* Bit 7: Year not compared for alarm */
+ /* Bits 8-31: Reserved */
+/* RTC Auxiliary Enable register */
+ /* Bits 0-3: Reserved */
+#define RTC_AUXEN_RTCOSCF (1 << 4) /* Bit 4: RTC Oscillator Fail detect flag */
+ /* Bits 5-31: Reserved */
+/* RTC Auxiliary control register */
+ /* Bits 0-3: Reserved */
+#define RTC_AUX_OSCFEN (1 << 4) /* Bit 4: Oscillator Fail Detect interrupt enable */
+ /* Bits 5-31: Reserved */
+/* Consolidated time registers */
+/* Consolidated Time Register 0 */
+
+#define RTC_CTIME0_SEC_SHIFT (0) /* Bits 0-5: Seconds */
+#define RTC_CTIME0_SEC_MASK (63 << RTC_CTIME0_SEC_SHIFT)
+ /* Bits 6-7: Reserved */
+#define RTC_CTIME0_MIN_SHIFT (8) /* Bits 8-13: Minutes */
+#define RTC_CTIME0_MIN_MASK (63 << RTC_CTIME0_MIN_SHIFT)
+ /* Bits 14-15: Reserved */
+#define RTC_CTIME0_HOURS_SHIFT (16) /* Bits 16-20: Hours */
+#define RTC_CTIME0_HOURS_MASK (31 << RTC_CTIME0_HOURS_SHIFT)
+ /* Bits 21-23: Reserved */
+#define RTC_CTIME0_DOW_SHIFT (24) /* Bits 24-26: Day of Week */
+#define RTC_CTIME0_DOW_MASK (7 << RTC_CTIME0_DOW_SHIFT)
+ /* Bits 27-31: Reserved */
+/* Consolidated Time Register 1 */
+
+#define RTC_CTIME1_DOM_SHIFT (0) /* Bits 0-4: Day of Month */
+#define RTC_CTIME1_DOM_MASK (31 << RTC_CTIME1_DOM_SHIFT)
+ /* Bits 5-7: Reserved */
+#define RTC_CTIME1_MON_SHIFT (8) /* Bits 8-11: Month */
+#define RTC_CTIME1_MON_MASK (15 << RTC_CTIME1_MON_SHIFT)
+ /* Bits 12-15: Reserved */
+#define RTC_CTIME1_YEAR_SHIFT (16) /* Bits 16-27: Year */
+#define RTC_CTIME1_YEAR_MASK (0x0fff << RTC_CTIME1_YEAR_SHIFT)
+ /* Bits 28-31: Reserved */
+/* Consolidated Time Register 2 */
+
+#define RTC_CTIME2_DOY_SHIFT (0) /* Bits 0-11: Day of Year */
+#define RTC_CTIME2_DOY_MASK (0x0fff << RTC_CTIME2_DOY_SHIFT)
+ /* Bits 12-31: Reserved */
+/* Time counter registers */
+
+#define RTC_SEC_MASK (0x003f)
+#define RTC_MIN_MASK (0x003f)
+#define RTC_HOUR_MASK (0x001f)
+#define RTC_DOM_MASK (0x001f)
+#define RTC_DOW_MASK (0x0007)
+#define RTC_DOY_MASK (0x01ff)
+#define RTC_MONTH_MASK (0x000f)
+#define RTC_YEAR_MASK (0x0fff)
+
+/* Calibration Value Register */
+
+#define RTC_CALIB_CALVAL_SHIFT (0) /* Bits 0-16: calibration counter counts to this value */
+#define RTC_CALIB_CALVAL_MASK (0xffff << RTC_CALIB_CALVAL_SHIFT)
+#define RTC_CALIB_CALDIR (1 << 17) /* Bit 17: Calibration direction */
+ /* Bits 18-31: Reserved */
+/* Alarm register group */
+
+#define RTC_ALSEC_MASK (0x003f)
+#define RTC_ALMIN_MASK (0x003f)
+#define RTC_ALHOUR_MASK (0x001f)
+#define RTC_ALDOM_MASK (0x001f)
+#define RTC_ALDOW_MASK (0x0007)
+#define RTC_ALDOY_MASK (0x01ff)
+#define RTC_ALMON_MASK (0x000f)
+#define RTC_ALYEAR_MASK (0x0fff)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_RTC_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_spi.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_spi.h
new file mode 100644
index 000000000..716e70cb5
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_spi.h
@@ -0,0 +1,141 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_spi.h
+ *
+ * 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
+ * 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_LPC17XX_CHIP_LPC17_SPI_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_SPI_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_SPI_CR_OFFSET 0x0000 /* Control Register */
+#define LPC17_SPI_SR_OFFSET 0x0004 /* SPI Status Register */
+#define LPC17_SPI_DR_OFFSET 0x0008 /* SPI Data Register */
+#define LPC17_SPI_CCR_OFFSET 0x000c /* SPI Clock Counter Register */
+#define LPC17_SPI_TCR_OFFSET 0x0010 /* SPI Test Control Register */
+#define LPC17_SPI_TSR_OFFSET 0x0014 /* SPI Test Status Register */
+#define LPC17_SPI_INT_OFFSET 0x001c /* SPI Interrupt Register */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_SPI_CR (LPC17_SPI_BASE+LPC17_SPI_CR_OFFSET)
+#define LPC17_SPI_SR (LPC17_SPI_BASE+LPC17_SPI_SR_OFFSET)
+#define LPC17_SPI_DR (LPC17_SPI_BASE+LPC17_SPI_DR_OFFSET)
+#define LPC17_SPI_CCR (LPC17_SPI_BASE+LPC17_SPI_CCR_OFFSET)
+#define LPC17_TCR_CCR (LPC17_SPI_BASE+LPC17_SPI_TCR_OFFSET)
+#define LPC17_TSR_CCR (LPC17_SPI_BASE+LPC17_SPI_TSR_OFFSET)
+#define LPC17_SPI_INT (LPC17_SPI_BASE+LPC17_SPI_INT_OFFSET)
+
+/* Register bit definitions *********************************************************/
+
+/* Control Register */
+ /* Bits 0-1: Reserved */
+#define SPI_CR_BITENABLE (1 << 2) /* Bit 2: Enable word size selected by BITS */
+#define SPI_CR_CPHA (1 << 3) /* Bit 3: Clock phase control */
+#define SPI_CR_CPOL (1 << 4) /* Bit 4: Clock polarity control */
+#define SPI_CR_MSTR (1 << 5) /* Bit 5: Master mode select */
+#define SPI_CR_LSBF (1 << 6) /* Bit 6: SPI data is transferred LSB first */
+#define SPI_CR_SPIE (1 << 7) /* Bit 7: Serial peripheral interrupt enable */
+#define SPI_CR_BITS_SHIFT (8) /* Bits 8-11: Number of bits per word (BITENABLE==1) */
+#define SPI_CR_BITS_MASK (15 << SPI_CR_BITS_SHIFT)
+# define SPI_CR_BITS_8BITS (8 << SPI_CR_BITS_SHIFT) /* 8 bits per transfer */
+# define SPI_CR_BITS_9BITS (9 << SPI_CR_BITS_SHIFT) /* 9 bits per transfer */
+# define SPI_CR_BITS_10BITS (10 << SPI_CR_BITS_SHIFT) /* 10 bits per transfer */
+# define SPI_CR_BITS_11BITS (11 << SPI_CR_BITS_SHIFT) /* 11 bits per transfer */
+# define SPI_CR_BITS_12BITS (12 << SPI_CR_BITS_SHIFT) /* 12 bits per transfer */
+# define SPI_CR_BITS_13BITS (13 << SPI_CR_BITS_SHIFT) /* 13 bits per transfer */
+# define SPI_CR_BITS_14BITS (14 << SPI_CR_BITS_SHIFT) /* 14 bits per transfer */
+# define SPI_CR_BITS_15BITS (15 << SPI_CR_BITS_SHIFT) /* 15 bits per transfer */
+# define SPI_CR_BITS_16BITS (0 << SPI_CR_BITS_SHIFT) /* 16 bits per transfer */
+ /* Bits 12-31: Reserved */
+/* SPI Status Register */
+ /* Bits 0-2: Reserved */
+#define SPI_SR_ABRT (1 << 3) /* Bit 3: Slave abort */
+#define SPI_SR_MODF (1 << 4) /* Bit 4: Mode fault */
+#define SPI_SR_ROVR (1 << 5) /* Bit 5: Read overrun */
+#define SPI_SR_WCOL (1 << 6) /* Bit 6: Write collision */
+#define SPI_SR_SPIF (1 << 7) /* Bit 7: SPI transfer complete */
+ /* Bits 8-31: Reserved */
+/* SPI Data Register */
+
+#define SPI_DR_MASK (0xff) /* Bits 0-15: SPI Bi-directional data port */
+#define SPI_DR_MASKWIDE (0xffff) /* Bits 0-15: If SPI_CR_BITENABLE != 0 */
+ /* Bits 8-31: Reserved */
+/* SPI Clock Counter Register */
+
+#define SPI_CCR_MASK (0xff) /* Bits 0-7: SPI Clock counter setting */
+ /* Bits 8-31: Reserved */
+/* SPI Test Control Register */
+ /* Bit 0: Reserved */
+#define SPI_TCR_TEST_SHIFT (1) /* Bits 1-7: SPI test mode */
+#define SPI_TCR_TEST_MASK (0x7f << SPI_TCR_TEST_SHIFT)
+ /* Bits 8-31: Reserved */
+/* SPI Test Status Register */
+ /* Bits 0-2: Reserved */
+#define SPI_TSR_ABRT (1 << 3) /* Bit 3: Slave abort */
+#define SPI_TSR_MODF (1 << 4) /* Bit 4: Mode fault */
+#define SPI_TSR_ROVR (1 << 5) /* Bit 5: Read overrun */
+#define SPI_TSR_WCOL (1 << 6) /* Bit 6: Write collision */
+#define SPI_TSR_SPIF (1 << 7) /* Bit 7: SPI transfer complete */
+ /* Bits 8-31: Reserved */
+/* SPI Interrupt Register */
+
+#define SPI_INT_SPIF (1 << 0) /* SPI interrupt */
+ /* Bits 1-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_SPI_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_ssp.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_ssp.h
new file mode 100644
index 000000000..e97a670a8
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_ssp.h
@@ -0,0 +1,174 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_ssp.h
+ *
+ * Copyright (C) 2010, 2012-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_LPC17XX_CHIP_LPC17_SSP_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_SSP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* 8 frame FIFOs for both transmit and receive */
+
+#define LPC17_SSP_FIFOSZ 8
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_SSP_CR0_OFFSET 0x0000 /* Control Register 0 */
+#define LPC17_SSP_CR1_OFFSET 0x0004 /* Control Register 1 */
+#define LPC17_SSP_DR_OFFSET 0x0008 /* Data Register */
+#define LPC17_SSP_SR_OFFSET 0x000c /* Status Register */
+#define LPC17_SSP_CPSR_OFFSET 0x0010 /* Clock Prescale Register */
+#define LPC17_SSP_IMSC_OFFSET 0x0014 /* Interrupt Mask Set and Clear Register */
+#define LPC17_SSP_RIS_OFFSET 0x0018 /* Raw Interrupt Status Register */
+#define LPC17_SSP_MIS_OFFSET 0x001c /* Masked Interrupt Status Register */
+#define LPC17_SSP_ICR_OFFSET 0x0020 /* Interrupt Clear Register */
+#define LPC17_SSP_DMACR_OFFSET 0x0024 /* DMA Control Register */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_SSP0_CR0 (LPC17_SSP0_BASE+LPC17_SSP_CR0_OFFSET)
+#define LPC17_SSP0_CR1 (LPC17_SSP0_BASE+LPC17_SSP_CR1_OFFSET)
+#define LPC17_SSP0_DR (LPC17_SSP0_BASE+LPC17_SSP_DR_OFFSET)
+#define LPC17_SSP0_SR (LPC17_SSP0_BASE+LPC17_SSP_SR_OFFSET)
+#define LPC17_SSP0_CPSR (LPC17_SSP0_BASE+LPC17_SSP_CPSR_OFFSET)
+#define LPC17_SSP0_IMSC (LPC17_SSP0_BASE+LPC17_SSP_IMSC_OFFSET)
+#define LPC17_SSP0_RIS (LPC17_SSP0_BASE+LPC17_SSP_RIS_OFFSET)
+#define LPC17_SSP0_MIS (LPC17_SSP0_BASE+LPC17_SSP_MIS_OFFSET)
+#define LPC17_SSP0_ICR (LPC17_SSP0_BASE+LPC17_SSP_ICR_OFFSET)
+#define LPC17_SSP0_DMACR (LPC17_SSP0_BASE+LPC17_SSP_DMACR_OFFSET)
+
+#define LPC17_SSP1_CR0 (LPC17_SSP1_BASE+LPC17_SSP_CR0_OFFSET)
+#define LPC17_SSP1_CR1 (LPC17_SSP1_BASE+LPC17_SSP_CR1_OFFSET)
+#define LPC17_SSP1_DR (LPC17_SSP1_BASE+LPC17_SSP_DR_OFFSET)
+#define LPC17_SSP1_SR (LPC17_SSP1_BASE+LPC17_SSP_SR_OFFSET)
+#define LPC17_SSP1_CPSR (LPC17_SSP1_BASE+LPC17_SSP_CPSR_OFFSET)
+#define LPC17_SSP1_IMSC (LPC17_SSP1_BASE+LPC17_SSP_IMSC_OFFSET)
+#define LPC17_SSP1_RIS (LPC17_SSP1_BASE+LPC17_SSP_RIS_OFFSET)
+#define LPC17_SSP1_MIS (LPC17_SSP1_BASE+LPC17_SSP_MIS_OFFSET)
+#define LPC17_SSP1_ICR (LPC17_SSP1_BASE+LPC17_SSP_ICR_OFFSET)
+#define LPC17_SSP1_DMACR (LPC17_SSP1_BASE+LPC17_SSP_DMACR_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* Control Register 0 */
+
+#define SSP_CR0_DSS_SHIFT (0) /* Bits 0-3: DSS Data Size Select */
+#define SSP_CR0_DSS_MASK (15 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_4BIT (3 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_5BIT (4 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_6BIT (5 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_7BIT (6 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_8BIT (7 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_9BIT (8 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_10BIT (9 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_11BIT (10 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_12BIT (11 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_13BIT (12 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_14BIT (13 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_15BIT (14 << SSP_CR0_DSS_SHIFT)
+# define SSP_CR0_DSS_16BIT (15 << SSP_CR0_DSS_SHIFT)
+#define SSP_CR0_FRF_SHIFT (4) /* Bits 4-5: FRF Frame Format */
+#define SSP_CR0_FRF_MASK (3 << SSP_CR0_FRF_SHIFT)
+# define SSP_CR0_FRF_SPI (0 << SSP_CR0_FRF_SHIFT)
+# define SSP_CR0_FRF_TI (1 << SSP_CR0_FRF_SHIFT)
+# define SSP_CR0_FRF_UWIRE (2 << SSP_CR0_FRF_SHIFT)
+#define SSP_CR0_CPOL (1 << 6) /* Bit 6: Clock Out Polarity */
+#define SSP_CR0_CPHA (1 << 7) /* Bit 7: Clock Out Phase */
+#define SSP_CR0_SCR_SHIFT (8) /* Bits 8-15: Serial Clock Rate */
+#define SSP_CR0_SCR_MASK (0xff << SSP_CR0_SCR_SHIFT)
+ /* Bits 8-31: Reserved */
+/* Control Register 1 */
+
+#define SSP_CR1_LBM (1 << 0) /* Bit 0: Loop Back Mode */
+#define SSP_CR1_SSE (1 << 1) /* Bit 1: SSP Enable */
+#define SSP_CR1_MS (1 << 2) /* Bit 2: Master/Slave Mode */
+#define SSP_CR1_SOD (1 << 3) /* Bit 3: Slave Output Disable */
+ /* Bits 4-31: Reserved */
+/* Data Register */
+
+#define SSP_DR_MASK (0xffff) /* Bits 0-15: Data */
+ /* Bits 16-31: Reserved */
+/* Status Register */
+
+#define SSP_SR_TFE (1 << 0) /* Bit 0: Transmit FIFO Empty */
+#define SSP_SR_TNF (1 << 1) /* Bit 1: Transmit FIFO Not Full */
+#define SSP_SR_RNE (1 << 2) /* Bit 2: Receive FIFO Not Empty */
+#define SSP_SR_RFF (1 << 3) /* Bit 3: Receive FIFO Full */
+#define SSP_SR_BSY (1 << 4) /* Bit 4: Busy */
+ /* Bits 5-31: Reserved */
+/* Clock Prescale Register */
+
+#define SSP_CPSR_DVSR_MASK (0xff) /* Bits 0-7: clock = SSP_PCLK/DVSR */
+ /* Bits 8-31: Reserved */
+/* Common format for interrupt control registers:
+ *
+ * Interrupt Mask Set and Clear Register (IMSC)
+ * Raw Interrupt Status Register (RIS)
+ * Masked Interrupt Status Register (MIS)
+ * Interrupt Clear Register (ICR)
+ */
+
+#define SSP_INT_ROR (1 << 0) /* Bit 0: RX FIFO overrun */
+#define SSP_INT_RT (1 << 1) /* Bit 1: RX FIFO timeout */
+#define SSP_INT_RX (1 << 2) /* Bit 2: RX FIFO at least half full (not ICR) */
+#define SSP_INT_TX (1 << 3 ) /* Bit 3: TX FIFO at least half empy (not ICR) */
+ /* Bits 4-31: Reserved */
+/* DMA Control Register */
+
+#define SSP_DMACR_RXDMAE (1 << 0) /* Bit 0: Receive DMA Enable */
+#define SSP_DMACR_TXDMAE (1 << 1) /* Bit 1: Transmit DMA Enable */
+ /* Bits 2-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_SSP_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_syscon.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_syscon.h
index 3b9c32526..15be1e672 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_syscon.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_syscon.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_syscon.h
+ * arch/arm/src/lpc17xx/chip/lpc17_syscon.h
*
- * 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
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LPC17XX_LPC17_SYSCON_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_SYSCON_H
+#ifndef __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_SYSCON_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_SYSCON_H
/************************************************************************************
* Included Files
@@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
@@ -491,4 +491,4 @@
* Public Functions
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_SYSCON_H */
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_SYSCON_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_timer.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_timer.h
new file mode 100644
index 000000000..455133ee7
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_timer.h
@@ -0,0 +1,250 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_timer.h
+ *
+ * Copyright (C) 2010, 2012-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_LPC17XX_CHIP_LPC17_TIMER_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_TIMER_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_TMR_IR_OFFSET 0x0000 /* Interrupt Register */
+#define LPC17_TMR_TCR_OFFSET 0x0004 /* Timer Control Register */
+#define LPC17_TMR_TC_OFFSET 0x0008 /* Timer Counter */
+#define LPC17_TMR_PR_OFFSET 0x000c /* Prescale Register */
+#define LPC17_TMR_PC_OFFSET 0x0010 /* Prescale Counter */
+#define LPC17_TMR_MCR_OFFSET 0x0014 /* Match Control Register */
+#define LPC17_TMR_MR0_OFFSET 0x0018 /* Match Register 0 */
+#define LPC17_TMR_MR1_OFFSET 0x001c /* Match Register 1 */
+#define LPC17_TMR_MR2_OFFSET 0x0020 /* Match Register 2 */
+#define LPC17_TMR_MR3_OFFSET 0x0024 /* Match Register 3 */
+#define LPC17_TMR_CCR_OFFSET 0x0028 /* Capture Control Register */
+#define LPC17_TMR_CR0_OFFSET 0x002c /* Capture Register 0 */
+#define LPC17_TMR_CR1_OFFSET 0x0030 /* Capture Register 1 */
+#define LPC17_TMR_EMR_OFFSET 0x003c /* External Match Register */
+#define LPC17_TMR_CTCR_OFFSET 0x0070 /* Count Control Register */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_TMR0_IR (LPC17_TMR0_BASE+LPC17_TMR_IR_OFFSET)
+#define LPC17_TMR0_TCR (LPC17_TMR0_BASE+LPC17_TMR_TCR_OFFSET)
+#define LPC17_TMR0_TC (LPC17_TMR0_BASE+LPC17_TMR_TC_OFFSET)
+#define LPC17_TMR0_PR (LPC17_TMR0_BASE+LPC17_TMR_PR_OFFSET)
+#define LPC17_TMR0_PC (LPC17_TMR0_BASE+LPC17_TMR_PC_OFFSET)
+#define LPC17_TMR0_MCR (LPC17_TMR0_BASE+LPC17_TMR_MCR_OFFSET)
+#define LPC17_TMR0_MR0 (LPC17_TMR0_BASE+LPC17_TMR_MR0_OFFSET)
+#define LPC17_TMR0_MR1 (LPC17_TMR0_BASE+LPC17_TMR_MR1_OFFSET)
+#define LPC17_TMR0_MR2 (LPC17_TMR0_BASE+LPC17_TMR_MR2_OFFSET)
+#define LPC17_TMR0_MR3 (LPC17_TMR0_BASE+LPC17_TMR_MR3_OFFSET)
+#define LPC17_TMR0_CCR (LPC17_TMR0_BASE+LPC17_TMR_CCR_OFFSET)
+#define LPC17_TMR0_CR0 (LPC17_TMR0_BASE+LPC17_TMR_CR0_OFFSET)
+#define LPC17_TMR0_CR1 (LPC17_TMR0_BASE+LPC17_TMR_CR1_OFFSET)
+#define LPC17_TMR0_EMR (LPC17_TMR0_BASE+LPC17_TMR_EMR_OFFSET)
+#define LPC17_TMR0_CTCR (LPC17_TMR0_BASE+LPC17_TMR_CTCR_OFFSET)
+
+#define LPC17_TMR1_IR (LPC17_TMR1_BASE+LPC17_TMR_IR_OFFSET)
+#define LPC17_TMR1_TCR (LPC17_TMR1_BASE+LPC17_TMR_TCR_OFFSET)
+#define LPC17_TMR1_TC (LPC17_TMR1_BASE+LPC17_TMR_TC_OFFSET)
+#define LPC17_TMR1_PR (LPC17_TMR1_BASE+LPC17_TMR_PR_OFFSET)
+#define LPC17_TMR1_PC (LPC17_TMR1_BASE+LPC17_TMR_PC_OFFSET)
+#define LPC17_TMR1_MCR (LPC17_TMR1_BASE+LPC17_TMR_MCR_OFFSET)
+#define LPC17_TMR1_MR0 (LPC17_TMR1_BASE+LPC17_TMR_MR0_OFFSET)
+#define LPC17_TMR1_MR1 (LPC17_TMR1_BASE+LPC17_TMR_MR1_OFFSET)
+#define LPC17_TMR1_MR2 (LPC17_TMR1_BASE+LPC17_TMR_MR2_OFFSET)
+#define LPC17_TMR1_MR3 (LPC17_TMR1_BASE+LPC17_TMR_MR3_OFFSET)
+#define LPC17_TMR1_CCR (LPC17_TMR1_BASE+LPC17_TMR_CCR_OFFSET)
+#define LPC17_TMR1_CR0 (LPC17_TMR1_BASE+LPC17_TMR_CR0_OFFSET)
+#define LPC17_TMR1_CR1 (LPC17_TMR1_BASE+LPC17_TMR_CR1_OFFSET)
+#define LPC17_TMR1_EMR (LPC17_TMR1_BASE+LPC17_TMR_EMR_OFFSET)
+#define LPC17_TMR1_CTCR (LPC17_TMR1_BASE+LPC17_TMR_CTCR_OFFSET)
+
+#define LPC17_TMR2_IR (LPC17_TMR2_BASE+LPC17_TMR_IR_OFFSET)
+#define LPC17_TMR2_TCR (LPC17_TMR2_BASE+LPC17_TMR_TCR_OFFSET)
+#define LPC17_TMR2_TC (LPC17_TMR2_BASE+LPC17_TMR_TC_OFFSET)
+#define LPC17_TMR2_PR (LPC17_TMR2_BASE+LPC17_TMR_PR_OFFSET)
+#define LPC17_TMR2_PC (LPC17_TMR2_BASE+LPC17_TMR_PC_OFFSET)
+#define LPC17_TMR2_MCR (LPC17_TMR2_BASE+LPC17_TMR_MCR_OFFSET)
+#define LPC17_TMR2_MR0 (LPC17_TMR2_BASE+LPC17_TMR_MR0_OFFSET)
+#define LPC17_TMR2_MR1 (LPC17_TMR2_BASE+LPC17_TMR_MR1_OFFSET)
+#define LPC17_TMR2_MR2 (LPC17_TMR2_BASE+LPC17_TMR_MR2_OFFSET)
+#define LPC17_TMR2_MR3 (LPC17_TMR2_BASE+LPC17_TMR_MR3_OFFSET)
+#define LPC17_TMR2_CCR (LPC17_TMR2_BASE+LPC17_TMR_CCR_OFFSET)
+#define LPC17_TMR2_CR0 (LPC17_TMR2_BASE+LPC17_TMR_CR0_OFFSET)
+#define LPC17_TMR2_CR1 (LPC17_TMR2_BASE+LPC17_TMR_CR1_OFFSET)
+#define LPC17_TMR2_EMR (LPC17_TMR2_BASE+LPC17_TMR_EMR_OFFSET)
+#define LPC17_TMR2_CTCR (LPC17_TMR2_BASE+LPC17_TMR_CTCR_OFFSET)
+
+#define LPC17_TMR3_IR (LPC17_TMR3_BASE+LPC17_TMR_IR_OFFSET)
+#define LPC17_TMR3_TCR (LPC17_TMR3_BASE+LPC17_TMR_TCR_OFFSET)
+#define LPC17_TMR3_TC (LPC17_TMR3_BASE+LPC17_TMR_TC_OFFSET)
+#define LPC17_TMR3_PR (LPC17_TMR3_BASE+LPC17_TMR_PR_OFFSET)
+#define LPC17_TMR3_PC (LPC17_TMR3_BASE+LPC17_TMR_PC_OFFSET)
+#define LPC17_TMR3_MCR (LPC17_TMR3_BASE+LPC17_TMR_MCR_OFFSET)
+#define LPC17_TMR3_MR0 (LPC17_TMR3_BASE+LPC17_TMR_MR0_OFFSET)
+#define LPC17_TMR3_MR1 (LPC17_TMR3_BASE+LPC17_TMR_MR1_OFFSET)
+#define LPC17_TMR3_MR2 (LPC17_TMR3_BASE+LPC17_TMR_MR2_OFFSET)
+#define LPC17_TMR3_MR3 (LPC17_TMR3_BASE+LPC17_TMR_MR3_OFFSET)
+#define LPC17_TMR3_CCR (LPC17_TMR3_BASE+LPC17_TMR_CCR_OFFSET)
+#define LPC17_TMR3_CR0 (LPC17_TMR3_BASE+LPC17_TMR_CR0_OFFSET)
+#define LPC17_TMR3_CR1 (LPC17_TMR3_BASE+LPC17_TMR_CR1_OFFSET)
+#define LPC17_TMR3_EMR (LPC17_TMR3_BASE+LPC17_TMR_EMR_OFFSET)
+#define LPC17_TMR3_CTCR (LPC17_TMR3_BASE+LPC17_TMR_CTCR_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* Registers holding 32-bit numeric values (no bit field definitions):
+ *
+ * Timer Counter (TC)
+ * Prescale Register (PR)
+ * Prescale Counter (PC)
+ * Match Register 0 (MR0)
+ * Match Register 1 (MR1)
+ * Match Register 2 (MR2)
+ * Match Register 3 (MR3)
+ * Capture Register 0 (CR0)
+ * Capture Register 1 (CR1)
+ */
+
+/* Interrupt Register */
+
+#define TMR_IR_MR0 (1 << 0) /* Bit 0: Match channel 0 interrupt */
+#define TMR_IR_MR1 (1 << 1) /* Bit 1: Match channel 1 interrupt */
+#define TMR_IR_MR2 (1 << 2) /* Bit 2: Match channel 2 interrupt */
+#define TMR_IR_MR3 (1 << 3) /* Bit 3: Match channel 3 interrupt */
+#define TMR_IR_CR0 (1 << 4) /* Bit 4: Capture channel 0 interrupt */
+#define TMR_IR_CR1 (1 << 5) /* Bit 5: Capture channel 1 interrupt */
+ /* Bits 6-31: Reserved */
+/* Timer Control Register */
+
+#define TMR_TCR_EN (1 << 0) /* Bit 0: Counter Enable */
+#define TMR_TCR_RESET (1 << 1) /* Bit 1: Counter Reset */
+ /* Bits 2-31: Reserved */
+/* Match Control Register */
+
+#define TMR_MCR_MR0I (1 << 0) /* Bit 0: Interrupt on MR0 */
+#define TMR_MCR_MR0R (1 << 1) /* Bit 1: Reset on MR0 */
+#define TMR_MCR_MR0S (1 << 2) /* Bit 2: Stop on MR0 */
+#define TMR_MCR_MR1I (1 << 3) /* Bit 3: Interrupt on MR1 */
+#define TMR_MCR_MR1R (1 << 4) /* Bit 4: Reset on MR1 */
+#define TMR_MCR_MR1S (1 << 5) /* Bit 5: Stop on MR1 */
+#define TMR_MCR_MR2I (1 << 6) /* Bit 6: Interrupt on MR2 */
+#define TMR_MCR_MR2R (1 << 7) /* Bit 7: Reset on MR2 */
+#define TMR_MCR_MR2S (1 << 8) /* Bit 8: Stop on MR2 */
+#define TMR_MCR_MR3I (1 << 9) /* Bit 9: Interrupt on MR3 */
+#define TMR_MCR_MR3R (1 << 10) /* Bit 10: Reset on MR3 */
+#define TMR_MCR_MR3S (1 << 11) /* Bit 11: Stop on MR3 */
+ /* Bits 12-31: Reserved */
+/* Capture Control Register */
+
+#define TMR_CCR_CAP0RE (1 << 0) /* Bit 0: Capture on CAPn.0 rising edge */
+#define TMR_CCR_CAP0FE (1 << 1) /* Bit 1: Capture on CAPn.0 falling edge */
+#define TMR_CCR_CAP0I (1 << 2) /* Bit 2: Interrupt on CAPn.0 */
+#define TMR_CCR_CAP1RE (1 << 3) /* Bit 3: Capture on CAPn.1 rising edge */
+#define TMR_CCR_CAP1FE (1 << 4) /* Bit 4: Capture on CAPn.1 falling edge */
+#define TMR_CCR_CAP1I (1 << 5) /* Bit 5: Interrupt on CAPn.1 */
+ /* Bits 6-31: Reserved */
+/* External Match Register */
+
+#define TMR_EMR_NOTHING (0) /* Do Nothing */
+#define TMR_EMR_CLEAR (1) /* Clear external match bit MATn.m */
+#define TMR_EMR_SET (2) /* Set external match bit MATn.m */
+#define TMR_EMR_TOGGLE (3) /* Toggle external match bit MATn.m */
+
+#define TMR_EMR_EM0 (1 << 0) /* Bit 0: External Match 0 */
+#define TMR_EMR_EM1 (1 << 1) /* Bit 1: External Match 1 */
+#define TMR_EMR_EM2 (1 << 2) /* Bit 2: External Match 2 */
+#define TMR_EMR_EM3 (1 << 3) /* Bit 3: External Match 3 */
+#define TMR_EMR_EMC0_SHIFT (4) /* Bits 4-5: External Match Control 0 */
+#define TMR_EMR_EMC0_MASK (3 << TMR_EMR_EMC0_SHIFTy)
+# define TMR_EMR_EMC0_NOTHING (TMR_EMR_NOTHING << TMR_EMR_EMC0_SHIFT)
+# define TMR_EMR_EMC0_CLEAR (TMR_EMR_CLEAR << TMR_EMR_EMC0_SHIFT)
+# define TMR_EMR_EMC0_SET (TMR_EMR_SET << TMR_EMR_EMC0_SHIFT)
+# define TMR_EMR_EMC0_TOGGLE (TMR_EMR_TOGGLE << TMR_EMR_EMC0_SHIFT)
+#define TMR_EMR_EMC1_SHIFT (6) /* Bits 6-7: External Match Control 1 */
+#define TMR_EMR_EMC1_MASK (3 << TMR_EMR_EMC1_SHIFT)
+# define TMR_EMR_EMC1_NOTHING (TMR_EMR_NOTHING << TMR_EMR_EMC1_SHIFT)
+# define TMR_EMR_EMC1_CLEAR (TMR_EMR_CLEAR << TMR_EMR_EMC1_SHIFT)
+# define TMR_EMR_EMC1_SET (TMR_EMR_SET << TMR_EMR_EMC1_SHIFT)
+# define TMR_EMR_EMC1_TOGGLE (TMR_EMR_TOGGLE << TMR_EMR_EMC1_SHIFT)
+#define TMR_EMR_EMC2_SHIFT (8) /* Bits 8-9: External Match Control 2 */
+#define TMR_EMR_EMC2_MASK (3 << TMR_EMR_EMC2_SHIFT)
+# define TMR_EMR_EMC2_NOTHING (TMR_EMR_NOTHING << TMR_EMR_EMC2_SHIFT)
+# define TMR_EMR_EMC2_CLEAR (TMR_EMR_CLEAR << TMR_EMR_EMC2_SHIFT)
+# define TMR_EMR_EMC2_SET (TMR_EMR_SET << TMR_EMR_EMC2_SHIFT)
+# define TMR_EMR_EMC2_TOGGLE (TMR_EMR_TOGGLE << TMR_EMR_EMC2_SHIFT)
+#define TMR_EMR_EMC3_SHIFT (10) /* Bits 10-11: External Match Control 3 */
+#define TMR_EMR_EMC3_MASK (3 << TMR_EMR_EMC3_SHIFT)
+# define TMR_EMR_EMC3_NOTHING (TMR_EMR_NOTHING << TMR_EMR_EMC3_SHIFT)
+# define TMR_EMR_EMC3_CLEAR (TMR_EMR_CLEAR << TMR_EMR_EMC3_SHIFT)
+# define TMR_EMR_EMC3_SET (TMR_EMR_SET << TMR_EMR_EMC3_SHIFT)
+# define TMR_EMR_EMC3_TOGGLE (TMR_EMR_TOGGLE << TMR_EMR_EMC3_SHIFT)
+ /* Bits 12-31: Reserved */
+/* Count Control Register */
+
+#define TMR_CTCR_MODE_SHIFT (0) /* Bits 0-1: Counter/Timer Mode */
+#define TMR_CTCR_MODE_MASK (3 << TMR_CTCR_MODE_SHIFT)
+# define TMR_CTCR_MODE_TIMER (0 << TMR_CTCR_MODE_SHIFT) /* Timer Mode, prescale match */
+# define TMR_CTCR_MODE_CNTRRE (1 << TMR_CTCR_MODE_SHIFT) /* Counter Mode, CAP rising edge */
+# define TMR_CTCR_MODE_CNTRFE (2 << TMR_CTCR_MODE_SHIFT) /* Counter Mode, CAP falling edge */
+# define TMR_CTCR_MODE_CNTRBE (3 << TMR_CTCR_MODE_SHIFT) /* Counter Mode, CAP both edges */
+#define TMR_CTCR_INPSEL_SHIFT (2) /* Bits 2-3: Count Input Select */
+#define TMR_CTCR_INPSEL_MASK (3 << TMR_CTCR_INPSEL_SHIFT)
+# define TMR_CTCR_INPSEL_CAPNp0 (0 << TMR_CTCR_INPSEL_SHIFT) /* CAPn.0 for TIMERn */
+# define TMR_CTCR_INPSEL_CAPNp1 (1 << TMR_CTCR_INPSEL_SHIFT) /* CAPn.1 for TIMERn */
+ /* Bits 4-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_TIMER_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_uart.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_uart.h
index 3664a0cb8..1def0d009 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_uart.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_uart.h
@@ -1,339 +1,339 @@
-/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_uart.h
- *
- * Copyright (C) 2010, 2012 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_LPC17XX_LPC17_UART_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_UART_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
-
-/************************************************************************************
- * Pre-processor Definitions
- ************************************************************************************/
-
-/* Register offsets *****************************************************************/
-
-#define LPC17_UART_RBR_OFFSET 0x0000 /* (DLAB =0) Receiver Buffer Register (all) */
-#define LPC17_UART_THR_OFFSET 0x0000 /* (DLAB =0) Transmit Holding Register (all) */
-#define LPC17_UART_DLL_OFFSET 0x0000 /* (DLAB =1) Divisor Latch LSB (all) */
-#define LPC17_UART_DLM_OFFSET 0x0004 /* (DLAB =1) Divisor Latch MSB (all) */
-#define LPC17_UART_IER_OFFSET 0x0004 /* (DLAB =0) Interrupt Enable Register (all) */
-#define LPC17_UART_IIR_OFFSET 0x0008 /* Interrupt ID Register (all) */
-#define LPC17_UART_FCR_OFFSET 0x0008 /* FIFO Control Register (all) */
-#define LPC17_UART_LCR_OFFSET 0x000c /* Line Control Register (all) */
-#define LPC17_UART_MCR_OFFSET 0x0010 /* Modem Control Register (UART1 only) */
-#define LPC17_UART_LSR_OFFSET 0x0014 /* Line Status Register (all) */
-#define LPC17_UART_MSR_OFFSET 0x0018 /* Modem Status Register (UART1 only) */
-#define LPC17_UART_SCR_OFFSET 0x001c /* Scratch Pad Register (all) */
-#define LPC17_UART_ACR_OFFSET 0x0020 /* Auto-baud Control Register (all) */
-#define LPC17_UART_ICR_OFFSET 0x0024 /* IrDA Control Register (UART0,2,3 only) */
-#define LPC17_UART_FDR_OFFSET 0x0028 /* Fractional Divider Register (all) */
-#define LPC17_UART_TER_OFFSET 0x0030 /* Transmit Enable Register (all) */
-#define LPC17_UART_RS485CTRL_OFFSET 0x004c /* RS-485/EIA-485 Control (UART1 only) */
-#define LPC17_UART_ADRMATCH_OFFSET 0x0050 /* RS-485/EIA-485 address match (UART1 only) */
-#define LPC17_UART_RS485DLY_OFFSET 0x0054 /* RS-485/EIA-485 direction control delay (UART1 only) */
-#define LPC17_UART_FIFOLVL_OFFSET 0x0058 /* FIFO Level register (all) */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_UART0_RBR (LPC17_UART0_BASE+LPC17_UART_RBR_OFFSET)
-#define LPC17_UART0_THR (LPC17_UART0_BASE+LPC17_UART_THR_OFFSET)
-#define LPC17_UART0_DLL (LPC17_UART0_BASE+LPC17_UART_DLL_OFFSET)
-#define LPC17_UART0_DLM (LPC17_UART0_BASE+LPC17_UART_DLM_OFFSET)
-#define LPC17_UART0_IER (LPC17_UART0_BASE+LPC17_UART_IER_OFFSET)
-#define LPC17_UART0_IIR (LPC17_UART0_BASE+LPC17_UART_IIR_OFFSET)
-#define LPC17_UART0_FCR (LPC17_UART0_BASE+LPC17_UART_FCR_OFFSET)
-#define LPC17_UART0_LCR (LPC17_UART0_BASE+LPC17_UART_LCR_OFFSET)
-#define LPC17_UART0_LSR (LPC17_UART0_BASE+LPC17_UART_LSR_OFFSET)
-#define LPC17_UART0_SCR (LPC17_UART0_BASE+LPC17_UART_SCR_OFFSET)
-#define LPC17_UART0_ACR (LPC17_UART0_BASE+LPC17_UART_ACR_OFFSET)
-#define LPC17_UART0_ICR (LPC17_UART0_BASE+LPC17_UART_ICR_OFFSET)
-#define LPC17_UART0_FDR (LPC17_UART0_BASE+LPC17_UART_FDR_OFFSET)
-#define LPC17_UART0_TER (LPC17_UART0_BASE+LPC17_UART_TER_OFFSET)
-#define LPC17_UART0_FIFOLVL (LPC17_UART0_BASE+LPC17_UART_FIFOLVL_OFFSET)
-
-#define LPC17_UART1_RBR (LPC17_UART1_BASE+LPC17_UART_RBR_OFFSET)
-#define LPC17_UART1_THR (LPC17_UART1_BASE+LPC17_UART_THR_OFFSET)
-#define LPC17_UART1_DLL (LPC17_UART1_BASE+LPC17_UART_DLL_OFFSET)
-#define LPC17_UART1_DLM (LPC17_UART1_BASE+LPC17_UART_DLM_OFFSET)
-#define LPC17_UART1_IER (LPC17_UART1_BASE+LPC17_UART_IER_OFFSET)
-#define LPC17_UART1_IIR (LPC17_UART1_BASE+LPC17_UART_IIR_OFFSET)
-#define LPC17_UART1_FCR (LPC17_UART1_BASE+LPC17_UART_FCR_OFFSET)
-#define LPC17_UART1_LCR (LPC17_UART1_BASE+LPC17_UART_LCR_OFFSET)
-#define LPC17_UART1_MCR (LPC17_UART1_BASE+LPC17_UART_MCR_OFFSET)
-#define LPC17_UART1_LSR (LPC17_UART1_BASE+LPC17_UART_LSR_OFFSET)
-#define LPC17_UART1_MSR (LPC17_UART1_BASE+LPC17_UART_MSR_OFFSET)
-#define LPC17_UART1_SCR (LPC17_UART1_BASE+LPC17_UART_SCR_OFFSET)
-#define LPC17_UART1_ACR (LPC17_UART1_BASE+LPC17_UART_ACR_OFFSET)
-#define LPC17_UART1_FDR (LPC17_UART1_BASE+LPC17_UART_FDR_OFFSET)
-#define LPC17_UART1_TER (LPC17_UART1_BASE+LPC17_UART_TER_OFFSET)
-#define LPC17_UART1_RS485CTRL (LPC17_UART1_BASE+LPC17_UART_RS485CTRL_OFFSET)
-#define LPC17_UART1_ADRMATCH (LPC17_UART1_BASE+LPC17_UART_ADRMATCH_OFFSET)
-#define LPC17_UART1_RS485DLY (LPC17_UART1_BASE+LPC17_UART_RS485DLY_OFFSET)
-#define LPC17_UART1_FIFOLVL (LPC17_UART1_BASE+LPC17_UART_FIFOLVL_OFFSET)
-
-#define LPC17_UART2_RBR (LPC17_UART2_BASE+LPC17_UART_RBR_OFFSET)
-#define LPC17_UART2_THR (LPC17_UART2_BASE+LPC17_UART_THR_OFFSET)
-#define LPC17_UART2_DLL (LPC17_UART2_BASE+LPC17_UART_DLL_OFFSET)
-#define LPC17_UART2_DLM (LPC17_UART2_BASE+LPC17_UART_DLM_OFFSET)
-#define LPC17_UART2_IER (LPC17_UART2_BASE+LPC17_UART_IER_OFFSET)
-#define LPC17_UART2_IIR (LPC17_UART2_BASE+LPC17_UART_IIR_OFFSET)
-#define LPC17_UART2_FCR (LPC17_UART2_BASE+LPC17_UART_FCR_OFFSET)
-#define LPC17_UART2_LCR (LPC17_UART2_BASE+LPC17_UART_LCR_OFFSET)
-#define LPC17_UART2_LSR (LPC17_UART2_BASE+LPC17_UART_LSR_OFFSET)
-#define LPC17_UART2_SCR (LPC17_UART2_BASE+LPC17_UART_SCR_OFFSET)
-#define LPC17_UART2_ACR (LPC17_UART2_BASE+LPC17_UART_ACR_OFFSET)
-#define LPC17_UART2_ICR (LPC17_UART2_BASE+LPC17_UART_ICR_OFFSET)
-#define LPC17_UART2_FDR (LPC17_UART2_BASE+LPC17_UART_FDR_OFFSET)
-#define LPC17_UART2_TER (LPC17_UART2_BASE+LPC17_UART_TER_OFFSET)
-#define LPC17_UART2_FIFOLVL (LPC17_UART2_BASE+LPC17_UART_FIFOLVL_OFFSET)
-
-#define LPC17_UART3_RBR (LPC17_UART3_BASE+LPC17_UART_RBR_OFFSET)
-#define LPC17_UART3_THR (LPC17_UART3_BASE+LPC17_UART_THR_OFFSET)
-#define LPC17_UART3_DLL (LPC17_UART3_BASE+LPC17_UART_DLL_OFFSET)
-#define LPC17_UART3_DLM (LPC17_UART3_BASE+LPC17_UART_DLM_OFFSET)
-#define LPC17_UART3_IER (LPC17_UART3_BASE+LPC17_UART_IER_OFFSET)
-#define LPC17_UART3_IIR (LPC17_UART3_BASE+LPC17_UART_IIR_OFFSET)
-#define LPC17_UART3_FCR (LPC17_UART3_BASE+LPC17_UART_FCR_OFFSET)
-#define LPC17_UART3_LCR (LPC17_UART3_BASE+LPC17_UART_LCR_OFFSET)
-#define LPC17_UART3_LSR (LPC17_UART3_BASE+LPC17_UART_LSR_OFFSET)
-#define LPC17_UART3_SCR (LPC17_UART3_BASE+LPC17_UART_SCR_OFFSET)
-#define LPC17_UART3_ACR (LPC17_UART3_BASE+LPC17_UART_ACR_OFFSET)
-#define LPC17_UART3_ICR (LPC17_UART3_BASE+LPC17_UART_ICR_OFFSET)
-#define LPC17_UART3_FDR (LPC17_UART3_BASE+LPC17_UART_FDR_OFFSET)
-#define LPC17_UART3_TER (LPC17_UART3_BASE+LPC17_UART_TER_OFFSET)
-#define LPC17_UART3_FIFOLVL (LPC17_UART3_BASE+LPC17_UART_FIFOLVL_OFFSET)
-
-/* Register bit definitions *********************************************************/
-
-/* RBR (DLAB =0) Receiver Buffer Register (all) */
-
-#define UART_RBR_MASK (0xff) /* Bits 0-7: Oldest received byte in RX FIFO */
- /* Bits 8-31: Reserved */
-
-/* THR (DLAB =0) Transmit Holding Register (all) */
-
-#define UART_THR_MASK (0xff) /* Bits 0-7: Adds byte to TX FIFO */
- /* Bits 8-31: Reserved */
-
-/* DLL (DLAB =1) Divisor Latch LSB (all) */
-
-#define UART_DLL_MASK (0xff) /* Bits 0-7: DLL */
- /* Bits 8-31: Reserved */
-
-/* DLM (DLAB =1) Divisor Latch MSB (all) */
-
-#define UART_DLM_MASK (0xff) /* Bits 0-7: DLM */
- /* Bits 8-31: Reserved */
-
-/* IER (DLAB =0) Interrupt Enable Register (all) */
-
-#define UART_IER_RBRIE (1 << 0) /* Bit 0: RBR Interrupt Enable */
-#define UART_IER_THREIE (1 << 1) /* Bit 1: THRE Interrupt Enable */
-#define UART_IER_RLSIE (1 << 2) /* Bit 2: RX Line Status Interrupt Enable */
-#define UART_IER_MSIE (1 << 3) /* Bit 3: Modem Status Interrupt Enable (UART1 only) */
- /* Bits 4-6: Reserved */
-#define UART_IER_CTSIE (1 << 7) /* Bit 7: CTS transition interrupt (UART1 only) */
-#define UART_IER_ABEOIE (1 << 8) /* Bit 8: Enables the end of auto-baud interrupt */
-#define UART_IER_ABTOIE (1 << 9) /* Bit 9: Enables the auto-baud time-out interrupt */
- /* Bits 10-31: Reserved */
-#define UART_IER_ALLIE (0x038f)
-
-/* IIR Interrupt ID Register (all) */
-
-#define UART_IIR_INTSTATUS (1 << 0) /* Bit 0: Interrupt status (active low) */
-#define UART_IIR_INTID_SHIFT (1) /* Bits 1-3: Interrupt identification */
-#define UART_IIR_INTID_MASK (7 << UART_IIR_INTID_SHIFT)
-# define UART_IIR_INTID_MSI (0 << UART_IIR_INTID_SHIFT) /* Modem Status (UART1 only) */
-# define UART_IIR_INTID_THRE (1 << UART_IIR_INTID_SHIFT) /* THRE Interrupt */
-# define UART_IIR_INTID_RDA (2 << UART_IIR_INTID_SHIFT) /* 2a - Receive Data Available (RDA) */
-# define UART_IIR_INTID_RLS (3 << UART_IIR_INTID_SHIFT) /* 1 - Receive Line Status (RLS) */
-# define UART_IIR_INTID_CTI (6 << UART_IIR_INTID_SHIFT) /* 2b - Character Time-out Indicator (CTI) */
- /* Bits 4-5: Reserved */
-#define UART_IIR_FIFOEN_SHIFT (6) /* Bits 6-7: Copies of FCR bit 0 */
-#define UART_IIR_FIFOEN_MASK (3 << UART_IIR_FIFOEN_SHIFT)
-#define UART_IIR_ABEOINT (1 << 8) /* Bit 8: End of auto-baud interrupt */
-#define UART_IIR_ABTOINT (1 << 9) /* Bit 9: Auto-baud time-out interrupt */
- /* Bits 10-31: Reserved */
-/* FCR FIFO Control Register (all) */
-
-#define UART_FCR_FIFOEN (1 << 0) /* Bit 0: Enable FIFOs */
-#define UART_FCR_RXRST (1 << 1) /* Bit 1: RX FIFO Reset */
-#define UART_FCR_TXRST (1 << 2) /* Bit 2: TX FIFO Reset */
-#define UART_FCR_DMAMODE (1 << 3) /* Bit 3: DMA Mode Select */
- /* Bits 4-5: Reserved */
-#define UART_FCR_RXTRIGGER_SHIFT (6) /* Bits 6-7: RX Trigger Level */
-#define UART_FCR_RXTRIGGER_MASK (3 << UART_FCR_RXTRIGGER_SHIFT)
-# define UART_FCR_RXTRIGGER_0 (0 << UART_FCR_RXTRIGGER_SHIFT) /* Trigger level 0 (1 character) */
-# define UART_FCR_RXTRIGGER_4 (1 << UART_FCR_RXTRIGGER_SHIFT) /* Trigger level 1 (4 characters) */
-# define UART_FCR_RXTRIGGER_8 (2 << UART_FCR_RXTRIGGER_SHIFT) /* Trigger level 2 (8 characters) */
-# define UART_FCR_RXTRIGGER_14 (3 << UART_FCR_RXTRIGGER_SHIFT) /* Trigger level 3 (14 characters) */
- /* Bits 8-31: Reserved */
-/* LCR Line Control Register (all) */
-
-#define UART_LCR_WLS_SHIFT (0) /* Bit 0-1: Word Length Select */
-#define UART_LCR_WLS_MASK (3 << UART_LCR_WLS_SHIFT)
-# define UART_LCR_WLS_5BIT (0 << UART_LCR_WLS_SHIFT)
-# define UART_LCR_WLS_6BIT (1 << UART_LCR_WLS_SHIFT)
-# define UART_LCR_WLS_7BIT (2 << UART_LCR_WLS_SHIFT)
-# define UART_LCR_WLS_8BIT (3 << UART_LCR_WLS_SHIFT)
-#define UART_LCR_STOP (1 << 2) /* Bit 2: Stop Bit Select */
-#define UART_LCR_PE (1 << 3) /* Bit 3: Parity Enable */
-#define UART_LCR_PS_SHIFT (4) /* Bits 4-5: Parity Select */
-#define UART_LCR_PS_MASK (3 << UART_LCR_PS_SHIFT)
-# define UART_LCR_PS_ODD (0 << UART_LCR_PS_SHIFT) /* Odd parity */
-# define UART_LCR_PS_EVEN (1 << UART_LCR_PS_SHIFT) /* Even Parity */
-# define UART_LCR_PS_STICK1 (2 << UART_LCR_PS_SHIFT) /* Forced "1" stick parity */
-# define UART_LCR_PS_STICK0 (3 << UART_LCR_PS_SHIFT) /* Forced "0" stick parity */
-#define UART_LCR_BRK (1 << 6) /* Bit 6: Break Control */
-#define UART_LCR_DLAB (1 << 7) /* Bit 7: Divisor Latch Access Bit (DLAB) */
- /* Bits 8-31: Reserved */
-/* MCR Modem Control Register (UART1 only) */
-
-#define UART_MCR_DTR (1 << 0) /* Bit 0: DTR Control Source for DTR output */
-#define UART_MCR_RTS (1 << 1) /* Bit 1: Control Source for RTS output */
- /* Bits 2-3: Reserved */
-#define UART_MCR_LPBK (1 << 4) /* Bit 4: Loopback Mode Select */
- /* Bit 5: Reserved */
-#define UART_MCR_RTSEN (1 << 6) /* Bit 6: Enable auto-rts flow control */
-#define UART_MCR_CTSEN (1 << 7) /* Bit 7: Enable auto-cts flow control */
- /* Bits 8-31: Reserved */
-/* LSR Line Status Register (all) */
-
-#define UART_LSR_RDR (1 << 0) /* Bit 0: Receiver Data Ready */
-#define UART_LSR_OE (1 << 1) /* Bit 1: Overrun Error */
-#define UART_LSR_PE (1 << 2) /* Bit 2: Parity Error */
-#define UART_LSR_FE (1 << 3) /* Bit 3: Framing Error */
-#define UART_LSR_BI (1 << 4) /* Bit 4: Break Interrupt */
-#define UART_LSR_THRE (1 << 5) /* Bit 5: Transmitter Holding Register Empty */
-#define UART_LSR_TEMT (1 << 6) /* Bit 6: Transmitter Empty */
-#define UART_LSR_RXFE (1 << 7) /* Bit 7: Error in RX FIFO (RXFE) */
- /* Bits 8-31: Reserved */
-/* MSR Modem Status Register (UART1 only) */
-
-#define UART_MSR_DELTACTS (1 << 0) /* Bit 0: CTS state change */
-#define UART_MSR_DELTADSR (1 << 1) /* Bit 1: DSR state change */
-#define UART_MSR_RIEDGE (1 << 2) /* Bit 2: RI ow to high transition */
-#define UART_MSR_DELTADCD (1 << 3) /* Bit 3: DCD state change */
-#define UART_MSR_CTS (1 << 4) /* Bit 4: CTS State */
-#define UART_MSR_DSR (1 << 5) /* Bit 5: DSR State */
-#define UART_MSR_RI (1 << 6) /* Bit 6: Ring Indicator State */
-#define UART_MSR_DCD (1 << 7) /* Bit 7: Data Carrier Detect State */
- /* Bits 8-31: Reserved */
-/* SCR Scratch Pad Register (all) */
-
-#define UART_SCR_MASK (0xff) /* Bits 0-7: SCR data */
- /* Bits 8-31: Reserved */
-/* ACR Auto-baud Control Register (all) */
-
-#define UART_ACR_START (1 << 0) /* Bit 0: Auto-baud start/running*/
-#define UART_ACR_MODE (1 << 1) /* Bit 1: Auto-baud mode select*/
-#define UART_ACR_AUTORESTART (1 << 2) /* Bit 2: Restart in case of time-out*/
- /* Bits 3-7: Reserved */
-#define UART_ACR_ABEOINTCLR (1 << 8) /* Bit 8: End of auto-baud interrupt clear */
-#define UART_ACR_ABTOINTCLRT (1 << 9) /* Bit 9: Auto-baud time-out interrupt clear */
- /* Bits 10-31: Reserved */
-/* ICA IrDA Control Register (UART0,2,3 only) */
-
-#define UART_ICR_IRDAEN (1 << 0) /* Bit 0: Enable IrDA mode */
-#define UART_ICR_IRDAINV (1 << 1) /* Bit 1: Invert serial input */
-#define UART_ICR_FIXPULSEEN (1 << 2) /* Bit 2: Enable IrDA fixed pulse width mode */
-#define UART_ICR_PULSEDIV_SHIFT (3) /* Bits 3-5: Configures the pulse when FixPulseEn = 1 */
-#define UART_ICR_PULSEDIV_MASK (7 << UART_ICR_PULSEDIV_SHIFT)
-# define UART_ICR_PULSEDIV_2TPCLK (0 << UART_ICR_PULSEDIV_SHIFT) /* 2 x TPCLK */
-# define UART_ICR_PULSEDIV_4TPCLK (1 << UART_ICR_PULSEDIV_SHIFT) /* 4 x TPCLK */
-# define UART_ICR_PULSEDIV_8TPCLK (2 << UART_ICR_PULSEDIV_SHIFT) /* 8 x TPCLK */
-# define UART_ICR_PULSEDIV_16TPCLK (3 << UART_ICR_PULSEDIV_SHIFT) /* 16 x TPCLK */
-# define UART_ICR_PULSEDIV_32TPCLK (4 << UART_ICR_PULSEDIV_SHIFT) /* 32 x TPCLK */
-# define UART_ICR_PULSEDIV_64TPCLK (5 << UART_ICR_PULSEDIV_SHIFT) /* 64 x TPCLK */
-# define UART_ICR_PULSEDIV_128TPCLK (6 << UART_ICR_PULSEDIV_SHIFT) /* 128 x TPCLK */
-# define UART_ICR_PULSEDIV_256TPCLK (7 << UART_ICR_PULSEDIV_SHIFT) /* 246 x TPCLK */
- /* Bits 6-31: Reserved */
-/* FDR Fractional Divider Register (all) */
-
-#define UART_FDR_DIVADDVAL_SHIFT (0) /* Bits 0-3: Baud-rate generation pre-scaler divisor value */
-#define UART_FDR_DIVADDVAL_MASK (15 << UART_FDR_DIVADDVAL_SHIFT)
-#define UART_FDR_MULVAL_SHIFT (3) /* Bits 4-7 Baud-rate pre-scaler multiplier value */
-#define UART_FDR_MULVAL_MASK (15 << UART_FDR_MULVAL_SHIFT)
- /* Bits 8-31: Reserved */
-/* TER Transmit Enable Register (all) */
- /* Bits 0-6: Reserved */
-#define UART_TER_TXEN (1 << 7) /* Bit 7: TX Enable */
- /* Bits 8-31: Reserved */
-/* RS-485/EIA-485 Control (UART1 only) */
-
-#define UART_RS485CTRL_NMMEN (1 << 0) /* Bit 0: RS-485/EIA-485 Normal Multidrop Mode (NMM) enabled */
-#define UART_RS485CTRL_RXDIS (1 << 1) /* Bit 1: Receiver is disabled */
-#define UART_RS485CTRL_AADEN (1 << 2) /* Bit 2: Auto Address Detect (AAD) is enabled */
-#define UART_RS485CTRL_SEL (1 << 3) /* Bit 3: RTS/DTR used for direction control (DCTRL=1) */
-#define UART_RS485CTRL_DCTRL (1 << 4) /* Bit 4: Enable Auto Direction Control */
-#define UART_RS485CTRL_OINV (1 << 5) /* Bit 5: Polarity of the direction control signal on RTS/DTR */
- /* Bits 6-31: Reserved */
-/* RS-485/EIA-485 address match (UART1 only) */
-
-#define UART_ADRMATCH_MASK (0xff) /* Bits 0-7: Address match value */
- /* Bits 8-31: Reserved */
-/* RS-485/EIA-485 direction control delay (UART1 only) */
-
-#define UART_RS485DLY_MASK (0xff) /* Bits 0-7: Direction control (RTS/DTR) delay */
- /* Bits 8-31: Reserved */
-/* FIFOLVL FIFO Level register (all) */
-
-#define UART_FIFOLVL_RX_SHIFT (0) /* Bits 0-3: Current level of the UART RX FIFO */
-#define UART_FIFOLVL_RX_MASK (15 << UART_FIFOLVL_RX_SHIFT)
- /* Bits 4-7: Reserved */
-#define UART_FIFOLVL_TX_SHIFT (8) /* Bits 8-11: Current level of the UART TX FIFO */
-#define UART_FIFOLVL_TX_MASK (15 << UART_FIFOLVL_TX_SHIFT)
- /* Bits 12-31: Reserved */
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
- * Public Data
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_UART_H */
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_uart.h
+ *
+ * Copyright (C) 2010, 2012-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_LPC17XX_CHIP_LPC17_UART_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_UART_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_UART_RBR_OFFSET 0x0000 /* (DLAB =0) Receiver Buffer Register (all) */
+#define LPC17_UART_THR_OFFSET 0x0000 /* (DLAB =0) Transmit Holding Register (all) */
+#define LPC17_UART_DLL_OFFSET 0x0000 /* (DLAB =1) Divisor Latch LSB (all) */
+#define LPC17_UART_DLM_OFFSET 0x0004 /* (DLAB =1) Divisor Latch MSB (all) */
+#define LPC17_UART_IER_OFFSET 0x0004 /* (DLAB =0) Interrupt Enable Register (all) */
+#define LPC17_UART_IIR_OFFSET 0x0008 /* Interrupt ID Register (all) */
+#define LPC17_UART_FCR_OFFSET 0x0008 /* FIFO Control Register (all) */
+#define LPC17_UART_LCR_OFFSET 0x000c /* Line Control Register (all) */
+#define LPC17_UART_MCR_OFFSET 0x0010 /* Modem Control Register (UART1 only) */
+#define LPC17_UART_LSR_OFFSET 0x0014 /* Line Status Register (all) */
+#define LPC17_UART_MSR_OFFSET 0x0018 /* Modem Status Register (UART1 only) */
+#define LPC17_UART_SCR_OFFSET 0x001c /* Scratch Pad Register (all) */
+#define LPC17_UART_ACR_OFFSET 0x0020 /* Auto-baud Control Register (all) */
+#define LPC17_UART_ICR_OFFSET 0x0024 /* IrDA Control Register (UART0,2,3 only) */
+#define LPC17_UART_FDR_OFFSET 0x0028 /* Fractional Divider Register (all) */
+#define LPC17_UART_TER_OFFSET 0x0030 /* Transmit Enable Register (all) */
+#define LPC17_UART_RS485CTRL_OFFSET 0x004c /* RS-485/EIA-485 Control (UART1 only) */
+#define LPC17_UART_ADRMATCH_OFFSET 0x0050 /* RS-485/EIA-485 address match (UART1 only) */
+#define LPC17_UART_RS485DLY_OFFSET 0x0054 /* RS-485/EIA-485 direction control delay (UART1 only) */
+#define LPC17_UART_FIFOLVL_OFFSET 0x0058 /* FIFO Level register (all) */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_UART0_RBR (LPC17_UART0_BASE+LPC17_UART_RBR_OFFSET)
+#define LPC17_UART0_THR (LPC17_UART0_BASE+LPC17_UART_THR_OFFSET)
+#define LPC17_UART0_DLL (LPC17_UART0_BASE+LPC17_UART_DLL_OFFSET)
+#define LPC17_UART0_DLM (LPC17_UART0_BASE+LPC17_UART_DLM_OFFSET)
+#define LPC17_UART0_IER (LPC17_UART0_BASE+LPC17_UART_IER_OFFSET)
+#define LPC17_UART0_IIR (LPC17_UART0_BASE+LPC17_UART_IIR_OFFSET)
+#define LPC17_UART0_FCR (LPC17_UART0_BASE+LPC17_UART_FCR_OFFSET)
+#define LPC17_UART0_LCR (LPC17_UART0_BASE+LPC17_UART_LCR_OFFSET)
+#define LPC17_UART0_LSR (LPC17_UART0_BASE+LPC17_UART_LSR_OFFSET)
+#define LPC17_UART0_SCR (LPC17_UART0_BASE+LPC17_UART_SCR_OFFSET)
+#define LPC17_UART0_ACR (LPC17_UART0_BASE+LPC17_UART_ACR_OFFSET)
+#define LPC17_UART0_ICR (LPC17_UART0_BASE+LPC17_UART_ICR_OFFSET)
+#define LPC17_UART0_FDR (LPC17_UART0_BASE+LPC17_UART_FDR_OFFSET)
+#define LPC17_UART0_TER (LPC17_UART0_BASE+LPC17_UART_TER_OFFSET)
+#define LPC17_UART0_FIFOLVL (LPC17_UART0_BASE+LPC17_UART_FIFOLVL_OFFSET)
+
+#define LPC17_UART1_RBR (LPC17_UART1_BASE+LPC17_UART_RBR_OFFSET)
+#define LPC17_UART1_THR (LPC17_UART1_BASE+LPC17_UART_THR_OFFSET)
+#define LPC17_UART1_DLL (LPC17_UART1_BASE+LPC17_UART_DLL_OFFSET)
+#define LPC17_UART1_DLM (LPC17_UART1_BASE+LPC17_UART_DLM_OFFSET)
+#define LPC17_UART1_IER (LPC17_UART1_BASE+LPC17_UART_IER_OFFSET)
+#define LPC17_UART1_IIR (LPC17_UART1_BASE+LPC17_UART_IIR_OFFSET)
+#define LPC17_UART1_FCR (LPC17_UART1_BASE+LPC17_UART_FCR_OFFSET)
+#define LPC17_UART1_LCR (LPC17_UART1_BASE+LPC17_UART_LCR_OFFSET)
+#define LPC17_UART1_MCR (LPC17_UART1_BASE+LPC17_UART_MCR_OFFSET)
+#define LPC17_UART1_LSR (LPC17_UART1_BASE+LPC17_UART_LSR_OFFSET)
+#define LPC17_UART1_MSR (LPC17_UART1_BASE+LPC17_UART_MSR_OFFSET)
+#define LPC17_UART1_SCR (LPC17_UART1_BASE+LPC17_UART_SCR_OFFSET)
+#define LPC17_UART1_ACR (LPC17_UART1_BASE+LPC17_UART_ACR_OFFSET)
+#define LPC17_UART1_FDR (LPC17_UART1_BASE+LPC17_UART_FDR_OFFSET)
+#define LPC17_UART1_TER (LPC17_UART1_BASE+LPC17_UART_TER_OFFSET)
+#define LPC17_UART1_RS485CTRL (LPC17_UART1_BASE+LPC17_UART_RS485CTRL_OFFSET)
+#define LPC17_UART1_ADRMATCH (LPC17_UART1_BASE+LPC17_UART_ADRMATCH_OFFSET)
+#define LPC17_UART1_RS485DLY (LPC17_UART1_BASE+LPC17_UART_RS485DLY_OFFSET)
+#define LPC17_UART1_FIFOLVL (LPC17_UART1_BASE+LPC17_UART_FIFOLVL_OFFSET)
+
+#define LPC17_UART2_RBR (LPC17_UART2_BASE+LPC17_UART_RBR_OFFSET)
+#define LPC17_UART2_THR (LPC17_UART2_BASE+LPC17_UART_THR_OFFSET)
+#define LPC17_UART2_DLL (LPC17_UART2_BASE+LPC17_UART_DLL_OFFSET)
+#define LPC17_UART2_DLM (LPC17_UART2_BASE+LPC17_UART_DLM_OFFSET)
+#define LPC17_UART2_IER (LPC17_UART2_BASE+LPC17_UART_IER_OFFSET)
+#define LPC17_UART2_IIR (LPC17_UART2_BASE+LPC17_UART_IIR_OFFSET)
+#define LPC17_UART2_FCR (LPC17_UART2_BASE+LPC17_UART_FCR_OFFSET)
+#define LPC17_UART2_LCR (LPC17_UART2_BASE+LPC17_UART_LCR_OFFSET)
+#define LPC17_UART2_LSR (LPC17_UART2_BASE+LPC17_UART_LSR_OFFSET)
+#define LPC17_UART2_SCR (LPC17_UART2_BASE+LPC17_UART_SCR_OFFSET)
+#define LPC17_UART2_ACR (LPC17_UART2_BASE+LPC17_UART_ACR_OFFSET)
+#define LPC17_UART2_ICR (LPC17_UART2_BASE+LPC17_UART_ICR_OFFSET)
+#define LPC17_UART2_FDR (LPC17_UART2_BASE+LPC17_UART_FDR_OFFSET)
+#define LPC17_UART2_TER (LPC17_UART2_BASE+LPC17_UART_TER_OFFSET)
+#define LPC17_UART2_FIFOLVL (LPC17_UART2_BASE+LPC17_UART_FIFOLVL_OFFSET)
+
+#define LPC17_UART3_RBR (LPC17_UART3_BASE+LPC17_UART_RBR_OFFSET)
+#define LPC17_UART3_THR (LPC17_UART3_BASE+LPC17_UART_THR_OFFSET)
+#define LPC17_UART3_DLL (LPC17_UART3_BASE+LPC17_UART_DLL_OFFSET)
+#define LPC17_UART3_DLM (LPC17_UART3_BASE+LPC17_UART_DLM_OFFSET)
+#define LPC17_UART3_IER (LPC17_UART3_BASE+LPC17_UART_IER_OFFSET)
+#define LPC17_UART3_IIR (LPC17_UART3_BASE+LPC17_UART_IIR_OFFSET)
+#define LPC17_UART3_FCR (LPC17_UART3_BASE+LPC17_UART_FCR_OFFSET)
+#define LPC17_UART3_LCR (LPC17_UART3_BASE+LPC17_UART_LCR_OFFSET)
+#define LPC17_UART3_LSR (LPC17_UART3_BASE+LPC17_UART_LSR_OFFSET)
+#define LPC17_UART3_SCR (LPC17_UART3_BASE+LPC17_UART_SCR_OFFSET)
+#define LPC17_UART3_ACR (LPC17_UART3_BASE+LPC17_UART_ACR_OFFSET)
+#define LPC17_UART3_ICR (LPC17_UART3_BASE+LPC17_UART_ICR_OFFSET)
+#define LPC17_UART3_FDR (LPC17_UART3_BASE+LPC17_UART_FDR_OFFSET)
+#define LPC17_UART3_TER (LPC17_UART3_BASE+LPC17_UART_TER_OFFSET)
+#define LPC17_UART3_FIFOLVL (LPC17_UART3_BASE+LPC17_UART_FIFOLVL_OFFSET)
+
+/* Register bit definitions *********************************************************/
+
+/* RBR (DLAB =0) Receiver Buffer Register (all) */
+
+#define UART_RBR_MASK (0xff) /* Bits 0-7: Oldest received byte in RX FIFO */
+ /* Bits 8-31: Reserved */
+
+/* THR (DLAB =0) Transmit Holding Register (all) */
+
+#define UART_THR_MASK (0xff) /* Bits 0-7: Adds byte to TX FIFO */
+ /* Bits 8-31: Reserved */
+
+/* DLL (DLAB =1) Divisor Latch LSB (all) */
+
+#define UART_DLL_MASK (0xff) /* Bits 0-7: DLL */
+ /* Bits 8-31: Reserved */
+
+/* DLM (DLAB =1) Divisor Latch MSB (all) */
+
+#define UART_DLM_MASK (0xff) /* Bits 0-7: DLM */
+ /* Bits 8-31: Reserved */
+
+/* IER (DLAB =0) Interrupt Enable Register (all) */
+
+#define UART_IER_RBRIE (1 << 0) /* Bit 0: RBR Interrupt Enable */
+#define UART_IER_THREIE (1 << 1) /* Bit 1: THRE Interrupt Enable */
+#define UART_IER_RLSIE (1 << 2) /* Bit 2: RX Line Status Interrupt Enable */
+#define UART_IER_MSIE (1 << 3) /* Bit 3: Modem Status Interrupt Enable (UART1 only) */
+ /* Bits 4-6: Reserved */
+#define UART_IER_CTSIE (1 << 7) /* Bit 7: CTS transition interrupt (UART1 only) */
+#define UART_IER_ABEOIE (1 << 8) /* Bit 8: Enables the end of auto-baud interrupt */
+#define UART_IER_ABTOIE (1 << 9) /* Bit 9: Enables the auto-baud time-out interrupt */
+ /* Bits 10-31: Reserved */
+#define UART_IER_ALLIE (0x038f)
+
+/* IIR Interrupt ID Register (all) */
+
+#define UART_IIR_INTSTATUS (1 << 0) /* Bit 0: Interrupt status (active low) */
+#define UART_IIR_INTID_SHIFT (1) /* Bits 1-3: Interrupt identification */
+#define UART_IIR_INTID_MASK (7 << UART_IIR_INTID_SHIFT)
+# define UART_IIR_INTID_MSI (0 << UART_IIR_INTID_SHIFT) /* Modem Status (UART1 only) */
+# define UART_IIR_INTID_THRE (1 << UART_IIR_INTID_SHIFT) /* THRE Interrupt */
+# define UART_IIR_INTID_RDA (2 << UART_IIR_INTID_SHIFT) /* 2a - Receive Data Available (RDA) */
+# define UART_IIR_INTID_RLS (3 << UART_IIR_INTID_SHIFT) /* 1 - Receive Line Status (RLS) */
+# define UART_IIR_INTID_CTI (6 << UART_IIR_INTID_SHIFT) /* 2b - Character Time-out Indicator (CTI) */
+ /* Bits 4-5: Reserved */
+#define UART_IIR_FIFOEN_SHIFT (6) /* Bits 6-7: Copies of FCR bit 0 */
+#define UART_IIR_FIFOEN_MASK (3 << UART_IIR_FIFOEN_SHIFT)
+#define UART_IIR_ABEOINT (1 << 8) /* Bit 8: End of auto-baud interrupt */
+#define UART_IIR_ABTOINT (1 << 9) /* Bit 9: Auto-baud time-out interrupt */
+ /* Bits 10-31: Reserved */
+/* FCR FIFO Control Register (all) */
+
+#define UART_FCR_FIFOEN (1 << 0) /* Bit 0: Enable FIFOs */
+#define UART_FCR_RXRST (1 << 1) /* Bit 1: RX FIFO Reset */
+#define UART_FCR_TXRST (1 << 2) /* Bit 2: TX FIFO Reset */
+#define UART_FCR_DMAMODE (1 << 3) /* Bit 3: DMA Mode Select */
+ /* Bits 4-5: Reserved */
+#define UART_FCR_RXTRIGGER_SHIFT (6) /* Bits 6-7: RX Trigger Level */
+#define UART_FCR_RXTRIGGER_MASK (3 << UART_FCR_RXTRIGGER_SHIFT)
+# define UART_FCR_RXTRIGGER_0 (0 << UART_FCR_RXTRIGGER_SHIFT) /* Trigger level 0 (1 character) */
+# define UART_FCR_RXTRIGGER_4 (1 << UART_FCR_RXTRIGGER_SHIFT) /* Trigger level 1 (4 characters) */
+# define UART_FCR_RXTRIGGER_8 (2 << UART_FCR_RXTRIGGER_SHIFT) /* Trigger level 2 (8 characters) */
+# define UART_FCR_RXTRIGGER_14 (3 << UART_FCR_RXTRIGGER_SHIFT) /* Trigger level 3 (14 characters) */
+ /* Bits 8-31: Reserved */
+/* LCR Line Control Register (all) */
+
+#define UART_LCR_WLS_SHIFT (0) /* Bit 0-1: Word Length Select */
+#define UART_LCR_WLS_MASK (3 << UART_LCR_WLS_SHIFT)
+# define UART_LCR_WLS_5BIT (0 << UART_LCR_WLS_SHIFT)
+# define UART_LCR_WLS_6BIT (1 << UART_LCR_WLS_SHIFT)
+# define UART_LCR_WLS_7BIT (2 << UART_LCR_WLS_SHIFT)
+# define UART_LCR_WLS_8BIT (3 << UART_LCR_WLS_SHIFT)
+#define UART_LCR_STOP (1 << 2) /* Bit 2: Stop Bit Select */
+#define UART_LCR_PE (1 << 3) /* Bit 3: Parity Enable */
+#define UART_LCR_PS_SHIFT (4) /* Bits 4-5: Parity Select */
+#define UART_LCR_PS_MASK (3 << UART_LCR_PS_SHIFT)
+# define UART_LCR_PS_ODD (0 << UART_LCR_PS_SHIFT) /* Odd parity */
+# define UART_LCR_PS_EVEN (1 << UART_LCR_PS_SHIFT) /* Even Parity */
+# define UART_LCR_PS_STICK1 (2 << UART_LCR_PS_SHIFT) /* Forced "1" stick parity */
+# define UART_LCR_PS_STICK0 (3 << UART_LCR_PS_SHIFT) /* Forced "0" stick parity */
+#define UART_LCR_BRK (1 << 6) /* Bit 6: Break Control */
+#define UART_LCR_DLAB (1 << 7) /* Bit 7: Divisor Latch Access Bit (DLAB) */
+ /* Bits 8-31: Reserved */
+/* MCR Modem Control Register (UART1 only) */
+
+#define UART_MCR_DTR (1 << 0) /* Bit 0: DTR Control Source for DTR output */
+#define UART_MCR_RTS (1 << 1) /* Bit 1: Control Source for RTS output */
+ /* Bits 2-3: Reserved */
+#define UART_MCR_LPBK (1 << 4) /* Bit 4: Loopback Mode Select */
+ /* Bit 5: Reserved */
+#define UART_MCR_RTSEN (1 << 6) /* Bit 6: Enable auto-rts flow control */
+#define UART_MCR_CTSEN (1 << 7) /* Bit 7: Enable auto-cts flow control */
+ /* Bits 8-31: Reserved */
+/* LSR Line Status Register (all) */
+
+#define UART_LSR_RDR (1 << 0) /* Bit 0: Receiver Data Ready */
+#define UART_LSR_OE (1 << 1) /* Bit 1: Overrun Error */
+#define UART_LSR_PE (1 << 2) /* Bit 2: Parity Error */
+#define UART_LSR_FE (1 << 3) /* Bit 3: Framing Error */
+#define UART_LSR_BI (1 << 4) /* Bit 4: Break Interrupt */
+#define UART_LSR_THRE (1 << 5) /* Bit 5: Transmitter Holding Register Empty */
+#define UART_LSR_TEMT (1 << 6) /* Bit 6: Transmitter Empty */
+#define UART_LSR_RXFE (1 << 7) /* Bit 7: Error in RX FIFO (RXFE) */
+ /* Bits 8-31: Reserved */
+/* MSR Modem Status Register (UART1 only) */
+
+#define UART_MSR_DELTACTS (1 << 0) /* Bit 0: CTS state change */
+#define UART_MSR_DELTADSR (1 << 1) /* Bit 1: DSR state change */
+#define UART_MSR_RIEDGE (1 << 2) /* Bit 2: RI ow to high transition */
+#define UART_MSR_DELTADCD (1 << 3) /* Bit 3: DCD state change */
+#define UART_MSR_CTS (1 << 4) /* Bit 4: CTS State */
+#define UART_MSR_DSR (1 << 5) /* Bit 5: DSR State */
+#define UART_MSR_RI (1 << 6) /* Bit 6: Ring Indicator State */
+#define UART_MSR_DCD (1 << 7) /* Bit 7: Data Carrier Detect State */
+ /* Bits 8-31: Reserved */
+/* SCR Scratch Pad Register (all) */
+
+#define UART_SCR_MASK (0xff) /* Bits 0-7: SCR data */
+ /* Bits 8-31: Reserved */
+/* ACR Auto-baud Control Register (all) */
+
+#define UART_ACR_START (1 << 0) /* Bit 0: Auto-baud start/running*/
+#define UART_ACR_MODE (1 << 1) /* Bit 1: Auto-baud mode select*/
+#define UART_ACR_AUTORESTART (1 << 2) /* Bit 2: Restart in case of time-out*/
+ /* Bits 3-7: Reserved */
+#define UART_ACR_ABEOINTCLR (1 << 8) /* Bit 8: End of auto-baud interrupt clear */
+#define UART_ACR_ABTOINTCLRT (1 << 9) /* Bit 9: Auto-baud time-out interrupt clear */
+ /* Bits 10-31: Reserved */
+/* ICA IrDA Control Register (UART0,2,3 only) */
+
+#define UART_ICR_IRDAEN (1 << 0) /* Bit 0: Enable IrDA mode */
+#define UART_ICR_IRDAINV (1 << 1) /* Bit 1: Invert serial input */
+#define UART_ICR_FIXPULSEEN (1 << 2) /* Bit 2: Enable IrDA fixed pulse width mode */
+#define UART_ICR_PULSEDIV_SHIFT (3) /* Bits 3-5: Configures the pulse when FixPulseEn = 1 */
+#define UART_ICR_PULSEDIV_MASK (7 << UART_ICR_PULSEDIV_SHIFT)
+# define UART_ICR_PULSEDIV_2TPCLK (0 << UART_ICR_PULSEDIV_SHIFT) /* 2 x TPCLK */
+# define UART_ICR_PULSEDIV_4TPCLK (1 << UART_ICR_PULSEDIV_SHIFT) /* 4 x TPCLK */
+# define UART_ICR_PULSEDIV_8TPCLK (2 << UART_ICR_PULSEDIV_SHIFT) /* 8 x TPCLK */
+# define UART_ICR_PULSEDIV_16TPCLK (3 << UART_ICR_PULSEDIV_SHIFT) /* 16 x TPCLK */
+# define UART_ICR_PULSEDIV_32TPCLK (4 << UART_ICR_PULSEDIV_SHIFT) /* 32 x TPCLK */
+# define UART_ICR_PULSEDIV_64TPCLK (5 << UART_ICR_PULSEDIV_SHIFT) /* 64 x TPCLK */
+# define UART_ICR_PULSEDIV_128TPCLK (6 << UART_ICR_PULSEDIV_SHIFT) /* 128 x TPCLK */
+# define UART_ICR_PULSEDIV_256TPCLK (7 << UART_ICR_PULSEDIV_SHIFT) /* 246 x TPCLK */
+ /* Bits 6-31: Reserved */
+/* FDR Fractional Divider Register (all) */
+
+#define UART_FDR_DIVADDVAL_SHIFT (0) /* Bits 0-3: Baud-rate generation pre-scaler divisor value */
+#define UART_FDR_DIVADDVAL_MASK (15 << UART_FDR_DIVADDVAL_SHIFT)
+#define UART_FDR_MULVAL_SHIFT (3) /* Bits 4-7 Baud-rate pre-scaler multiplier value */
+#define UART_FDR_MULVAL_MASK (15 << UART_FDR_MULVAL_SHIFT)
+ /* Bits 8-31: Reserved */
+/* TER Transmit Enable Register (all) */
+ /* Bits 0-6: Reserved */
+#define UART_TER_TXEN (1 << 7) /* Bit 7: TX Enable */
+ /* Bits 8-31: Reserved */
+/* RS-485/EIA-485 Control (UART1 only) */
+
+#define UART_RS485CTRL_NMMEN (1 << 0) /* Bit 0: RS-485/EIA-485 Normal Multidrop Mode (NMM) enabled */
+#define UART_RS485CTRL_RXDIS (1 << 1) /* Bit 1: Receiver is disabled */
+#define UART_RS485CTRL_AADEN (1 << 2) /* Bit 2: Auto Address Detect (AAD) is enabled */
+#define UART_RS485CTRL_SEL (1 << 3) /* Bit 3: RTS/DTR used for direction control (DCTRL=1) */
+#define UART_RS485CTRL_DCTRL (1 << 4) /* Bit 4: Enable Auto Direction Control */
+#define UART_RS485CTRL_OINV (1 << 5) /* Bit 5: Polarity of the direction control signal on RTS/DTR */
+ /* Bits 6-31: Reserved */
+/* RS-485/EIA-485 address match (UART1 only) */
+
+#define UART_ADRMATCH_MASK (0xff) /* Bits 0-7: Address match value */
+ /* Bits 8-31: Reserved */
+/* RS-485/EIA-485 direction control delay (UART1 only) */
+
+#define UART_RS485DLY_MASK (0xff) /* Bits 0-7: Direction control (RTS/DTR) delay */
+ /* Bits 8-31: Reserved */
+/* FIFOLVL FIFO Level register (all) */
+
+#define UART_FIFOLVL_RX_SHIFT (0) /* Bits 0-3: Current level of the UART RX FIFO */
+#define UART_FIFOLVL_RX_MASK (15 << UART_FIFOLVL_RX_SHIFT)
+ /* Bits 4-7: Reserved */
+#define UART_FIFOLVL_TX_SHIFT (8) /* Bits 8-11: Current level of the UART TX FIFO */
+#define UART_FIFOLVL_TX_MASK (15 << UART_FIFOLVL_TX_SHIFT)
+ /* Bits 12-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_UART_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usb.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_usb.h
index 8fd599584..d1e6dd013 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_usb.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_usb.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_usb.h
+ * arch/arm/src/lpc17xx/chip/lpc17_usb.h
*
- * 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
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LPC17XX_LPC17_USB_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_USB_H
+#ifndef __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_USB_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_USB_H
/************************************************************************************
* Included Files
@@ -44,7 +44,7 @@
#include <nuttx/usb/ohci.h>
#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
@@ -775,4 +775,4 @@
* Public Functions
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_USB_H */
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC17_USB_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_wdt.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_wdt.h
new file mode 100644
index 000000000..9c83ac4de
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_wdt.h
@@ -0,0 +1,108 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc17_wdt.h
+ *
+ * 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
+ * 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_LPC17XX_LPC17_WDT_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_WDT_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_WDT_WDMOD_OFFSET 0x0000 /* Watchdog mode register */
+#define LPC17_WDT_WDTC_OFFSET 0x0004 /* Watchdog timer constant register */
+#define LPC17_WDT_WDFEED_OFFSET 0x0008 /* Watchdog feed sequence register */
+#define LPC17_WDT_WDTV_OFFSET 0x000c /* Watchdog timer value register */
+#define LPC17_WDT_WDCLKSEL_OFFSET 0x0010 /* Watchdog clock source selection register */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_WDT_WDMOD (LPC17_WDT_BASE+LPC17_WDT_WDMOD_OFFSET)
+#define LPC17_WDT_WDTC (LPC17_WDT_BASE+LPC17_WDT_WDTC_OFFSET)
+#define LPC17_WDT_WDFEED (LPC17_WDT_BASE+LPC17_WDT_WDFEED_OFFSET)
+#define LPC17_WDT_WDTV (LPC17_WDT_BASE+LPC17_WDT_WDTV_OFFSET)
+#define LPC17_WDT_WDCLKSEL (LPC17_WDT_BASE+LPC17_WDT_WDCLKSEL_OFFSET)
+
+/* Register bit definitions *********************************************************/
+
+/* Watchdog mode register */
+
+#define WDT_WDMOD_WDEN (1 << 0) /* Bit 0: Watchdog enable */
+#define WDT_WDMOD_WDRESET (1 << 1) /* Bit 1: Watchdog reset enable */
+#define WDT_WDMOD_WDTOF (1 << 2) /* Bit 2: Watchdog time-out */
+#define WDT_WDMOD_WDINT (1 << 3) /* Bit 3: Watchdog interrupt */
+ /* Bits 14-31: Reserved */
+
+/* Watchdog timer constant register (Bits 0-31: Watchdog time-out interval) */
+
+/* Watchdog feed sequence register */
+
+#define WDT_WDFEED_MASK (0xff) /* Bits 0-7: Feed value should be 0xaa followed by 0x55 */
+ /* Bits 14-31: Reserved */
+/* Watchdog timer value register (Bits 0-31: Counter timer value) */
+
+/* Watchdog clock source selection register */
+
+#define WDT_WDCLKSEL_WDSEL_SHIFT (0) /* Bits 0-1: Clock source for the Watchdog timer */
+#define WDT_WDCLKSEL_WDSEL_MASK (3 << WDT_WDCLKSEL_WDSEL_SHIFT)
+# define WDT_WDCLKSEL_WDSEL_INTRC (0 << WDT_WDCLKSEL_WDSEL_SHIFT) /* Internal RC osc */
+# define WDT_WDCLKSEL_WDSEL_APB (1 << WDT_WDCLKSEL_WDSEL_SHIFT) /* APB peripheral clock (watchdog pclk) */
+# define WDT_WDCLKSEL_WDSEL_RTC (2 << WDT_WDCLKSEL_WDSEL_SHIFT) /* RTC oscillator (rtc_clk) */
+ /* Bits 2-30: Reserved */
+#define WDT_WDCLKSEL_WDLOCK (1 << 31) /* Bit 31: Lock WDT register bits if set */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_WDT_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_adc.c b/nuttx/arch/arm/src/lpc17xx/lpc17_adc.c
index ebc05d13e..81e13e342 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_adc.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_adc.c
@@ -60,9 +60,8 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
-#include "lpc17_syscon.h"
-#include "lpc17_pinconn.h"
+#include "chip/lpc17_syscon.h"
+#include "lpc17_gpio.h"
#include "lpc17_adc.h"
#if defined(CONFIG_LPC17_ADC)
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_adc.h b/nuttx/arch/arm/src/lpc17xx/lpc17_adc.h
index 6b9a58345..5a1bef14a 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_adc.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_adc.h
@@ -1,180 +1,88 @@
-/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_adc.h
- *
- * Copyright (C) 2010, 2012 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_LPC17XX_LPC17_ADC_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_ADC_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
-
-/************************************************************************************
- * Pre-processor Definitions
- ************************************************************************************/
-
-/* Register offsets *****************************************************************/
-
-#define LPC17_ADC_CR_OFFSET 0x0000 /* A/D Control Register */
-#define LPC17_ADC_GDR_OFFSET 0x0004 /* A/D Global Data Register */
-#define LPC17_ADC_INTEN_OFFSET 0x000c /* A/D Interrupt Enable Register */
-
-#define LPC17_ADC_DR_OFFSET(n) (0x0010+((n) << 2))
-#define LPC17_ADC_DR0_OFFSET 0x0010 /* A/D Channel 0 Data Register */
-#define LPC17_ADC_DR1_OFFSET 0x0014 /* A/D Channel 1 Data Register */
-#define LPC17_ADC_DR2_OFFSET 0x0018 /* A/D Channel 2 Data Register */
-#define LPC17_ADC_DR3_OFFSET 0x001c /* A/D Channel 3 Data Register */
-#define LPC17_ADC_DR4_OFFSET 0x0020 /* A/D Channel 4 Data Register */
-#define LPC17_ADC_DR5_OFFSET 0x0024 /* A/D Channel 5 Data Register */
-#define LPC17_ADC_DR6_OFFSET 0x0028 /* A/D Channel 6 Data Register */
-#define LPC17_ADC_DR7_OFFSET 0x002c /* A/D Channel 7 Data Register */
-
-#define LPC17_ADC_STAT_OFFSET 0x0030 /* A/D Status Register */
-#define LPC17_ADC_TRM_OFFSET 0x0034 /* ADC trim register */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_ADC_CR (LPC17_ADC_BASE+LPC17_ADC_CR_OFFSET)
-#define LPC17_ADC_GDR (LPC17_ADC_BASE+LPC17_ADC_GDR_OFFSET)
-#define LPC17_ADC_INTEN (LPC17_ADC_BASE+LPC17_ADC_INTEN_OFFSET)
-
-#define LPC17_ADC_DR(n) (LPC17_ADC_BASE+LPC17_ADC_DR_OFFSET(n))
-#define LPC17_ADC_DR0 (LPC17_ADC_BASE+LPC17_ADC_DR0_OFFSET)
-#define LPC17_ADC_DR1 (LPC17_ADC_BASE+LPC17_ADC_DR1_OFFSET)
-#define LPC17_ADC_DR2 (LPC17_ADC_BASE+LPC17_ADC_DR2_OFFSET)
-#define LPC17_ADC_DR3 (LPC17_ADC_BASE+LPC17_ADC_DR3_OFFSET)
-#define LPC17_ADC_DR4 (LPC17_ADC_BASE+LPC17_ADC_DR4_OFFSET)
-#define LPC17_ADC_DR5 (LPC17_ADC_BASE+LPC17_ADC_DR5_OFFSET)
-#define LPC17_ADC_DR6 (LPC17_ADC_BASE+LPC17_ADC_DR6_OFFSET)
-#define LPC17_ADC_DR7 (LPC17_ADC_BASE+LPC17_ADC_DR7_OFFSET)
-
-#define LPC17_ADC_STAT (LPC17_ADC_BASE+LPC17_ADC_STAT_OFFSET)
-#define LPC17_ADC_TRM (LPC17_ADC_BASE+LPC17_ADC_TRM_OFFSET)
-
-/* Register bit definitions *********************************************************/
-
-/* A/D Control Register */
-
-#define ADC_CR_SEL_SHIFT (0) /* Bits 0-7: Selects pins to be sampled */
-#define ADC_CR_SEL_MASK (0xff << ADC_CR_SEL_MASK)
-#define ADC_CR_CLKDIV_SHIFT (8) /* Bits 8-15: APB clock (PCLK_ADC0) divisor */
-#define ADC_CR_CLKDIV_MASK (0xff << ADC_CR_CLKDIV_SHIFT)
-#define ADC_CR_BURST (1 << 16) /* Bit 16: A/D Repeated conversions */
- /* Bits 17-20: Reserved */
-#define ADC_CR_PDN (1 << 21) /* Bit 21: A/D converter power-down mode */
- /* Bits 22-23: Reserved */
-#define ADC_CR_START_SHIFT (24) /* Bits 24-26: Control A/D conversion start */
-#define ADC_CR_START_MASK (7 << ADC_CR_START_SHIFT)
-# define ADC_CR_START_NOSTART (0 << ADC_CR_START_SHIFT) /* No start */
-# define ADC_CR_START_NOW (1 << ADC_CR_START_SHIFT) /* Start now */
-# define ADC_CR_START_P2p10 (2 << ADC_CR_START_SHIFT) /* Start edge on P2.10/EINT0/NMI */
-# define ADC_CR_START_P1p27 (3 << ADC_CR_START_SHIFT) /* Start edge on P1.27/CLKOUT/USB_OVRCRn/CAP0.1 */
-# define ADC_CR_START_MAT0p1 (4 << ADC_CR_START_SHIFT) /* Start edge on MAT0.1 */
-# define ADC_CR_START_MAT0p3 (5 << ADC_CR_START_SHIFT) /* Start edge on MAT0.3 */
-# define ADC_CR_START_MAT1p0 (6 << ADC_CR_START_SHIFT) /* Start edge on MAT1.0 */
-# define ADC_CR_START_MAT1p1 (7 << ADC_CR_START_SHIFT) /* Start edge on MAT1.1 */
-#define ADC_CR_EDGE (1 << 27) /* Bit 27: Start on falling edge */
- /* Bits 28-31: Reserved */
-/* A/D Global Data Register AND Channel 0-7 Data Register */
- /* Bits 0-3: Reserved */
-#define ADC_DR_RESULT_SHIFT (4) /* Bits 4-15: Result of conversion (DONE==1) */
-#define ADC_DR_RESULT_MASK (0x0fff << ADC_DR_RESULT_SHIFT)
- /* Bits 16-23: Reserved */
-#define ADC_DR_CHAN_SHIFT (24) /* Bits 24-26: Channel converted */
-#define ADC_DR_CHAN_MASK (3 << ADC_DR_CHN_SHIFT)
- /* Bits 27-29: Reserved */
-#define ADC_DR_OVERRUN (1 << 30) /* Bit 30: Conversion(s) lost/overwritten*/
-#define ADC_DR_DONE (1 << 31) /* Bit 31: A/D conversion complete*/
-
-/* A/D Interrupt Enable Register */
-
-#define ADC_INTEN_CHAN(n) (1 << (n))
-#define ADC_INTEN_CHAN0 (1 << 0) /* Bit 0: Enable ADC chan 0 complete intterrupt */
-#define ADC_INTEN_CHAN1 (1 << 1) /* Bit 1: Enable ADC chan 1 complete interrupt */
-#define ADC_INTEN_CHAN2 (1 << 2) /* Bit 2: Enable ADC chan 2 complete interrupt */
-#define ADC_INTEN_CHAN3 (1 << 3) /* Bit 3: Enable ADC chan 3 complete interrupt */
-#define ADC_INTEN_CHAN4 (1 << 4) /* Bit 4: Enable ADC chan 4 complete interrupt */
-#define ADC_INTEN_CHAN5 (1 << 5) /* Bit 5: Enable ADC chan 5 complete interrupt */
-#define ADC_INTEN_CHAN6 (1 << 6) /* Bit 6: Enable ADC chan 6 complete interrupt */
-#define ADC_INTEN_CHAN7 (1 << 7) /* Bit 7: Enable ADC chan 7 complete interrupt */
-#define ADC_INTEN_GLOBAL (1 << 8) /* Bit 8: Only the global DONE generates interrupt */
- /* Bits 9-31: Reserved */
-/* A/D Status Register */
-
-#define ADC_STAT_DONE(n) (1 << (n))
-#define ADC_STAT_DONE0 (1 << 0) /* Bit 0: A/D chan 0 DONE */
-#define ADC_STAT_DONE1 (1 << 1) /* Bit 1: A/D chan 1 DONE */
-#define ADC_STAT_DONE2 (1 << 2) /* Bit 2: A/D chan 2 DONE */
-#define ADC_STAT_DONE3 (1 << 3) /* Bit 3: A/D chan 3 DONE */
-#define ADC_STAT_DONE4 (1 << 4) /* Bit 4: A/D chan 4 DONE */
-#define ADC_STAT_DONE5 (1 << 5) /* Bit 5: A/D chan 5 DONE */
-#define ADC_STAT_DONE6 (1 << 6) /* Bit 6: A/D chan 6 DONE */
-#define ADC_STAT_DONE7 (1 << 7) /* Bit 7: A/D chan 7 DONE */
-#define ADC_STAT_OVERRUN(n) ((1 << (n)) + 8)
-#define ADC_STAT_OVERRUN0 (1 << 8) /* Bit 8: A/D chan 0 OVERRUN */
-#define ADC_STAT_OVERRUN1 (1 << 9) /* Bit 9: A/D chan 1 OVERRUN */
-#define ADC_STAT_OVERRUN2 (1 << 10) /* Bit 10: A/D chan 2 OVERRUN */
-#define ADC_STAT_OVERRUN3 (1 << 11) /* Bit 11: A/D chan 3 OVERRUN */
-#define ADC_STAT_OVERRUN4 (1 << 12) /* Bit 12: A/D chan 4 OVERRUN */
-#define ADC_STAT_OVERRUN5 (1 << 13) /* Bit 13: A/D chan 5 OVERRUN */
-#define ADC_STAT_OVERRUN6 (1 << 14) /* Bit 14: A/D chan 6 OVERRUN */
-#define ADC_STAT_OVERRUN7 (1 << 15) /* Bit 15: A/D chan 7 OVERRUN */
-#define ADC_STAT_INT (1 << 16) /* Bit 15: A/D interrupt */
- /* Bits 17-31: Reserved */
-/* ADC trim register */
- /* Bits 0-3: Reserved */
-#define ADC_TRM_ADCOFFS_SHIFT (4) /* Bits 4-7: A/D offset trim bits */
-#define ADC_TRM_ADCOFFS_MASK (15 << ADC_TRM_ADCOFFS_SHIFT)
-#define ADC_TRM_TRIM_SHIFT (8) /* Bits 8-11: Written-to by boot code */
-#define ADC_TRM_TRIM_MASK (15 << ADC_TRM_TRIM_SHIFT)
- /* Bits 12-31: Reserved */
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
- * Public Data
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_ADC_H */
+/****************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_adc.h
+ *
+ * Copyright (C) 2010, 2012, 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_LPC17XX_LPC17_ADC_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_ADC_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/lpc17_adc.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: lpc17_adcinitialize
+ *
+ * Description:
+ * Initialize the adc
+ *
+ * Returned Value:
+ * Valid can device structure reference on succcess; a NULL on failure
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_LPC17_ADC
+FAR struct adc_dev_s *lpc17_adcinitialize(void);
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_ADC_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
index 501358716..5da6ffa22 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
@@ -50,7 +50,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_memorymap.h"
#include "lpc17_emacram.h"
#include "lpc17_ohciram.h"
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_can.c b/nuttx/arch/arm/src/lpc17xx/lpc17_can.c
index 409785d29..abdf8c7b7 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_can.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_can.c
@@ -62,9 +62,8 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
-#include "lpc17_syscon.h"
-#include "lpc17_pinconn.h"
+#include "chip/lpc17_syscon.h"
+#include "lpc17_gpio.h"
#include "lpc17_can.h"
#if defined(CONFIG_LPC17_CAN1) || defined(CONFIG_LPC17_CAN2)
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_can.h b/nuttx/arch/arm/src/lpc17xx/lpc17_can.h
index e990958fd..e15eaced5 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_can.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_can.h
@@ -1,7 +1,7 @@
-/************************************************************************************
+/****************************************************************************
* arch/arm/src/lpc17xx/lpc17_can.h
*
- * Copyright (C) 2010-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2012, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -31,480 +31,62 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************************************/
+ ****************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC17XX_LPC17_CAN_H
#define __ARCH_ARM_SRC_LPC17XX_LPC17_CAN_H
-/************************************************************************************
+/****************************************************************************
* Included Files
- ************************************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
+#include "chip/lpc17_can.h"
-#include "chip.h"
-#include "lpc17_memorymap.h"
-
-/************************************************************************************
+/****************************************************************************
* Pre-processor Definitions
- ************************************************************************************/
-
-/* Register offsets *****************************************************************/
-/* CAN acceptance filter registers */
-
-#define LPC17_CANAF_AFMR_OFFSET 0x0000 /* Acceptance Filter Register */
-#define LPC17_CANAF_SFFSA_OFFSET 0x0004 /* Standard Frame Individual Start Address Register */
-#define LPC17_CANAF_SFFGRPSA_OFFSET 0x0008 /* Standard Frame Group Start Address Register */
-#define LPC17_CANAF_EFFSA_OFFSET 0x000c /* Extended Frame Start Address Register */
-#define LPC17_CANAF_EFFGRPSA_OFFSET 0x0010 /* Extended Frame Group Start Address Register */
-#define LPC17_CANAF_EOT_OFFSET 0x0014 /* End of AF Tables register */
-#define LPC17_CANAF_LUTERRAD_OFFSET 0x0018 /* LUT Error Address register */
-#define LPC17_CANAF_LUTERR_OFFSET 0x001c /* LUT Error Register */
-#define LPC17_CANAF_FCANIE_OFFSET 0x0020 /* FullCAN interrupt enable register */
-#define LPC17_CANAF_FCANIC0_OFFSET 0x0024 /* FullCAN interrupt and capture register 0 */
-#define LPC17_CANAF_FCANIC1_OFFSET 0x0028 /* FullCAN interrupt and capture register 1 */
-
-/* Central CAN registers */
-
-#define LPC17_CAN_TXSR_OFFSET 0x0000 /* CAN Central Transmit Status Register */
-#define LPC17_CAN_RXSR_OFFSET 0x0004 /* CAN Central Receive Status Register */
-#define LPC17_CAN_MSR_OFFSET 0x0008 /* CAN Central Miscellaneous Register */
-
-/* CAN1/2 registers */
-
-#define LPC17_CAN_MOD_OFFSET 0x0000 /* CAN operating mode */
-#define LPC17_CAN_CMR_OFFSET 0x0004 /* Command bits */
-#define LPC17_CAN_GSR_OFFSET 0x0008 /* Controller Status and Error Counters */
-#define LPC17_CAN_ICR_OFFSET 0x000c /* Interrupt and capure register */
-#define LPC17_CAN_IER_OFFSET 0x0010 /* Interrupt Enable */
-#define LPC17_CAN_BTR_OFFSET 0x0014 /* Bus Timing */
-#define LPC17_CAN_EWL_OFFSET 0x0018 /* Error Warning Limit */
-#define LPC17_CAN_SR_OFFSET 0x001c /* Status Register */
-#define LPC17_CAN_RFS_OFFSET 0x0020 /* Receive frame status */
-#define LPC17_CAN_RID_OFFSET 0x0024 /* Received Identifier */
-#define LPC17_CAN_RDA_OFFSET 0x0028 /* Received data bytes 1-4 */
-#define LPC17_CAN_RDB_OFFSET 0x002c /* Received data bytes 5-8 */
-#define LPC17_CAN_TFI1_OFFSET 0x0030 /* Transmit frame info (Tx Buffer 1) */
-#define LPC17_CAN_TID1_OFFSET 0x0034 /* Transmit Identifier (Tx Buffer 1) */
-#define LPC17_CAN_TDA1_OFFSET 0x0038 /* Transmit data bytes 1-4 (Tx Buffer 1) */
-#define LPC17_CAN_TDB1_OFFSET 0x003c /* Transmit data bytes 5-8 (Tx Buffer 1) */
-#define LPC17_CAN_TFI2_OFFSET 0x0040 /* Transmit frame info (Tx Buffer 2) */
-#define LPC17_CAN_TID2_OFFSET 0x0044 /* Transmit Identifier (Tx Buffer 2) */
-#define LPC17_CAN_TDA2_OFFSET 0x0048 /* Transmit data bytes 1-4 (Tx Buffer 2) */
-#define LPC17_CAN_TDB2_OFFSET 0x004c /* Transmit data bytes 5-8 (Tx Buffer 2) */
-#define LPC17_CAN_TFI3_OFFSET 0x0050 /* Transmit frame info (Tx Buffer 3) */
-#define LPC17_CAN_TID3_OFFSET 0x0054 /* Transmit Identifier (Tx Buffer 3) */
-#define LPC17_CAN_TDA3_OFFSET 0x0058 /* Transmit data bytes 1-4 (Tx Buffer 3) */
-#define LPC17_CAN_TDB3_OFFSET 0x005c /* Transmit data bytes 5-8 (Tx Buffer 3) */
-
-/* Register addresses ***************************************************************/
-/* CAN acceptance filter registers */
-
-#define LPC17_CANAF_AFMR (LPC17_CANAF_BASE+LPC17_CANAF_AFMR_OFFSET)
-#define LPC17_CANAF_SFFSA (LPC17_CANAF_BASE+LPC17_CANAF_SFFSA_OFFSET)
-#define LPC17_CANAF_SFFGRPSA (LPC17_CANAF_BASE+LPC17_CANAF_SFFGRPSA_OFFSET)
-#define LPC17_CANAF_EFFSA (LPC17_CANAF_BASE+LPC17_CANAF_EFFSA_OFFSET)
-#define LPC17_CANAF_EFFGRPSA (LPC17_CANAF_BASE+LPC17_CANAF_EFFGRPSA_OFFSET)
-#define LPC17_CANAF_EOT (LPC17_CANAF_BASE+LPC17_CANAF_EOT_OFFSET)
-#define LPC17_CANAF_LUTERRAD (LPC17_CANAF_BASE+LPC17_CANAF_LUTERRAD_OFFSET)
-#define LPC17_CANAF_LUTERR (LPC17_CANAF_BASE+LPC17_CANAF_LUTERR_OFFSET)
-#define LPC17_CANAF_FCANIE (LPC17_CANAF_BASE+LPC17_CANAF_FCANIE_OFFSET)
-#define LPC17_CANAF_FCANIC0 (LPC17_CANAF_BASE+LPC17_CANAF_FCANIC0_OFFSET)
-#define LPC17_CANAF_FCANIC1 (LPC17_CANAF_BASE+LPC17_CANAF_FCANIC1_OFFSET)
-
-/* Central CAN registers */
-
-#define LPC17_CAN_TXSR (LPC17_CAN_BASE+LPC17_CAN_TXSR_OFFSET)
-#define LPC17_CAN_RXSR (LPC17_CAN_BASE+LPC17_CAN_RXSR_OFFSET)
-#define LPC17_CAN_MSR (LPC17_CAN_BASE+LPC17_CAN_MSR_OFFSET)
-
-/* CAN1/2 registers */
-
-#define LPC17_CAN1_MOD (LPC17_CAN1_BASE+LPC17_CAN_MOD_OFFSET)
-#define LPC17_CAN1_CMR (LPC17_CAN1_BASE+LPC17_CAN_CMR_OFFSET)
-#define LPC17_CAN1_GSR (LPC17_CAN1_BASE+LPC17_CAN_GSR_OFFSET)
-#define LPC17_CAN1_ICR (LPC17_CAN1_BASE+LPC17_CAN_ICR_OFFSET)
-#define LPC17_CAN1_IER (LPC17_CAN1_BASE+LPC17_CAN_IER_OFFSET)
-#define LPC17_CAN1_BTR (LPC17_CAN1_BASE+LPC17_CAN_BTR_OFFSET)
-#define LPC17_CAN1_EWL (LPC17_CAN1_BASE+LPC17_CAN_EWL_OFFSET)
-#define LPC17_CAN1_SR (LPC17_CAN1_BASE+LPC17_CAN_SR_OFFSET)
-#define LPC17_CAN1_RFS (LPC17_CAN1_BASE+LPC17_CAN_RFS_OFFSET)
-#define LPC17_CAN1_RID (LPC17_CAN1_BASE+LPC17_CAN_RID_OFFSET)
-#define LPC17_CAN1_RDA (LPC17_CAN1_BASE+LPC17_CAN_RDA_OFFSET)
-#define LPC17_CAN1_RDB (LPC17_CAN1_BASE+LPC17_CAN_RDB_OFFSET)
-#define LPC17_CAN1_TFI1 (LPC17_CAN1_BASE+LPC17_CAN_TFI1_OFFSET)
-#define LPC17_CAN1_TID1 (LPC17_CAN1_BASE+LPC17_CAN_TID1_OFFSET)
-#define LPC17_CAN1_TDA1 (LPC17_CAN1_BASE+LPC17_CAN_TDA1_OFFSET)
-#define LPC17_CAN1_TDB1 (LPC17_CAN1_BASE+LPC17_CAN_TDB1_OFFSET)
-#define LPC17_CAN1_TFI2 (LPC17_CAN1_BASE+LPC17_CAN_TFI2_OFFSET)
-#define LPC17_CAN1_TID2 (LPC17_CAN1_BASE+LPC17_CAN_TID2_OFFSET)
-#define LPC17_CAN1_TDA2 (LPC17_CAN1_BASE+LPC17_CAN_TDA2_OFFSET)
-#define LPC17_CAN1_TDB2 (LPC17_CAN1_BASE+LPC17_CAN_TDB2_OFFSET)
-#define LPC17_CAN1_TFI3 (LPC17_CAN1_BASE+LPC17_CAN_TFI3_OFFSET)
-#define LPC17_CAN1_TID3 (LPC17_CAN1_BASE+LPC17_CAN_TID3_OFFSET)
-#define LPC17_CAN1_TDA3 (LPC17_CAN1_BASE+LPC17_CAN_TDA3_OFFSET)
-#define LPC17_CAN1_TDB3 (LPC17_CAN1_BASE+LPC17_CAN_TDB3_OFFSET)
-
-#define LPC17_CAN2_MOD (LPC17_CAN2_BASE+LPC17_CAN_MOD_OFFSET)
-#define LPC17_CAN2_CMR (LPC17_CAN2_BASE+LPC17_CAN_CMR_OFFSET)
-#define LPC17_CAN2_GSR (LPC17_CAN2_BASE+LPC17_CAN_GSR_OFFSET)
-#define LPC17_CAN2_ICR (LPC17_CAN2_BASE+LPC17_CAN_ICR_OFFSET)
-#define LPC17_CAN2_IER (LPC17_CAN2_BASE+LPC17_CAN_IER_OFFSET)
-#define LPC17_CAN2_BTR (LPC17_CAN2_BASE+LPC17_CAN_BTR_OFFSET)
-#define LPC17_CAN2_EWL (LPC17_CAN2_BASE+LPC17_CAN_EWL_OFFSET)
-#define LPC17_CAN2_SR (LPC17_CAN2_BASE+LPC17_CAN_SR_OFFSET)
-#define LPC17_CAN2_RFS (LPC17_CAN2_BASE+LPC17_CAN_RFS_OFFSET)
-#define LPC17_CAN2_RID (LPC17_CAN2_BASE+LPC17_CAN_RID_OFFSET)
-#define LPC17_CAN2_RDA (LPC17_CAN2_BASE+LPC17_CAN_RDA_OFFSET)
-#define LPC17_CAN2_RDB (LPC17_CAN2_BASE+LPC17_CAN_RDB_OFFSET)
-#define LPC17_CAN2_TFI1 (LPC17_CAN2_BASE+LPC17_CAN_TFI1_OFFSET)
-#define LPC17_CAN2_TID1 (LPC17_CAN2_BASE+LPC17_CAN_TID1_OFFSET)
-#define LPC17_CAN2_TDA1 (LPC17_CAN2_BASE+LPC17_CAN_TDA1_OFFSET)
-#define LPC17_CAN2_TDB1 (LPC17_CAN2_BASE+LPC17_CAN_TDB1_OFFSET)
-#define LPC17_CAN2_TFI2 (LPC17_CAN2_BASE+LPC17_CAN_TFI2_OFFSET)
-#define LPC17_CAN2_TID2 (LPC17_CAN2_BASE+LPC17_CAN_TID2_OFFSET)
-#define LPC17_CAN2_TDA2 (LPC17_CAN2_BASE+LPC17_CAN_TDA2_OFFSET)
-#define LPC17_CAN2_TDB2 (LPC17_CAN2_BASE+LPC17_CAN_TDB2_OFFSET)
-#define LPC17_CAN2_TFI3 (LPC17_CAN2_BASE+LPC17_CAN_TFI3_OFFSET)
-#define LPC17_CAN2_TID3 (LPC17_CAN2_BASE+LPC17_CAN_TID3_OFFSET)
-#define LPC17_CAN2_TDA3 (LPC17_CAN2_BASE+LPC17_CAN_TDA3_OFFSET)
-#define LPC17_CAN2_TDB3 (LPC17_CAN2_BASE+LPC17_CAN_TDB3_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* CAN acceptance filter registers */
-/* Acceptance Filter Register */
-
-#define CANAF_AFMR_ACCOFF (1 << 0) /* Bit 0: AF non-operational; All RX messages ignored */
-#define CANAF_AFMR_ACCBP (1 << 1) /* Bit 1: AF bypass: All RX messages accepted */
-#define CANAF_AFMR_EFCAN (1 << 2) /* Bit 2: Enable Full CAN mode */
- /* Bits 3-31: Reserved */
-/* Standard Frame Individual Start Address Register */
- /* Bits 0-1: Reserved */
-#define CANAF_SFFSA_SHIFT (2) /* Bits 2-10: Address of Standard Identifiers in AF Lookup RAM */
-#define CANAF_SFFSA_MASK (0x01ff << CANAF_SFFSA_SHIFT)
- /* Bits 11-31: Reserved */
-/* Standard Frame Group Start Address Register */
- /* Bits 0-1: Reserved */
-#define CANAF_SFFGRPSA_SHIFT (2) /* Bits 2-10: Address of grouped Standard Identifiers in AF Lookup RAM */
-#define CANAF_SFFGRPSA_MASK (0x01ff << CANAF_SFFGRPSA_SHIFT)
- /* Bits 11-31: Reserved */
-/* Extended Frame Start Address Register */
- /* Bits 0-1: Reserved */
-#define CANAF_EFFSA_SHIFT (2) /* Bits 2-10: Address of Extended Identifiers in AF Lookup RAM */
-#define CANAF_EFFSA_MASK (0x01ff << CANAF_EFFSA_SHIFT)
- /* Bits 11-31: Reserved */
-/* Extended Frame Group Start Address Register */
- /* Bits 0-1: Reserved */
-#define CANAF_EFFGRPSA_SHIFT (2) /* Bits 2-10: Address of grouped Extended Identifiers in AF Lookup RAM */
-#define CANAF_EFFGRPSA_MASK (0x01ff << CANAF_EFFGRPSA_SHIFT)
- /* Bits 11-31: Reserved */
-/* End of AF Tables register */
- /* Bits 0-1: Reserved */
-#define CANAF_EOT_SHIFT (2) /* Bits 2-10: Last active address in last active AF table */
-#define CANAF_EOT_MASK (0x01ff << CANAF_EOT_SHIFT)
- /* Bits 11-31: Reserved */
-/* LUT Error Address register */
- /* Bits 0-1: Reserved */
-#define CANAF_LUTERRAD_SHIFT (2) /* Bits 2-10: Address in AF Lookup RAM of error */
-#define CANAF_LUTERRAD_MASK (0x01ff << CANAF_EOT_SHIFT)
- /* Bits 11-31: Reserved */
-/* LUT Error Register */
-
-#define CANAF_LUTERR_LUTERR (1 << 0) /* Bit 0: AF error in AF RAM tables */
- /* Bits 1-31: Reserved */
-/* FullCAN interrupt enable register */
-
-#define CANAF_FCANIE_FCANIE (1 << 0) /* Bit 0: Global FullCAN Interrupt Enable */
- /* Bits 1-31: Reserved */
-
-/* FullCAN interrupt and capture register 0 */
-
-#define CANAF_FCANIC0_INTPND(n) (1 << (n)) /* n=0,1,2,... 31 */
-
-/* FullCAN interrupt and capture register 1 */
-
-#define CANAF_FCANIC1_INTPND(n) (1 << ((n)-32)) /* n=32,33,...63 */
-
-/* Central CAN registers */
-/* CAN Central Transmit Status Register */
-
-#define CAN_TXSR_TS1 (1 << 0) /* Bit 0: CAN1 sending */
-#define CAN_TXSR_TS2 (1 << 1) /* Bit 1: CAN2 sending */
- /* Bits 2-7: Reserved */
-#define CAN_TXSR_TBS1 (1 << 8) /* Bit 8: All 3 CAN1 TX buffers available */
-#define CAN_TXSR_TBS2 (1 << 9) /* Bit 9: All 3 CAN2 TX buffers available */
- /* Bits 10-15: Reserved */
-#define CAN_TXSR_TCS1 (1 << 16) /* Bit 16: All CAN1 xmissions completed */
-#define CAN_TXSR_TCS2 (1 << 17) /* Bit 17: All CAN2 xmissions completed */
- /* Bits 18-31: Reserved */
-/* CAN Central Receive Status Register */
-
-#define CAN_RXSR_RS1 (1 << 0) /* Bit 0: CAN1 receiving */
-#define CAN_RXSR_RS2 (1 << 1) /* Bit 1: CAN2 receiving */
- /* Bits 2-7: Reserved */
-#define CAN_RXSR_RB1 (1 << 8) /* Bit 8: CAN1 received message available */
-#define CAN_RXSR_RB2 (1 << 9) /* Bit 9: CAN2 received message available */
- /* Bits 10-15: Reserved */
-#define CAN_RXSR_DOS1 (1 << 16) /* Bit 16: All CAN1 message lost */
-#define CAN_RXSR_DOS2 (1 << 17) /* Bit 17: All CAN2 message lost */
- /* Bits 18-31: Reserved */
-/* CAN Central Miscellaneous Register */
-
-#define CAN_MSR_E1 (1 << 0) /* Bit 0: CAN1 error counters at limit */
-#define CAN_MSR_E2 (1 << 1) /* Bit 1: CAN2 error counters at limit */
- /* Bits 2-7: Reserved */
-#define CAN_MSR_BS1 (1 << 8) /* Bit 8: CAN1 busy */
-#define CAN_MSR_BS2 (1 << 9) /* Bit 7: CAN2 busy */
- /* Bits 10-31: Reserved */
-/* CAN1/2 registers */
-/* CAN operating mode */
-
-#define CAN_MOD_RM (1 << 0) /* Bit 0: Reset Mode */
-#define CAN_MOD_LOM (1 << 1) /* Bit 1: Listen Only Mode */
-#define CAN_MOD_STM (1 << 2) /* Bit 2: Self Test Mode */
-#define CAN_MOD_TPM (1 << 3) /* Bit 3: Transmit Priority Mode */
-#define CAN_MOD_SM (1 << 4) /* Bit 4: Sleep Mode */
-#define CAN_MOD_RPM (1 << 5) /* Bit 5: Receive Polarity Mode */
- /* Bit 6: Reserved */
-#define CAN_MOD_TM (1 << 7) /* Bit 7: Test Mode */
- /* Bits 8-31: Reserved */
-/* Command bits */
-
-#define CAN_CMR_TR (1 << 0) /* Bit 0: Transmission Request */
-#define CAN_CMR_AT (1 << 1) /* Bit 1: Abort Transmission */
-#define CAN_CMR_RRB (1 << 2) /* Bit 2: Release Receive Buffer */
-#define CAN_CMR_CDO (1 << 3) /* Bit 3: Clear Data Overrun */
-#define CAN_CMR_SRR (1 << 4) /* Bit 4: Self Reception Request */
-#define CAN_CMR_STB1 (1 << 5) /* Bit 5: Select Tx Buffer 1 */
-#define CAN_CMR_STB2 (1 << 6) /* Bit 6: Select Tx Buffer 2 */
-#define CAN_CMR_STB3 (1 << 7) /* Bit 7: Select Tx Buffer 3 */
- /* Bits 8-31: Reserved */
-/* Controller Status and Error Counters */
-
-#define CAN_GSR_RBS (1 << 0) /* Bit 0: Receive Buffer Status */
-#define CAN_GSR_DOS (1 << 1) /* Bit 1: Data Overrun Status */
-#define CAN_GSR_TBS (1 << 2) /* Bit 2: Transmit Buffer Status */
-#define CAN_GSR_TCS (1 << 3) /* Bit 3: Transmit Complete Status */
-#define CAN_GSR_RS (1 << 4) /* Bit 4: Receive Status */
-#define CAN_GSR_TS (1 << 5) /* Bit 5: Transmit Status */
-#define CAN_GSR_ES (1 << 6) /* Bit 6: Error Status */
-#define CAN_GSR_BS (1 << 7) /* Bit 7: Bus Status */
- /* Bits 8-15: Reserved */
-#define CAN_GSR_RXERR_SHIFT (16) /* Bits 16-23: Rx Error Counter */
-#define CAN_GSR_RXERR_MASK (0xff << CAN_GSR_RXERR_SHIFT)
-#define CAN_GSR_TXERR_SHIFT (24) /* Bits 24-31: Tx Error Counter */
-#define CAN_GSR_TXERR_MASK (0xff << CAN_GSR_TXERR_SHIFT)
+ ****************************************************************************/
-/* Interrupt and capture register */
-
-#define CAN_ICR_RI (1 << 0) /* Bit 0: Receive Interrupt */
-#define CAN_ICR_TI1 (1 << 1) /* Bit 1: Transmit Interrupt 1 */
-#define CAN_ICR_EI (1 << 2) /* Bit 2: Error Warning Interrupt */
-#define CAN_ICR_DOI (1 << 3) /* Bit 3: Data Overrun Interrupt */
-#define CAN_ICR_WUI (1 << 4) /* Bit 4: Wake-Up Interrupt */
-#define CAN_ICR_EPI (1 << 5) /* Bit 5: Error Passive Interrupt */
-#define CAN_ICR_ALI (1 << 6) /* Bit 6: Arbitration Lost Interrupt */
-#define CAN_ICR_BEI (1 << 7) /* Bit 7: Bus Error Interrupt */
-#define CAN_ICR_IDI (1 << 8) /* Bit 8: ID Ready Interrupt */
-#define CAN_ICR_TI2 (1 << 9) /* Bit 9: Transmit Interrupt 2 */
-#define CAN_ICR_TI3 (1 << 10) /* Bit 10: Transmit Interrupt 3 */
- /* Bits 11-15: Reserved */
-#define CAN_ICR_ERRBIT_SHIFT (16) /* Bits 16-20: Error Code Capture */
-#define CAN_ICR_ERRBIT_MASK (0x1f << CAN_ICR_ERRBIT_SHIFT)
-# define CAN_ICR_ERRBIT_SOF (3 << CAN_ICR_ERRBIT_SHIFT) /* Start of Frame */
-# define CAN_ICR_ERRBIT_ID28 (2 << CAN_ICR_ERRBIT_SHIFT) /* ID28 ... ID21 */
-# define CAN_ICR_ERRBIT_SRTR (4 << CAN_ICR_ERRBIT_SHIFT) /* SRTR Bit */
-# define CAN_ICR_ERRBIT_IDE (5 << CAN_ICR_ERRBIT_SHIFT) /* DE bit */
-# define CAN_ICR_ERRBIT_ID20 (6 << CAN_ICR_ERRBIT_SHIFT) /* ID20 ... ID18 */
-# define CAN_ICR_ERRBIT_ID17 (7 << CAN_ICR_ERRBIT_SHIFT) /* ID17 ... 13 */
-# define CAN_ICR_ERRBIT_CRC (8 << CAN_ICR_ERRBIT_SHIFT) /* CRC Sequence */
-# define CAN_ICR_ERRBIT_DATA (10 << CAN_ICR_ERRBIT_SHIFT) /* Data Field */
-# define CAN_ICR_ERRBIT_LEN (11 << CAN_ICR_ERRBIT_SHIFT) /* Data Length Code */
-# define CAN_ICR_ERRBIT_ RTR (12 << CAN_ICR_ERRBIT_SHIFT) /* RTR Bit */
-# define CAN_ICR_ERRBIT_ID4 (14 << CAN_ICR_ERRBIT_SHIFT) /* ID4 ... ID0 */
-# define CAN_ICR_ERRBIT_ID12 (15 << CAN_ICR_ERRBIT_SHIFT) /* ID12 ... ID5 */
-# define CAN_ICR_ERRBIT_AERR (17 << CAN_ICR_ERRBIT_SHIFT) /* Active Error Flag */
-# define CAN_ICR_ERRBIT_INTERMSN (18 << CAN_ICR_ERRBIT_SHIFT) /* Intermission */
-# define CAN_ICR_ERRBIT_DOM (19 << CAN_ICR_ERRBIT_SHIFT) /* Tolerate Dominant Bits */
-# define CAN_ICR_ERRBIT_PERR (22 << CAN_ICR_ERRBIT_SHIFT) /* Passive Error Flag */
-# define CAN_ICR_ERRBIT_ERRDLM (23 << CAN_ICR_ERRBIT_SHIFT) /* Error Delimiter */
-# define CAN_ICR_ERRBIT_CRCDLM (24 << CAN_ICR_ERRBIT_SHIFT) /* CRC Delimiter */
-# define CAN_ICR_ERRBIT_ACKSLT (25 << CAN_ICR_ERRBIT_SHIFT) /* Acknowledge Slot */
-# define CAN_ICR_ERRBIT_EOF (26 << CAN_ICR_ERRBIT_SHIFT) /* End of Frame */
-# define CAN_ICR_ERRBIT_ACKDLM (27 << CAN_ICR_ERRBIT_SHIFT) /* Acknowledge Delimiter */
-# define CAN_ICR_ERRBIT_OVLD (28 << CAN_ICR_ERRBIT_SHIFT) /* Overload flag */
-#define CAN_ICR_ERRDIR (1 << 21) /* Bit 21: Direction bit at time of error */
-#define CAN_ICR_ERRC_SHIFT (22) /* Bits 22-23: Type of error */
-#define CAN_ICR_ERRC_MASK (3 << CAN_ICR_ERRC_SHIFT)
-# define CAN_ICR_ERRC_BIT (0 << CAN_ICR_ERRC_SHIFT)
-# define CAN_ICR_ERRC_FORM (1 << CAN_ICR_ERRC_SHIFT)
-# define CAN_ICR_ERRC_STUFF (2 << CAN_ICR_ERRC_SHIFT)
-# define CAN_ICR_ERRC_OTHER (3 << CAN_ICR_ERRC_SHIFT)
-#define CAN_ICR_ALCBIT_SHIFT (24) /* Bits 24-31: Bit number within frame */
-#define CAN_ICR_ALCBIT_MASK (0xff << CAN_ICR_ALCBIT_SHIFT)
-
-/* Interrupt Enable */
-
-#define CAN_IER_RIE (1 << 0) /* Bit 0: Receiver Interrupt Enable */
-#define CAN_IER_TIE1 (1 << 1) /* Bit 1: Transmit Interrupt Enable for Buffer1 */
-#define CAN_IER_EIE (1 << 2) /* Bit 2: Error Warning Interrupt Enable */
-#define CAN_IER_DOIE (1 << 3) /* Bit 3: Data Overrun Interrupt Enable */
-#define CAN_IER_WUIE (1 << 4) /* Bit 4: Wake-Up Interrupt Enable */
-#define CAN_IER_EPIE (1 << 5) /* Bit 5: Error Passive Interrupt Enable */
-#define CAN_IER_ALIE (1 << 6) /* Bit 6: Arbitration Lost Interrupt Enable */
-#define CAN_IER_BEIE (1 << 7) /* Bit 7: Bus Error Interrupt */
-#define CAN_IER_IDIE (1 << 8) /* Bit 8: ID Ready Interrupt Enable */
-#define CAN_IER_TIE2 (1 << 9) /* Bit 9: Transmit Interrupt Enable for Buffer2 */
-#define CAN_IER_TIE3 (1 << 10) /* Bit 10: Transmit Interrupt Enable for Buffer3 */
- /* Bits 11-31: Reserved */
-/* Bus Timing */
-
-#define CAN_BTR_BRP_SHIFT (0) /* Bits 0-9: Baud Rate Prescaler */
-#define CAN_BTR_BRP_MASK (0x3ff << CAN_BTR_BRP_SHIFT)
- /* Bits 10-13: Reserved */
-#define CAN_BTR_SJW_SHIFT (14) /* Bits 14-15: Synchronization Jump Width */
-#define CAN_BTR_SJW_MASK (3 << CAN_BTR_SJW_SHIFT)
-#define CAN_BTR_TSEG1_SHIFT (16) /* Bits 16-19: Sync to sample delay */
-#define CAN_BTR_TSEG1_MASK (15 << CAN_BTR_TSEG1_SHIFT)
-#define CAN_BTR_TSEG2_SHIFT (20) /* Bits 20-22: smaple to next delay */
-#define CAN_BTR_TSEG2_MASK (7 << CAN_BTR_TSEG2_SHIFT)
-#define CAN_BTR_SAM (1 << 23) /* Bit 23: Sampling */
- /* Bits 24-31: Reserved */
-
-#define CAN_BTR_BRP_MAX (1024) /* Maximum BTR value (without decrement) */
-#define CAN_BTR_TSEG1_MAX (16) /* Maximum TSEG1 value (without decrement) */
-#define CAN_BTR_TSEG2_MAX (8) /* Maximum TSEG2 value (without decrement) */
-
-/* Error Warning Limit */
-
-#define CAN_EWL_SHIFT (0) /* Bits 0-7: Error warning limit */
-#define CAN_EWL_MASK (0xff << CAN_EWL_SHIFT)
- /* Bits 8-31: Reserved */
-/* Status Register */
-
-#define CAN_SR_RBS1 (1 << 0) /* Bit 0: Receive Buffer Status */
-#define CAN_SR_DOS1 (1 << 1) /* Bit 1: Data Overrun Status */
-#define CAN_SR_TBS1 (1 << 2) /* Bit 2: Transmit Buffer Status 1 */
-#define CAN_SR_TCS1 (1 << 3) /* Bit 3: Transmission Complete Status */
-#define CAN_SR_RS1 (1 << 4) /* Bit 4: Receive Status */
-#define CAN_SR_TS1 (1 << 5) /* Bit 5: Transmit Status 1 */
-#define CAN_SR_ES1 (1 << 6) /* Bit 6: Error Status */
-#define CAN_SR_BS1 (1 << 7) /* Bit 7: Bus Status */
-#define CAN_SR_RBS2 (1 << 8) /* Bit 8: Receive Buffer Status */
-#define CAN_SR_DOS2 (1 << 9) /* Bit 9: Data Overrun Status */
-#define CAN_SR_TBS2 (1 << 10) /* Bit 10: Transmit Buffer Status 2 */
-#define CAN_SR_TCS2 (1 << 11) /* Bit 11: Transmission Complete Status */
-#define CAN_SR_RS2 (1 << 12) /* Bit 12: Receive Status */
-#define CAN_SR_TS2 (1 << 13) /* Bit 13: Transmit Status 2 */
-#define CAN_SR_ES2 (1 << 14) /* Bit 14: Error Status */
-#define CAN_SR_BS2 (1 << 15) /* Bit 15: Bus Status */
-#define CAN_SR_RBS3 (1 << 16) /* Bit 16: Receive Buffer Status */
-#define CAN_SR_DOS3 (1 << 17) /* Bit 17: Data Overrun Status */
-#define CAN_SR_TBS3 (1 << 18) /* Bit 18: Transmit Buffer Status 3 */
-#define CAN_SR_TCS3 (1 << 19) /* Bit 19: Transmission Complete Status */
-#define CAN_SR_RS3 (1 << 20) /* Bit 20: Receive Status */
-#define CAN_SR_TS3 (1 << 21) /* Bit 21: Transmit Status 3 */
-#define CAN_SR_ES3 (1 << 22) /* Bit 22: Error Status */
-#define CAN_SR_BS3 (1 << 23) /* Bit 23: Bus Status */
- /* Bits 24-31: Reserved */
-/* Receive frame status */
-
-#define CAN_RFS_ID_SHIFT (0) /* Bits 0-9: ID Index */
-#define CAN_RFS_ID_MASK (0x03ff << CAN_RFS_ID_SHIFT)
-#define CAN_RFS_BP (1 << 10) /* Bit 10: Received in AF Bypass mode */
- /* Bits 11-15: Reserved */
-#define CAN_RFS_DLC_SHIFT (16) /* Bits 16-19: Message Data Length Code (DLC) */
-#define CAN_RFS_DLC_MASK (15 << CAN_RFS_DLC_SHIFT)
- /* Bits 20-29: Reserved */
-#define CAN_RFS_RTR (1 << 30) /* Bit 30: Message Remote Transmission Request */
-#define CAN_RFS_FF (1 << 31) /* Bit 31: Message 29-bit vs 11-bit ID */
-
-/* Received Identifier */
-
-#define CAN_RID_ID11_MASK (0x7ff) /* Bits 0-10: 11-bit Identifier (FF=0) */
- /* Bits 11-31: Reserved */
-#define CAN_RID_ID29_MASK (0x1fffffff) /* Bits 0-28: 29-bit Identifiter (FF=1) */
- /* Bits 29-31: Reserved */
-/* Received data bytes 1-4 */
-
-#define CAN_RDA_DATA1_SHIFT (0) /* Bits 0-7: If CANRFS >= 1 */
-#define CAN_RDA_DATA1_MASK (0x0ff << CAN_RDA_DATA1_SHIFT)
-#define CAN_RDA_DATA2_SHIFT (8) /* Bits 8-15: If CANRFS >= 2 */
-#define CAN_RDA_DATA2_MASK (0x0ff << CAN_RDA_DATA2_SHIFT)
-#define CAN_RDA_DATA3_SHIFT (16) /* Bits 16-23: If CANRFS >= 3 */
-#define CAN_RDA_DATA3_MASK (0x0ff << CAN_RDA_DATA3_SHIFT)
-#define CAN_RDA_DATA4_SHIFT (24) /* Bits 24-31: If CANRFS >= 4 */
-#define CAN_RDA_DATA4_MASK (0x0ff << CAN_RDA_DATA4_SHIFT)
-
-/* Received data bytes 5-8 */
-
-#define CAN_RDB_DATA5_SHIFT (0) /* Bits 0-7: If CANRFS >= 5 */
-#define CAN_RDB_DATA5_MASK (0x0ff << CAN_RDB_DATA5_SHIFT)
-#define CAN_RDB_DATA6_SHIFT (8) /* Bits 8-15: If CANRFS >= 6 */
-#define CAN_RDB_DATA6_MASK (0x0ff << CAN_RDB_DATA6_SHIFT)
-#define CAN_RDB_DATA7_SHIFT (16) /* Bits 16-23: If CANRFS >= 7 */
-#define CAN_RDB_DATA7_MASK (0x0ff << CAN_RDB_DATA7_SHIFT)
-#define CAN_RDB_DATA8_SHIFT (24) /* Bits 24-31: If CANRFS >= 8 */
-#define CAN_RDB_DATA8_MASK (0x0ff << CAN_RDB_DATA8_SHIFT)
-
-/* Transmit frame info (Tx Buffer 1), Transmit frame info (Tx Buffer 2), and
- * Transmit frame info (Tx Buffer 3) common bit field definitions
- */
-
-#define CAN_TFI_PRIO_SHIFT (0) /* Bits 0-7: TX buffer priority */
-#define CAN_TFI_PRIO_MASK (0xff << CAN_TFI_PRIO_SHIFT)
- /* Bits 8-15: Reserved */
-#define CAN_TFI_DLC_SHIFT (16) /* Bits 16-19: TX Data Length Code */
-#define CAN_TFI_DLC_MASK (15 << CAN_TFI_DLC_SHIFT)
- /* Bits 20-29: Reserved */
-#define CAN_TFI_RTR (1 << 30) /* Bit 30: TX RTR bit */
-#define CAN_TFI_FF (1 << 31) /* Bit 31: Message 29-bit vs 11-bit ID */
-
-/* Transmit Identifier (Tx Buffer 1), Transmit Identifier (Tx Buffer 2), and
- * Transmit Identifier (Tx Buffer 3) common bit field definitions.
- */
-
-#define CAN_TID_ID11_MASK (0x7ff) /* Bits 0-10: 11-bit Identifier (FF=0) */
- /* Bits 11-31: Reserved */
-#define CAN_TID_ID29_MASK (0x1fffffff) /* Bits 0-28: 29-bit Identifiter (FF=1) */
- /* Bits 29-31: Reserved */
-
-/* Transmit data bytes 1-4 (Tx Buffer 1), Transmit data bytes 1-4 (Tx Buffer 2), and
- * Transmit data bytes 1-4 (Tx Buffer 3) common bit field definitions.
- */
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
-#define CAN_TDA_DATA1_SHIFT (0) /* Bits 0-7: RTR=0 && DLC >= 1 */
-#define CAN_TDA_DATA1_MASK (0x0ff << CAN_TDA_DATA1_SHIFT)
-#define CAN_TDA_DATA2_SHIFT (8) /* Bits 8-15: RTR=0 && DLC >= 2 */
-#define CAN_TDA_DATA2_MASK (0x0ff << CAN_TDA_DATA2_SHIFT)
-#define CAN_TDA_DATA3_SHIFT (16) /* Bits 16-23: RTR=0 && DLC >= 3 */
-#define CAN_TDA_DATA3_MASK (0x0ff << CAN_TDA_DATA3_SHIFT)
-#define CAN_TDA_DATA4_SHIFT (24) /* Bits 24-31: RTR=0 && DLC >= 4 */
-#define CAN_TDA_DATA4_MASK (0x0ff << CAN_TDA_DATA4_SHIFT)
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
-/* Transmit data bytes 5-8 (Tx Buffer 1), Transmit data bytes 5-8 (Tx Buffer 2), and
- * Transmit data bytes 5-8 (Tx Buffer 3) common bit field definitions.
- */
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
-#define CAN_RDB_DATA5_SHIFT (0) /* Bits 0-7: RTR=0 && DLC >= 5 */
-#define CAN_RDB_DATA5_MASK (0x0ff << CAN_RDB_DATA5_SHIFT)
-#define CAN_RDB_DATA6_SHIFT (8) /* Bits 8-15: RTR=0 && DLC >= 6 */
-#define CAN_RDB_DATA6_MASK (0x0ff << CAN_RDB_DATA6_SHIFT)
-#define CAN_RDB_DATA7_SHIFT (16) /* Bits 16-23: RTR=0 && DLC >= 7 */
-#define CAN_RDB_DATA7_MASK (0x0ff << CAN_RDB_DATA7_SHIFT)
-#define CAN_RDB_DATA8_SHIFT (24) /* Bits 24-31: RTR=0 && DLC >= 8 */
-#define CAN_RDB_DATA8_MASK (0x0ff << CAN_RDB_DATA8_SHIFT)
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
-/************************************************************************************
- * Public Types
- ************************************************************************************/
+/****************************************************************************
+ * Name: lpc17_caninitialize
+ *
+ * Description:
+ * Initialize the selected can port
+ *
+ * Input Parameter:
+ * Port number (for hardware that has mutiple can interfaces)
+ *
+ * Returned Value:
+ * Valid can device structure reference on succcess; a NULL on failure
+ *
+ ****************************************************************************/
-/************************************************************************************
- * Public Data
- ************************************************************************************/
+#if defined(CONFIG_CAN) && (defined(CONFIG_LPC17_CAN1) || defined(CONFIG_LPC17_CAN2))
+struct can_dev_s;
+FAR struct can_dev_s *lpc17_caninitialize(int port);
+#endif
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_CAN_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c b/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c
index 635090e9f..aba2079e4 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c
@@ -48,8 +48,8 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
-#include "lpc17_syscon.h"
+#include "lpc17_clockconfig.h"
+#include "chip/lpc17_syscon.h"
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.h b/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.h
new file mode 100644
index 000000000..ffc9fa88d
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.h
@@ -0,0 +1,84 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_clockconfig.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_LPC17XX_LPC17_CLOCKCONFIG_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_CLOCKCONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc17_clockconfig
+ *
+ * Description:
+ * Called to initialize the LPC17XX. This does whatever setup is needed to put the
+ * MCU in a usable state. This includes the initialization of clocking using the
+ * settings in board.h.
+ *
+ ************************************************************************************/
+
+void lpc17_clockconfig(void);
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_CLOCKCONFIG_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_clrpend.c b/nuttx/arch/arm/src/lpc17xx/lpc17_clrpend.c
index 242f7ac4f..dcea79e7b 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_clrpend.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_clrpend.c
@@ -44,7 +44,7 @@
#include "nvic.h"
#include "up_arch.h"
-#include "lpc17_internal.h"
+#include "lpc17_clrpend.h"
/****************************************************************************
* Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_clrpend.h b/nuttx/arch/arm/src/lpc17xx/lpc17_clrpend.h
new file mode 100644
index 000000000..d7bf5b90d
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_clrpend.h
@@ -0,0 +1,84 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_clrpend.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_LPC17XX_LPC17_CLRPEND_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_CLRPEND_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc17_clrpend
+ *
+ * Description:
+ * Clear a pending interrupt at the NVIC. This does not seem to be required
+ * for most interrupts. Don't know why... but the LPC1766 Ethernet EMAC
+ * interrupt definitely needs it!
+ *
+ ************************************************************************************/
+
+void lpc17_clrpend(int irq);
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_CLRPEND_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c b/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c
index 13ac212f6..87f49ba33 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c
@@ -60,9 +60,8 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
-#include "lpc17_syscon.h"
-#include "lpc17_pinconn.h"
+
+#include "chip/lpc17_syscon.h"
#include "lpc17_dac.h"
#ifdef CONFIG_LPC17_DAC
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_dac.h b/nuttx/arch/arm/src/lpc17xx/lpc17_dac.h
index a35e16eae..ac8477507 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_dac.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_dac.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_dac.h
*
- * 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
@@ -41,47 +41,12 @@
************************************************************************************/
#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_dac.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-
-#define LPC17_DAC_CR_OFFSET 0x0000 /* D/A Converter Register */
-#define LPC17_DAC_CTRL_OFFSET 0x0004 /* DAC Control register */
-#define LPC17_DAC_CNTVAL_OFFSET 0x0008 /* DAC Counter Value register */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_DAC_CR (LPC17_DAC_BASE+LPC17_DAC_CR_OFFSET)
-#define LPC17_DAC_CTRL (LPC17_DAC_BASE+LPC17_DAC_CTRL_OFFSET)
-#define LPC17_DAC_CNTVAL (LPC17_DAC_BASE+LPC17_DAC_CNTVAL_OFFSET)
-
-/* Register bit definitions *********************************************************/
-
-/* D/A Converter Register */
- /* Bits 0-5: Reserved */
-#define DAC_CR_VALUE_SHIFT (6) /* Bits 6-15: Controls voltage on the AOUT pin */
-#define DAC_CR_VALUE_MASK (0x3ff << DAC_CR_VALUE_SHIFT)
-#define DAC_CR_BIAS (1 << 16) /* Bit 16: Controls DAC settling time */
- /* Bits 17-31: Reserved */
-/* DAC Control register */
-
-#define DAC_CTRL_INTDMAREQ (1 << 0) /* Bit 0: Timer timed out */
-#define DAC_CTRL_DBLBUFEN (1 << 1) /* Bit 1: Enable DACR double-buffering */
-#define DAC_CTRL_CNTEN (1 << 2) /* Bit 2: Enable timeout counter */
-#define DAC_CTRL_DMAEN (1 << 3) /* Bit 3: Enable DMA access */
- /* Bits 4-31: Reserved */
-/* DAC Counter Value register */
-
-#define DAC_CNTVAL_SHIFT (0) /* Bits 0-15: Reload value for DAC interrupt/DMA timer */
-#define DAC_CNTVAL_MASK (0xffff << DAC_CNTVAL_SHIFT)
- /* Bits 8-31: Reserved */
-
/************************************************************************************
* Public Types
************************************************************************************/
@@ -90,8 +55,34 @@
* Public Data
************************************************************************************/
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
/************************************************************************************
* Public Functions
************************************************************************************/
+/****************************************************************************
+ * Name: lpc17_dacinitialize
+ *
+ * Description:
+ * Initialize the DAC
+ *
+ * Returned Value:
+ * Valid dac device structure reference on succcess; a NULL on failure
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_LPC17_DAC
+FAR struct dac_dev_s *lpc17_dacinitialize(void);
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_DAC_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_emacram.h b/nuttx/arch/arm/src/lpc17xx/lpc17_emacram.h
index 700ad7ec3..84a7ebb15 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_emacram.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_emacram.h
@@ -42,7 +42,7 @@
#include <nuttx/config.h>
#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
index 47a22ec2e..bf6d18287 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
@@ -57,12 +57,13 @@
#include <nuttx/net/uip/uip-arp.h>
#include <nuttx/net/uip/uip-arch.h>
-#include "chip.h"
#include "up_arch.h"
-#include "lpc17_syscon.h"
+#include "chip.h"
+#include "chip/lpc17_syscon.h"
+#include "lpc17_gpio.h"
#include "lpc17_ethernet.h"
#include "lpc17_emacram.h"
-#include "lpc17_internal.h"
+#include "lpc17_clrpend.h"
#include <arch/board/board.h>
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h
index f48c6d953..77ce1cc0f 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_ethernet.h
*
- * 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
@@ -41,547 +41,12 @@
************************************************************************************/
#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_ethernet.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-/* MAC registers */
-
-#define LPC17_ETH_MAC1_OFFSET 0x0000 /* MAC configuration register 1 */
-#define LPC17_ETH_MAC2_OFFSET 0x0004 /* MAC configuration register 2 */
-#define LPC17_ETH_IPGT_OFFSET 0x0008 /* Back-to-Back Inter-Packet-Gap register */
-#define LPC17_ETH_IPGR_OFFSET 0x000c /* Non Back-to-Back Inter-Packet-Gap register */
-#define LPC17_ETH_CLRT_OFFSET 0x0010 /* Collision window / Retry register */
-#define LPC17_ETH_MAXF_OFFSET 0x0014 /* Maximum Frame register */
-#define LPC17_ETH_SUPP_OFFSET 0x0018 /* PHY Support register */
-#define LPC17_ETH_TEST_OFFSET 0x001c /* Test register */
-#define LPC17_ETH_MCFG_OFFSET 0x0020 /* MII Mgmt Configuration register */
-#define LPC17_ETH_MCMD_OFFSET 0x0024 /* MII Mgmt Command register */
-#define LPC17_ETH_MADR_OFFSET 0x0028 /* MII Mgmt Address register */
-#define LPC17_ETH_MWTD_OFFSET 0x002c /* MII Mgmt Write Data register */
-#define LPC17_ETH_MRDD_OFFSET 0x0030 /* MII Mgmt Read Data register */
-#define LPC17_ETH_MIND_OFFSET 0x0034 /* MII Mgmt Indicators register */
-#define LPC17_ETH_SA0_OFFSET 0x0040 /* Station Address 0 register */
-#define LPC17_ETH_SA1_OFFSET 0x0044 /* Station Address 1 register */
-#define LPC17_ETH_SA2_OFFSET 0x0048 /* Station Address 2 register */
-
-/* Control registers */
-
-#define LPC17_ETH_CMD_OFFSET 0x0100 /* Command register */
-#define LPC17_ETH_STAT_OFFSET 0x0104 /* Status register */
-#define LPC17_ETH_RXDESC_OFFSET 0x0108 /* Receive descriptor base address register */
-#define LPC17_ETH_RXSTAT_OFFSET 0x010c /* Receive status base address register */
-#define LPC17_ETH_RXDESCNO_OFFSET 0x0110 /* Receive number of descriptors register */
-#define LPC17_ETH_RXPRODIDX_OFFSET 0x0114 /* Receive produce index register */
-#define LPC17_ETH_RXCONSIDX_OFFSET 0x0118 /* Receive consume index register */
-#define LPC17_ETH_TXDESC_OFFSET 0x011c /* Transmit descriptor base address register */
-#define LPC17_ETH_TXSTAT_OFFSET 0x0120 /* Transmit status base address register */
-#define LPC17_ETH_TXDESCRNO_OFFSET 0x0124 /* Transmit number of descriptors register */
-#define LPC17_ETH_TXPRODIDX_OFFSET 0x0128 /* Transmit produce index register */
-#define LPC17_ETH_TXCONSIDX_OFFSET 0x012c /* Transmit consume index register */
-#define LPC17_ETH_TSV0_OFFSET 0x0158 /* Transmit status vector 0 register */
-#define LPC17_ETH_TSV1_OFFSET 0x015c /* Transmit status vector 1 register */
-#define LPC17_ETH_RSV_OFFSET 0x0160 /* Receive status vector register */
-#define LPC17_ETH_FCCNTR_OFFSET 0x0170 /* Flow control counter register */
-#define LPC17_ETH_FCSTAT_OFFSET 0x0174 /* Flow control status register */
-
-/* Rx filter registers */
-
-#define LPC17_ETH_RXFLCTRL_OFFSET 0x0200 /* Receive filter control register */
-#define LPC17_ETH_RXFLWOLST_OFFSET 0x0204 /* Receive filter WoL status register */
-#define LPC17_ETH_RXFLWOLCLR_OFFSET 0x0208 /* Receive filter WoL clear register */
-#define LPC17_ETH_HASHFLL_OFFSET 0x0210 /* Hash filter table LSBs register */
-#define LPC17_ETH_HASHFLH_OFFSET 0x0214 /* Hash filter table MSBs register */
-
-/* Module control registers */
-
-#define LPC17_ETH_INTST_OFFSET 0x0fe0 /* Interrupt status register */
-#define LPC17_ETH_INTEN_OFFSET 0x0fe4 /* Interrupt enable register */
-#define LPC17_ETH_INTCLR_OFFSET 0x0fe8 /* Interrupt clear register */
-#define LPC17_ETH_INTSET_OFFSET 0x0fec /* Interrupt set register */
-#define LPC17_ETH_PWRDOWN_OFFSET 0x0ff4 /* Power-down register */
-
-/* Register addresses ***************************************************************/
-/* MAC registers */
-
-#define LPC17_ETH_MAC1 (LPC17_ETH_BASE+LPC17_ETH_MAC1_OFFSET)
-#define LPC17_ETH_MAC2 (LPC17_ETH_BASE+LPC17_ETH_MAC2_OFFSET)
-#define LPC17_ETH_IPGT (LPC17_ETH_BASE+LPC17_ETH_IPGT_OFFSET)
-#define LPC17_ETH_IPGR (LPC17_ETH_BASE+LPC17_ETH_IPGR_OFFSET)
-#define LPC17_ETH_CLRT (LPC17_ETH_BASE+LPC17_ETH_CLRT_OFFSET)
-#define LPC17_ETH_MAXF (LPC17_ETH_BASE+LPC17_ETH_MAXF_OFFSET)
-#define LPC17_ETH_SUPP (LPC17_ETH_BASE+LPC17_ETH_SUPP_OFFSET)
-#define LPC17_ETH_TEST (LPC17_ETH_BASE+LPC17_ETH_TEST_OFFSET)
-#define LPC17_ETH_MCFG (LPC17_ETH_BASE+LPC17_ETH_MCFG_OFFSET)
-#define LPC17_ETH_MCMD (LPC17_ETH_BASE+LPC17_ETH_MCMD_OFFSET)
-#define LPC17_ETH_MADR (LPC17_ETH_BASE+LPC17_ETH_MADR_OFFSET)
-#define LPC17_ETH_MWTD (LPC17_ETH_BASE+LPC17_ETH_MWTD_OFFSET)
-#define LPC17_ETH_MRDD (LPC17_ETH_BASE+LPC17_ETH_MRDD_OFFSET)
-#define LPC17_ETH_MIND (LPC17_ETH_BASE+LPC17_ETH_MIND_OFFSET)
-#define LPC17_ETH_SA0 (LPC17_ETH_BASE+LPC17_ETH_SA0_OFFSET)
-#define LPC17_ETH_SA1 (LPC17_ETH_BASE+LPC17_ETH_SA1_OFFSET)
-#define LPC17_ETH_SA2 (LPC17_ETH_BASE+LPC17_ETH_SA2_OFFSET)
-
-/* Control registers */
-
-#define LPC17_ETH_CMD (LPC17_ETH_BASE+LPC17_ETH_CMD_OFFSET)
-#define LPC17_ETH_STAT (LPC17_ETH_BASE+LPC17_ETH_STAT_OFFSET)
-#define LPC17_ETH_RXDESC (LPC17_ETH_BASE+LPC17_ETH_RXDESC_OFFSET)
-#define LPC17_ETH_RXSTAT (LPC17_ETH_BASE+LPC17_ETH_RXSTAT_OFFSET)
-#define LPC17_ETH_RXDESCNO (LPC17_ETH_BASE+LPC17_ETH_RXDESCNO_OFFSET)
-#define LPC17_ETH_RXPRODIDX (LPC17_ETH_BASE+LPC17_ETH_RXPRODIDX_OFFSET)
-#define LPC17_ETH_RXCONSIDX (LPC17_ETH_BASE+LPC17_ETH_RXCONSIDX_OFFSET)
-#define LPC17_ETH_TXDESC (LPC17_ETH_BASE+LPC17_ETH_TXDESC_OFFSET)
-#define LPC17_ETH_TXSTAT (LPC17_ETH_BASE+LPC17_ETH_TXSTAT_OFFSET)
-#define LPC17_ETH_TXDESCRNO (LPC17_ETH_BASE+LPC17_ETH_TXDESCRNO_OFFSET)
-#define LPC17_ETH_TXPRODIDX (LPC17_ETH_BASE+LPC17_ETH_TXPRODIDX_OFFSET)
-#define LPC17_ETH_TXCONSIDX (LPC17_ETH_BASE+LPC17_ETH_TXCONSIDX_OFFSET)
-#define LPC17_ETH_TSV0 (LPC17_ETH_BASE+LPC17_ETH_TSV0_OFFSET)
-#define LPC17_ETH_TSV1 (LPC17_ETH_BASE+LPC17_ETH_TSV1_OFFSET)
-#define LPC17_ETH_RSV (LPC17_ETH_BASE+LPC17_ETH_RSV_OFFSET)
-#define LPC17_ETH_FCCNTR (LPC17_ETH_BASE+LPC17_ETH_FCCNTR_OFFSET)
-#define LPC17_ETH_FCSTAT (LPC17_ETH_BASE+LPC17_ETH_FCSTAT_OFFSET)
-
-/* Rx filter registers */
-
-#define LPC17_ETH_RXFLCTRL (LPC17_ETH_BASE+LPC17_ETH_RXFLCTRL_OFFSET)
-#define LPC17_ETH_RXFLWOLST (LPC17_ETH_BASE+LPC17_ETH_RXFLWOLST_OFFSET)
-#define LPC17_ETH_RXFLWOLCLR (LPC17_ETH_BASE+LPC17_ETH_RXFLWOLCLR_OFFSET)
-#define LPC17_ETH_HASHFLL (LPC17_ETH_BASE+LPC17_ETH_HASHFLL_OFFSET)
-#define LPC17_ETH_HASHFLH (LPC17_ETH_BASE+LPC17_ETH_HASHFLH_OFFSET)
-
-/* Module control registers */
-
-#define LPC17_ETH_INTST (LPC17_ETH_BASE+LPC17_ETH_INTST_OFFSET)
-#define LPC17_ETH_INTEN (LPC17_ETH_BASE+LPC17_ETH_INTEN_OFFSET)
-#define LPC17_ETH_INTCLR (LPC17_ETH_BASE+LPC17_ETH_INTCLR_OFFSET)
-#define LPC17_ETH_INTSET (LPC17_ETH_BASE+LPC17_ETH_INTSET_OFFSET)
-#define LPC17_ETH_PWRDOWN (LPC17_ETH_BASE+LPC17_ETH_PWRDOWN_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* MAC registers */
-/* MAC configuration register 1 (MAC1) */
-
-#define ETH_MAC1_RE (1 << 0) /* Bit 0: Receive enable */
-#define ETH_MAC1_PARF (1 << 1) /* Bit 1: Passall all receive frames */
-#define ETH_MAC1_RFC (1 << 2) /* Bit 2: RX flow control */
-#define ETH_MAC1_TFC (1 << 3) /* Bit 3: TX flow control */
-#define ETH_MAC1_LPBK (1 << 4) /* Bit 4: Loopback */
- /* Bits 5-7: Reserved */
-#define ETH_MAC1_TXRST (1 << 8) /* Bit 8: Reset TX */
-#define ETH_MAC1_MCSTXRST (1 << 9) /* Bit 9: Reset MCS/TX */
-#define ETH_MAC1_RXRST (1 << 10) /* Bit 10: Reset RX */
-#define ETH_MAC1_MCSRXRST (1 << 11) /* Bit 11: Reset MCS/RX */
- /* Bits 12-13: Reserved */
-#define ETH_MAC1_SIMRST (1 << 14) /* Bit 14: Simulation reset */
-#define ETH_MAC1_SOFTRST (1 << 15) /* Bit 15: Soft reset */
- /* Bits 16-31: Reserved */
-/* MAC configuration register 2 (MAC2) */
-
-#define ETH_MAC2_FD (1 << 0) /* Bit 0: Full duplex */
-#define ETH_MAC2_FLC (1 << 1) /* Bit 1: Frame length checking */
-#define ETH_MAC2_HFE (1 << 2) /* Bit 2: Huge frame enable */
-#define ETH_MAC2_DCRC (1 << 3) /* Bit 3: Delayed CRC */
-#define ETH_MAC2_CRCEN (1 << 4) /* Bit 4: CRC enable */
-#define ETH_MAC2_PADCRCEN (1 << 5) /* Bit 5: Pad/CRC enable */
-#define ETH_MAC2_VLANPADEN (1 << 6) /* Bit 6: VLAN pad enable */
-#define ETH_MAC2_AUTOPADEN (1 << 7) /* Bit 7: Auto detect pad enable */
-#define ETH_MAC2_PPE (1 << 8) /* Bit 8: Pure preamble enforcement */
-#define ETH_MAC2_LPE (1 << 9) /* Bit 9: Long preamble enforcement */
- /* Bits 10-11: Reserved */
-#define ETH_MAC2_NBKOFF (1 << 12) /* Bit 12: No backoff */
-#define ETH_MAC2_BPNBKOFF (1 << 13) /* Bit 13: Back pressure/no backoff */
-#define ETH_MAC2_EXDEF (1 << 14) /* Bit 14: Excess defer */
- /* Bits 15-31: Reserved */
-/* Back-to-Back Inter-Packet-Gap register (IPGT) */
-
-#define ETH_IPGT_SHIFT (0) /* Bits 0-6 */
-#define ETH_IPGT_MASK (0x7f << ETH_IPGT_SHIFT)
- /* Bits 7-31: Reserved */
-/* Non Back-to-Back Inter-Packet-Gap register (IPGR) */
-
-#define ETH_IPGR_GAP2_SHIFT (0) /* Bits 0-6: Gap part 2 */
-#define ETH_IPGR_GAP2_MASK (0x7f << ETH_IPGR_GAP2_SHIFT)
- /* Bit 7: Reserved */
-#define ETH_IPGR_GAP1_SHIFT (8) /* Bits 8-18: Gap part 1 */
-#define ETH_IPGR_GAP1_MASK (0x7f << ETH_IPGR_GAP2_SHIFT)
- /* Bits 15-31: Reserved */
-/* Collision window / Retry register (CLRT) */
-
-#define ETH_CLRT_RMAX_SHIFT (0) /* Bits 0-3: Retransmission maximum */
-#define ETH_CLRT_RMAX_MASK (15 << ETH_CLRT_RMAX_SHIFT)
- /* Bits 4-7: Reserved */
-#define ETH_CLRT_COLWIN_SHIFT (8) /* Bits 8-13: Collision window */
-#define ETH_CLRT_COLWIN_MASK (0x3f << ETH_CLRT_COLWIN_SHIFT)
- /* Bits 14-31: Reserved */
-/* Maximum Frame register (MAXF) */
-
-#define ETH_MAXF_SHIFT (0) /* Bits 0-15 */
-#define ETH_MAXF_MASK (0xffff << ETH_MAXF_SHIFT)
- /* Bits 16-31: Reserved */
-/* PHY Support register (SUPP) */
- /* Bits 0-7: Reserved */
-#define ETH_SUPP_SPEED (1 << 8) /* Bit 8: 0=10Bps 1=100Bps */
- /* Bits 9-31: Reserved */
-/* Test register (TEST) */
-
-#define ETH_TEST_SPQ (1 << 0) /* Bit 0: Shortcut pause quanta */
-#define ETH_TEST_TP (1 << 1) /* Bit 1: Test pause */
-#define ETH_TEST_TBP (1 << 2) /* Bit 2: Test packpressure */
- /* Bits 3-31: Reserved */
-/* MII Mgmt Configuration register (MCFG) */
-
-#define ETH_MCFG_SCANINC (1 << 0) /* Bit 0: Scan increment */
-#define ETH_MCFG_SUPPRE (1 << 1) /* Bit 1: Suppress preamble */
-#define ETH_MCFG_CLKSEL_SHIFT (2) /* Bits 2-5: Clock select */
-#define ETH_MCFG_CLKSEL_MASK (15 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV4 (0 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV6 (2 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV8 (3 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV10 (4 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV14 (5 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV20 (6 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV28 (7 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV36 (8 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV40 (9 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV44 (10 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV48 (11 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV52 (12 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV56 (13 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV60 (14 << ETH_MCFG_CLKSEL_SHIFT)
-# define ETH_MCFG_CLKSEL_DIV64 (15 << ETH_MCFG_CLKSEL_SHIFT)
- /* Bits 6-14: Reserved */
-#define ETH_MCFG_MIIRST (1 << 15) /* Bit 15: Reset MII mgmt */
- /* Bits 16-31: Reserved */
-/* MII Mgmt Command register (MCMD) */
-
-#define ETH_MCMD_READ (1 << 0) /* Bit 0: Single read cycle */
-#define ETH_MCMD_SCAN (1 << 1) /* Bit 1: Continuous read cycles */
- /* Bits 2-31: Reserved */
-#define ETH_MCMD_WRITE (0)
-
-/* MII Mgmt Address register (MADR) */
-
-#define ETH_MADR_REGADDR_SHIFT (0) /* Bits 0-4: Register address */
-#define ETH_MADR_REGADDR_MASK (31 << ETH_MADR_REGADDR_SHIFT)
- /* Bits 7-5: Reserved */
-#define ETH_MADR_PHYADDR_SHIFT (8) /* Bits 8-12: PHY address */
-#define ETH_MADR_PHYADDR_MASK (31 << ETH_MADR_PHYADDR_SHIFT)
- /* Bits 13-31: Reserved */
-/* MII Mgmt Write Data register (MWTD) */
-
-#define ETH_MWTD_SHIFT (0) /* Bits 0-15 */
-#define ETH_MWTD_MASK (0xffff << ETH_MWTD_SHIFT)
- /* Bits 16-31: Reserved */
-/* MII Mgmt Read Data register (MRDD) */
-
-#define ETH_MRDD_SHIFT (0) /* Bits 0-15 */
-#define ETH_MRDD_MASK (0xffff << ETH_MRDD_SHIFT)
- /* Bits 16-31: Reserved */
-/* MII Mgmt Indicators register (MIND) */
-
-#define ETH_MIND_BUSY (1 << 0) /* Bit 0: Busy */
-#define ETH_MIND_SCANNING (1 << 1) /* Bit 1: Scanning */
-#define ETH_MIND_NVALID (1 << 2) /* Bit 2: Not valid */
-#define ETH_MIND_MIIFAIL (1 << 3) /* Bit 3: MII link fail */
- /* Bits 4-31: Reserved */
-/* Station Address 0 register (SA0) */
-
-#define ETH_SA0_OCTET2_SHIFT (0) /* Bits 0-7: Station address 2nd octet */
-#define ETH_SA0_OCTET2_MASK (0xff << ETH_SA0_OCTET2_SHIFT)
-#define ETH_SA0_OCTET1_SHIFT (8) /* Bits 8-15: Station address 1st octet */
-#define ETH_SA0_OCTET1_MASK (0xff << ETH_SA0_OCTET1_SHIFT)
- /* Bits 16-31: Reserved */
-/* Station Address 1 register (SA1) */
-
-#define ETH_SA1_OCTET4_SHIFT (0) /* Bits 0-7: Station address 4th octet */
-#define ETH_SA1_OCTET4_MASK (0xff << ETH_SA0_OCTET4_SHIFT)
-#define ETH_SA1_OCTET3_SHIFT (8) /* Bits 8-15: Station address 3rd octet */
-#define ETH_SA1_OCTET3_MASK (0xff << ETH_SA0_OCTET3_SHIFT)
- /* Bits 16-31: Reserved */
-/* Station Address 2 register (SA2) */
-
-#define ETH_SA2_OCTET6_SHIFT (0) /* Bits 0-7: Station address 5th octet */
-#define ETH_SA2_OCTET6_MASK (0xff << ETH_SA0_OCTET6_SHIFT)
-#define ETH_SA2_OCTET5_SHIFT (8) /* Bits 8-15: Station address 6th octet */
-#define ETH_SA2_OCTET5_MASK (0xff << ETH_SA0_OCTET5_SHIFT)
- /* Bits 16-31: Reserved */
-/* Control registers */
-/* Command register (CMD) */
-
-#define ETH_CMD_RXEN (1 << 0) /* Bit 0: Receive enable */
-#define ETH_CMD_TXEN (1 << 1) /* Bit 1: Transmit enable */
- /* Bit 2: Reserved */
-#define ETH_CMD_REGRST (1 << 3) /* Bit 3: Reset host registers */
-#define ETH_CMD_TXRST (1 << 4) /* Bit 4: Reset transmit datapath */
-#define ETH_CMD_RXRST (1 << 5) /* Bit 5: Reset receive datapath */
-#define ETH_CMD_PRFRAME (1 << 6) /* Bit 6: Pass run frame */
-#define ETH_CMD_PRFILTER (1 << 7) /* Bit 7: Pass RX filter */
-#define ETH_CMD_TXFC (1 << 8) /* Bit 8: TX flow control */
-#define ETH_CMD_RMII (1 << 9) /* Bit 9: RMII mode */
-#define ETH_CMD_FD (1 << 10) /* Bit 10: Full duplex */
- /* Bits 11-31: Reserved */
-/* Status register */
-
-#define ETH_STAT_RX (1 << 0) /* Bit 0: RX status */
-#define ETH_STAT_TX (1 << 1) /* Bit 1: TX status */
- /* Bits 2-31: Reserved */
-/* Receive descriptor base address register (RXDESC)
- *
- * The receive descriptor base address is a byte address aligned to a word
- * boundary i.e. LSB 1:0 are fixed to 00. The register contains the lowest
- * address in the array of descriptors.
- */
-
-/* Receive status base address register (RXSTAT)
- *
- * The receive status base address is a byte address aligned to a double word
- * boundary i.e. LSB 2:0 are fixed to 000.
- */
-
-/* Receive number of descriptors register (RXDESCNO) */
-
-#define ETH_RXDESCNO_SHIFT (0) /* Bits 0-15 */
-#define ETH_RXDESCNO_MASK (0xffff << ETH_RXDESCNO_SHIFT)
- /* Bits 16-31: Reserved */
-/* Receive produce index register (RXPRODIDX) */
-
-#define ETH_RXPRODIDX_SHIFT (0) /* Bits 0-15 */
-#define ETH_RXPRODIDX_MASK (0xffff << ETH_RXPRODIDX_SHIFT)
- /* Bits 16-31: Reserved */
-/* Receive consume index register (RXCONSIDX) */
-
-#define ETH_RXCONSIDX_SHIFT (0) /* Bits 0-15 */
-#define ETH_RXCONSIDX_MASK (0xffff << ETH_RXPRODIDX_SHIFT)
- /* Bits 16-31: Reserved */
-/* Transmit descriptor base address register (TXDESC)
- *
- * The transmit descriptor base address is a byte address aligned to a word
- * boundary i.e. LSB 1:0 are fixed to 00. The register contains the lowest
- * address in the array of descriptors.
- */
-
-/* Transmit status base address register (TXSTAT)
- *
- * The transmit status base address is a byte address aligned to a word
- * boundary i.e. LSB1:0 are fixed to 00. The register contains the lowest
- * address in the array of statuses.
- */
-
-/* Transmit number of descriptors register (TXDESCRNO) */
-
-#define ETH_TXDESCRNO_SHIFT (0) /* Bits 0-15 */
-#define ETH_TXDESCRNO_MASK (0xffff << ETH_TXDESCRNO_SHIFT)
- /* Bits 16-31: Reserved */
-/* Transmit produce index register (TXPRODIDX) */
-
-#define ETH_TXPRODIDX_SHIFT (0) /* Bits 0-15 */
-#define ETH_TXPRODIDX_MASK (0xffff << ETH_TXPRODIDX_SHIFT)
- /* Bits 16-31: Reserved */
-/* Transmit consume index register (TXCONSIDX) */
-
-#define ETH_TXCONSIDX_SHIFT (0) /* Bits 0-15 */
-#define ETH_TXCONSIDX_MASK (0xffff << ETH_TXPRODIDX_SHIFT)
- /* Bits 16-31: Reserved */
-/* Transmit status vector 0 register (TSV0) */
-
-#define ETH_TSV0_CRCERR (1 << 0) /* Bit 0: CRC error */
-#define ETH_TSV0_LENCHKERR (1 << 1) /* Bit 1: Length check error */
-#define ETH_TSV0_LENOOR (1 << 2) /* Bit 2: Length out of range */
-#define ETH_TSV0_DONE (1 << 3) /* Bit 3: Done */
-#define ETH_TSV0_MCAST (1 << 4) /* Bit 4: Multicast */
-#define ETH_TSV0_BCAST (1 << 5) /* Bit 5: Broadcast */
-#define ETH_TSV0_PKTDEFER (1 << 6) /* Bit 6: Packet Defer */
-#define ETH_TSV0_EXCDEFER (1 << 7) /* Bit 7: Excessive Defer */
-#define ETH_TSV0_EXCCOL (1 << 8) /* Bit 8: Excessive Collision */
-#define ETH_TSV0_LATECOL (1 << 9) /* Bit 9: Late Collision */
-#define ETH_TSV0_GIANT (1 << 10) /* Bit 10: Giant */
-#define ETH_TSV0_UNDRUN (1 << 11) /* Bit 11: Underrun */
-#define ETH_TSV0_TOTBYTES_SHIFT (12) /* Bits 12-27:Total bytes */
-#define ETH_TSV0_TOTBYTES_MASK (0xffff << ETH_TSV0_TOTBYTES_SHIFT)
-#define ETH_TSV0_CTLFRAME (1 << 28) /* Bit 28: Control frame */
-#define ETH_TSV0_PAUSE (1 << 29) /* Bit 29: Pause */
-#define ETH_TSV0_BP (1 << 30) /* Bit 30: Backpressure */
-#define ETH_TSV0_VLAN (1 << 31) /* Bit 31: VLAN */
-
-/* Transmit status vector 1 register (TSV1) */
-
-#define ETH_TSV1_TXCNT_SHIFT (0) /* Bits 0-15: Transmit byte count */
-#define ETH_TSV1_TXCNT_MASK (0xffff << ETH_TSV1_TXCNT_SHIFT)
-#define ETH_TSV1_COLCNT_SHIFT (16) /* Bits 16-19: Transmit collision count */
-#define ETH_TSV1_COLCNT_MASK (15 << ETH_TSV1_COLCNT_SHIFT)
- /* Bits 20-31: Reserved */
-/* Receive status vector register (RSV) */
-
-#define ETH_RSV_RXCNT_SHIFT (0) /* Bits 0-15: Received byte count */
-#define ETH_RSV_RXCNT_MASK (0xffff << ETH_RSV_RXCNT_SHIFT)
-#define ETH_RSV_PKTPI (1 << 16) /* Bit 16: Packet previously ignored */
-#define ETH_RSV_RXEPS (1 << 17) /* Bit 17: RXDV event previously seen */
-#define ETH_RSV_CEPS (1 << 18) /* Bit 18: Carrier event previously seen */
-#define ETH_RSV_RXCV (1 << 19) /* Bit 19: Receive code violation */
-#define ETH_RSV_CRCERR (1 << 20) /* Bit 20: CRC error */
-#define ETH_RSV_LENCHKERR (1 << 21) /* Bit 21: Length check error */
-#define ETH_RSV_LENOOR (1 << 22) /* Bit 22: Length out of range */
-#define ETH_RSV_RXOK (1 << 23) /* Bit 23: Receive OK */
-#define ETH_RSV_MCAST (1 << 24) /* Bit 24: Multicast */
-#define ETH_RSV_BCAST (1 << 25) /* Bit 25: Broadcast */
-#define ETH_RSV_DRIBNIB (1 << 26) /* Bit 26: Dribble Nibble */
-#define ETH_RSV_CTLFRAME (1 << 27) /* Bit 27: Control frame */
-#define ETH_RSV_PAUSE (1 << 28) /* Bit 28: Pause */
-#define ETH_RSV_UNSUPOP (1 << 29) /* Bit 29: Unsupported Opcode */
-#define ETH_RSV_VLAN (1 << 30) /* Bit 30: VLAN */
- /* Bit 31: Reserved */
-/* Flow control counter register (FCCNTR) */
-
-#define ETH_FCCNTR_MCOUNT_SHIFT (0) /* Bits 0-15: Mirror count */
-#define ETH_FCCNTR_MCOUNT_MASK (0xffff << ETH_FCCNTR_MCOUNT_SHIFT)
-#define ETH_FCCNTR_PTMR_SHIFT (16) /* Bits 16-31: Pause timer */
-#define ETH_FCCNTR_PTMR_MASK (0xffff << ETH_FCCNTR_PTMR_SHIFT)
-
-/* Flow control status register (FCSTAT) */
-
-#define ETH_FCSTAT_MCOUNT_SHIFT (0) /* Bits 0-15: Current mirror count */
-#define ETH_FCSTAT_MCOUNT_MASK (0xffff << ETH_FCSTAT_MCOUNT_SHIFT)
- /* Bits 16-31: Reserved */
-/* Rx filter registers */
-/* Receive filter control register (RXFLCTRL) */
-
-#define ETH_RXFLCTRL_UCASTEN (1 << 0) /* Bit 0: Accept all unicast frames */
-#define ETH_RXFLCTRL_BCASTEN (1 << 1) /* Bit 1: Accept all broadcast frames */
-#define ETH_RXFLCTRL_MCASTEN (1 << 2) /* Bit 2: Accept all multicast frames */
-#define ETH_RXFLCTRL_UCASTHASHEN (1 << 3) /* Bit 3: Accept hashed unicast */
-#define ETH_RXFLCTRL_MCASTHASHEN (1 << 4) /* Bit 4: Accect hashed multicast */
-#define ETH_RXFLCTRL_PERFEN (1 << 5) /* Bit 5: Accept perfect dest match */
- /* Bits 6-11: Reserved */
-#define ETH_RXFLCTRL_MPKTEN (1 << 12) /* Bit 12: Magic pkt filter WoL int */
-#define ETH_RXFLCTRL_RXFILEN (1 << 13) /* Bit 13: Perfect match WoL interrupt */
- /* Bits 14-31: Reserved */
-/* Receive filter WoL status register (RXFLWOLST) AND
- * Receive filter WoL clear register (RXFLWOLCLR)
- */
-
-#define ETH_RXFLWOL_UCAST (1 << 0) /* Bit 0: Unicast frame WoL */
-#define ETH_RXFLWOL_BCAST (1 << 1) /* Bit 1: Broadcast frame WoL */
-#define ETH_RXFLWOL_MCAST (1 << 2) /* Bit 2: Multicast frame WoL */
-#define ETH_RXFLWOL_UCASTHASH (1 << 3) /* Bit 3: Unicast hash filter WoL */
-#define ETH_RXFLWOL_MCASTHASH (1 << 4) /* Bit 4: Multiicast hash filter WoL */
-#define ETH_RXFLWOL_PERF (1 << 5) /* Bit 5: Perfect addr match WoL */
- /* Bit 6: Reserved */
-#define ETH_RXFLWOL_RXFIL (1 << 7) /* Bit 7: Receive filter WoL */
-#define ETH_RXFLWOL_MPKT (1 << 8) /* Bit 8: Magic pkt filter WoL */
- /* Bits 9-31: Reserved */
-/* Hash filter table LSBs register (HASHFLL) AND Hash filter table MSBs register
-* (HASHFLH) Are registers containing a 32-bit value with no bitfield.
- */
-
-/* Module control registers */
-/* Interrupt status register (INTST), Interrupt enable register (INTEN), Interrupt
- * clear register (INTCLR), and Interrupt set register (INTSET) common bit field
- * definition:
- */
-
-#define ETH_INT_RXOVR (1 << 0) /* Bit 0: RX overrun interrupt */
-#define ETH_INT_RXERR (1 << 1) /* Bit 1: RX error interrupt */
-#define ETH_INT_RXFIN (1 << 2) /* Bit 2: RX finished interrupt */
-#define ETH_INT_RXDONE (1 << 3) /* Bit 3: RX done interrupt */
-#define ETH_INT_TXUNR (1 << 4) /* Bit 4: TX underrun interrupt */
-#define ETH_INT_TXERR (1 << 5) /* Bit 5: TX error interrupt */
-#define ETH_INT_TXFIN (1 << 6) /* Bit 6: TX finished interrupt */
-#define ETH_INT_TXDONE (1 << 7) /* Bit 7: TX done interrupt */
- /* Bits 8-11: Reserved */
-#define ETH_INT_SOFT (1 << 12) /* Bit 12: Soft interrupt */
-#define ETH_INT_WKUP (1 << 13) /* Bit 13: Wakeup interrupt */
- /* Bits 14-31: Reserved */
-/* Power-down register */
- /* Bits 0-30: Reserved */
-#define ETH_PWRDOWN_MACAHB (1 << 31) /* Power down MAC/AHB */
-
-/* Descriptors Offsets **************************************************************/
-
-/* Tx descriptor offsets */
-
-#define LPC17_TXDESC_PACKET 0x00 /* Base address of the Tx data buffer */
-#define LPC17_TXDESC_CONTROL 0x04 /* Control Information */
-#define LPC17_TXDESC_SIZE 0x08 /* Size in bytes of one Tx descriptor */
-
-/* Tx status offsets */
-
-#define LPC17_TXSTAT_INFO 0x00 /* Transmit status return flags */
-#define LPC17_TXSTAT_SIZE 0x04 /* Size in bytes of one Tx status */
-
-/* Rx descriptor offsets */
-
-#define LPC17_RXDESC_PACKET 0x00 /* Base address of the Rx data buffer */
-#define LPC17_RXDESC_CONTROL 0x04 /* Control Information */
-#define LPC17_RXDESC_SIZE 0x08 /* Size in bytes of one Rx descriptor */
-
-/* Rx status offsets */
-
-#define LPC17_RXSTAT_INFO 0x00 /* Receive status return flags */
-#define LPC17_RXSTAT_HASHCRC 0x04 /* Dest and source hash CRC */
-#define LPC17_RXSTAT_SIZE 0x08 /* Size in bytes of one Rx status */
-
-/* Descriptor Bit Definitions *******************************************************/
-
-/* Tx descriptor bit definitions */
-
-#define TXDESC_CONTROL_SIZE_SHIFT (0) /* Bits 0-10: Size of data buffer */
-#define TXDESC_CONTROL_SIZE_MASK (0x7ff << RXDESC_CONTROL_SIZE_SHIFT)
-
-#define TXDESC_CONTROL_OVERRIDE (1 << 26 /* Bit 26: Per-frame override */
-#define TXDESC_CONTROL_HUGE (1 << 27) /* Bit 27: Enable huge frame size */
-#define TXDESC_CONTROL_PAD (1 << 28) /* Bit 28: Pad short frames */
-#define TXDESC_CONTROL_CRC (1 << 29) /* Bit 29: Append CRC */
-#define TXDESC_CONTROL_LAST (1 << 30) /* Bit 30: Last descriptor of a fragment */
-#define TXDESC_CONTROL_INT (1 << 31) /* Bit 31: Generate TxDone interrupt */
-
-/* Tx status bit definitions */
-
-#define TXSTAT_INFO_COLCNT_SHIFT (21) /* Bits 21-24: Number of collisions */
-#define TXSTAT_INFO_COLCNT_MASK (15 << TXSTAT_INFO_COLCNT_SHIFT)
-#define TXSTAT_INFO_DEFER (1 << 25) /* Bit 25: Packet deffered */
-#define TXSTAT_INFO_EXCESSDEFER (1 << 26) /* Bit 26: Excessive packet defferals */
-#define TXSTAT_INFO_EXCESSCOL (1 << 27) /* Bit 27: Excessive packet collisions */
-#define TXSTAT_INFO_LATECOL (1 << 28) /* Bit 28: Out of window collision */
-#define TXSTAT_INFO_UNDERRUN (1 << 29) /* Bit 29: Tx underrun */
-#define TXSTAT_INFO_NODESC (1 << 30) /* Bit 29: No Tx descriptor available */
-#define TXSTAT_INFO_ERROR (1 << 31) /* Bit 31: OR of other error conditions */
-
-/* Rx descriptor bit definitions */
-
-#define RXDESC_CONTROL_SIZE_SHIFT (0) /* Bits 0-10: Size of data buffer */
-#define RXDESC_CONTROL_SIZE_MASK (0x7ff << RXDESC_CONTROL_SIZE_SHIFT)
-#define RXDESC_CONTROL_INT (1 << 31) /* Bit 31: Generate RxDone interrupt */
-
-/* Rx status bit definitions */
-
-#define RXSTAT_SAHASHCRC_SHIFT (0) /* Bits 0-8: Hash CRC calculated from the source address */
-#define RXSTAT_SAHASHCRC_MASK (0x1ff << RXSTAT_SAHASHCRC_SHIFT)
-#define RXSTAT_DAHASHCRC_SHIFT (16) /* Bits 16-24: Hash CRC calculated from the dest address */
-#define RXSTAT_DAHASHCRC_MASK (0x1ff << RXSTAT_DAHASHCRC_SHIFT)
-
-#define RXSTAT_INFO_RXSIZE_SHIFT (0) /* Bits 0-10: Size of actual data transferred */
-#define RXSTAT_INFO_RXSIZE_MASK (0x7ff << RXSTAT_INFO_RXSIZE_SHIFT)
-#define RXSTAT_INFO_CONTROL (1 << 18) /* Bit 18: This is a control frame */
-#define RXSTAT_INFO_VLAN (1 << 19) /* Bit 19: This is a VLAN frame */
-#define RXSTAT_INFO_FAILFILTER (1 << 20) /* Bit 20: Frame failed Rx filter */
-#define RXSTAT_INFO_MULTICAST (1 << 21) /* Bit 21: This is a multicast frame */
-#define RXSTAT_INFO_BROADCAST (1 << 22) /* Bit 22: This is a broadcast frame */
-#define RXSTAT_INFO_CRCERROR (1 << 23) /* Bit 23: Received frame had a CRC error */
-#define RXSTAT_INFO_SYMBOLERROR (1 << 24) /* Bit 24: PHY reported bit error */
-#define RXSTAT_INFO_LENGTHERROR (1 << 25) /* Bit 25: Invalid frame length */
-#define RXSTAT_INFO_RANGEERROR (1 << 26) /* Bit 26: Exceeds maximum packet size */
-#define RXSTAT_INFO_ALIGNERROR (1 << 27) /* Bit 27: Alignment error */
-#define RXSTAT_INFO_OVERRUN (1 << 28) /* Bit 28: Receive overrun error */
-#define RXSTAT_INFO_NODESC (1 << 29) /* Bit 29: No Rx descriptor available */
-#define RXSTAT_INFO_LASTFLAG (1 << 30) /* Bit 30: Last fragment of a frame */
-#define RXSTAT_INFO_ERROR (1 << 31) /* Bit 31: OR of other error conditions */
-
/************************************************************************************
* Public Types
************************************************************************************/
@@ -590,8 +55,19 @@
* Public Data
************************************************************************************/
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
/************************************************************************************
* Public Functions
************************************************************************************/
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_ETHERNET_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c
index f567d52c0..4833fff3b 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.c
@@ -51,8 +51,8 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
-#include "lpc17_syscon.h"
+
+#include "chip/lpc17_syscon.h"
#include "lpc17_gpdma.h"
#ifdef CONFIG_LPC17_GPDMA
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h b/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h
index c0e70efa5..41e60877d 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpdma.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_gpdma.h
*
- * 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
@@ -41,377 +41,190 @@
************************************************************************************/
#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_gpdma.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-
-/* General registers (see also LPC17_SYSCON_DMAREQSEL_OFFSET in lpc17_syscon.h) */
-
-#define LPC17_DMA_INTST_OFFSET 0x0000 /* DMA Interrupt Status Register */
-#define LPC17_DMA_INTTCST_OFFSET 0x0004 /* DMA Interrupt Terminal Count Request Status Register */
-#define LPC17_DMA_INTTCCLR_OFFSET 0x0008 /* DMA Interrupt Terminal Count Request Clear Register */
-#define LPC17_DMA_INTERRST_OFFSET 0x000c /* DMA Interrupt Error Status Register */
-#define LPC17_DMA_INTERRCLR_OFFSET 0x0010 /* DMA Interrupt Error Clear Register */
-#define LPC17_DMA_RAWINTTCST_OFFSET 0x0014 /* DMA Raw Interrupt Terminal Count Status Register */
-#define LPC17_DMA_RAWINTERRST_OFFSET 0x0018 /* DMA Raw Error Interrupt Status Register */
-#define LPC17_DMA_ENBLDCHNS_OFFSET 0x001c /* DMA Enabled Channel Register */
-#define LPC17_DMA_SOFTBREQ_OFFSET 0x0020 /* DMA Software Burst Request Register */
-#define LPC17_DMA_SOFTSREQ_OFFSET 0x0024 /* DMA Software Single Request Register */
-#define LPC17_DMA_SOFTLBREQ_OFFSET 0x0028 /* DMA Software Last Burst Request Register */
-#define LPC17_DMA_SOFTLSREQ_OFFSET 0x002c /* DMA Software Last Single Request Register */
-#define LPC17_DMA_CONFIG_OFFSET 0x0030 /* DMA Configuration Register */
-#define LPC17_DMA_SYNC_OFFSET 0x0034 /* DMA Synchronization Register */
-
-/* Channel Registers */
-
-#define LPC17_DMA_CHAN_OFFSET(n) (0x0100 + ((n) << 5)) /* n=0,1,...7 */
-
-#define LPC17_DMACH_SRCADDR_OFFSET 0x0000 /* DMA Channel Source Address Register */
-#define LPC17_DMACH_DESTADDR_OFFSET 0x0004 /* DMA Channel Destination Address Register */
-#define LPC17_DMACH_LLI_OFFSET 0x0008 /* DMA Channel Linked List Item Register */
-#define LPC17_DMACH_CONTROL_OFFSET 0x000c /* DMA Channel Control Register */
-#define LPC17_DMACH_CONFIG_OFFSET 0x0010 /* DMA Channel Configuration Register */
-
-#define LPC17_DMACH0_SRCADDR_OFFSET (0x100+LPC17_DMACH_SRCADDR_OFFSET)
-#define LPC17_DMACH0_DESTADDR_OFFSET (0x100+LPC17_DMACH_DESTADDR_OFFSET)
-#define LPC17_DMACH0_LLI_OFFSET (0x100+LPC17_DMACH_LLI_OFFSET)
-#define LPC17_DMACH0_CONTROL_OFFSET (0x100+LPC17_DMACH_CONTROL_OFFSET)
-#define LPC17_DMACH0_CONFIG_OFFSET (0x100+LPC17_DMACH_CONFIG_OFFSET)
-
-#define LPC17_DMACH1_SRCADDR_OFFSET (0x120+LPC17_DMACH_SRCADDR_OFFSET)
-#define LPC17_DMACH1_DESTADDR_OFFSET (0x120+LPC17_DMACH_DESTADDR_OFFSET)
-#define LPC17_DMACH1_LLI_OFFSET (0x120+LPC17_DMACH_LLI_OFFSET)
-#define LPC17_DMACH1_CONTROL_OFFSET (0x120+LPC17_DMACH_CONTROL_OFFSET)
-#define LPC17_DMACH1_CONFIG_OFFSET (0x120+LPC17_DMACH_CONFIG_OFFSET)
-
-#define LPC17_DMACH2_SRCADDR_OFFSET (0x140+LPC17_DMACH_SRCADDR_OFFSET)
-#define LPC17_DMACH2_DESTADDR_OFFSET (0x140+LPC17_DMACH_DESTADDR_OFFSET)
-#define LPC17_DMACH2_LLI_OFFSET (0x140+LPC17_DMACH_LLI_OFFSET)
-#define LPC17_DMACH2_CONTROL_OFFSET (0x140+LPC17_DMACH_CONTROL_OFFSET)
-#define LPC17_DMACH2_CONFIG_OFFSET (0x140+LPC17_DMACH_CONFIG_OFFSET)
-
-#define LPC17_DMACH3_SRCADDR_OFFSET (0x160+LPC17_DMACH_SRCADDR_OFFSET)
-#define LPC17_DMACH3_DESTADDR_OFFSET (0x160+LPC17_DMACH_DESTADDR_OFFSET)
-#define LPC17_DMACH3_LLI_OFFSET (0x160+LPC17_DMACH_LLI_OFFSET)
-#define LPC17_DMACH3_CONTROL_OFFSET (0x160+LPC17_DMACH_CONTROL_OFFSET)
-#define LPC17_DMACH3_CONFIG_OFFSET (0x160+LPC17_DMACH_CONFIG_OFFSET)
-
-#define LPC17_DMACH4_SRCADDR_OFFSET (0x180+LPC17_DMACH_SRCADDR_OFFSET)
-#define LPC17_DMACH4_DESTADDR_OFFSET (0x180+LPC17_DMACH_DESTADDR_OFFSET)
-#define LPC17_DMACH4_LLI_OFFSET (0x180+LPC17_DMACH_LLI_OFFSET)
-#define LPC17_DMACH4_CONTROL_OFFSET (0x180+LPC17_DMACH_CONTROL_OFFSET)
-#define LPC17_DMACH4_CONFIG_OFFSET (0x180+LPC17_DMACH_CONFIG_OFFSET)
-
-#define LPC17_DMACH5_SRCADDR_OFFSET (0x1a0+LPC17_DMACH_SRCADDR_OFFSET)
-#define LPC17_DMACH5_DESTADDR_OFFSET (0x1a0+LPC17_DMACH_DESTADDR_OFFSET)
-#define LPC17_DMACH5_LLI_OFFSET (0x1a0+LPC17_DMACH_LLI_OFFSET)
-#define LPC17_DMACH5_CONTROL_OFFSET (0x1a0+LPC17_DMACH_CONTROL_OFFSET)
-#define LPC17_DMACH5_CONFIG_OFFSET (0x1a0+LPC17_DMACH_CONFIG_OFFSET)
-
-#define LPC17_DMACH6_SRCADDR_OFFSET (0x1c0+LPC17_DMACH_SRCADDR_OFFSET)
-#define LPC17_DMACH6_DESTADDR_OFFSET (0x1c0+LPC17_DMACH_DESTADDR_OFFSET)
-#define LPC17_DMACH6_LLI_OFFSET (0x1c0+LPC17_DMACH_LLI_OFFSET)
-#define LPC17_DMACH6_CONTROL_OFFSET (0x1c0+LPC17_DMACH_CONTROL_OFFSET)
-#define LPC17_DMACH6_CONFIG_OFFSET (0x1c0+LPC17_DMACH_CONFIG_OFFSET)
-
-#define LPC17_DMACH7_SRCADDR_OFFSET (0x1e0+LPC17_DMACH_SRCADDR_OFFSET)
-#define LPC17_DMACH7_DESTADDR_OFFSET (0x1e0+LPC17_DMACH_DESTADDR_OFFSET)
-#define LPC17_DMACH7_LLI_OFFSET (0x1e0+LPC17_DMACH_LLI_OFFSET)
-#define LPC17_DMACH7_CONTROL_OFFSET (0x1e0+LPC17_DMACH_CONTROL_OFFSET)
-#define LPC17_DMACH7_CONFIG_OFFSET (0x1e0+LPC17_DMACH_CONFIG_OFFSET)
-
-/* Register addresses ***************************************************************/
-/* General registers (see also LPC17_SYSCON_DMAREQSEL in lpc17_syscon.h) */
-
-#define LPC17_DMA_INTST (LPC17_GPDMA_BASE+LPC17_DMA_INTST_OFFSET)
-#define LPC17_DMA_INTTCST (LPC17_GPDMA_BASE+LPC17_DMA_INTTCST_OFFSET)
-#define LPC17_DMA_INTTCCLR (LPC17_GPDMA_BASE+LPC17_DMA_INTTCCLR_OFFSET)
-#define LPC17_DMA_INTERRST (LPC17_GPDMA_BASE+LPC17_DMA_INTERRST_OFFSET)
-#define LPC17_DMA_INTERRCLR (LPC17_GPDMA_BASE+LPC17_DMA_INTERRCLR_OFFSET)
-#define LPC17_DMA_RAWINTTCST (LPC17_GPDMA_BASE+LPC17_DMA_RAWINTTCST_OFFSET)
-#define LPC17_DMA_RAWINTERRST (LPC17_GPDMA_BASE+LPC17_DMA_RAWINTERRST_OFFSET)
-#define LPC17_DMA_ENBLDCHNS (LPC17_GPDMA_BASE+LPC17_DMA_ENBLDCHNS_OFFSET)
-#define LPC17_DMA_SOFTBREQ (LPC17_GPDMA_BASE+LPC17_DMA_SOFTBREQ_OFFSET)
-#define LPC17_DMA_SOFTSREQ (LPC17_GPDMA_BASE+LPC17_DMA_SOFTSREQ_OFFSET)
-#define LPC17_DMA_SOFTLBREQ (LPC17_GPDMA_BASE+LPC17_DMA_SOFTLBREQ_OFFSET)
-#define LPC17_DMA_SOFTLSREQ (LPC17_GPDMA_BASE+LPC17_DMA_SOFTLSREQ_OFFSET)
-#define LPC17_DMA_CONFIG (LPC17_GPDMA_BASE+LPC17_DMA_CONFIG_OFFSET)
-#define LPC17_DMA_SYNC (LPC17_GPDMA_BASE+LPC17_DMA_SYNC_OFFSET)
-
-/* Channel Registers */
-
-#define LPC17_DMACH_BASE(n) (LPC17_GPDMA_BASE+LPC17_DMA_CHAN_OFFSET(n))
-
-#define LPC17_DMACH_SRCADDR(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_SRCADDR_OFFSET)
-#define LPC17_DMACH_DESTADDR(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_DESTADDR_OFFSET)
-#define LPC17_DMACH_LLI(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_LLI_OFFSET)
-#define LPC17_DMACH_CONTROL(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_CONTROL_OFFSET)
-#define LPC17_DMACH_CONFIG(n) (LPC17_DMACH_BASE(n)+LPC17_DMACH_CONFIG_OFFSET)
-
-#define LPC17_DMACH0_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH0_SRCADDR_OFFSET)
-#define LPC17_DMACH0_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH0_DESTADDR_OFFSET)
-#define LPC17_DMACH0_LLI (LPC17_GPDMA_BASE+LPC17_DMACH0_LLI_OFFSET)
-#define LPC17_DMACH0_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH0_CONTROL_OFFSET)
-#define LPC17_DMACH0_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH0_CONFIG_OFFSET)
-
-#define LPC17_DMACH1_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH1_SRCADDR_OFFSET)
-#define LPC17_DMACH1_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH1_DESTADDR_OFFSET)
-#define LPC17_DMACH1_LLI (LPC17_GPDMA_BASE+LPC17_DMACH1_LLI_OFFSET)
-#define LPC17_DMACH1_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH1_CONTROL_OFFSET)
-#define LPC17_DMACH1_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH1_CONFIG_OFFSET)
-
-#define LPC17_DMACH2_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH2_SRCADDR_OFFSET)
-#define LPC17_DMACH2_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH2_DESTADDR_OFFSET)
-#define LPC17_DMACH2_LLI (LPC17_GPDMA_BASE+LPC17_DMACH2_LLI_OFFSET)
-#define LPC17_DMACH2_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH2_CONTROL_OFFSET)
-#define LPC17_DMACH2_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH2_CONFIG_OFFSET)
-
-#define LPC17_DMACH3_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH3_SRCADDR_OFFSET)
-#define LPC17_DMACH3_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH3_DESTADDR_OFFSET)
-#define LPC17_DMACH3_LLI (LPC17_GPDMA_BASE+LPC17_DMACH3_LLI_OFFSET)
-#define LPC17_DMACH3_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH3_CONTROL_OFFSET)
-#define LPC17_DMACH3_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH3_CONFIG_OFFSET)
-
-#define LPC17_DMACH4_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH4_SRCADDR_OFFSET)
-#define LPC17_DMACH4_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH4_DESTADDR_OFFSET)
-#define LPC17_DMACH4_LLI (LPC17_GPDMA_BASE+LPC17_DMACH4_LLI_OFFSET)
-#define LPC17_DMACH4_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH4_CONTROL_OFFSET)
-#define LPC17_DMACH4_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH4_CONFIG_OFFSET)
-
-#define LPC17_DMACH5_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH5_SRCADDR_OFFSET)
-#define LPC17_DMACH5_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH5_DESTADDR_OFFSET)
-#define LPC17_DMACH5_LLI (LPC17_GPDMA_BASE+LPC17_DMACH5_LLI_OFFSET)
-#define LPC17_DMACH5_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH5_CONTROL_OFFSET)
-#define LPC17_DMACH5_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH5_CONFIG_OFFSET)
-
-#define LPC17_DMACH6_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH6_SRCADDR_OFFSET)
-#define LPC17_DMACH6_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH6_DESTADDR_OFFSET)
-#define LPC17_DMACH6_LLI (LPC17_GPDMA_BASE+LPC17_DMACH6_LLI_OFFSET)
-#define LPC17_DMACH6_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH6_CONTROL_OFFSET)
-#define LPC17_DMACH6_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH6_CONFIG_OFFSET)
-
-#define LPC17_DMACH7_SRCADDR (LPC17_GPDMA_BASE+LPC17_DMACH7_SRCADDR_OFFSET)
-#define LPC17_DMACH7_DESTADDR (LPC17_GPDMA_BASE+LPC17_DMACH7_DESTADDR_OFFSET)
-#define LPC17_DMACH7_LLI (LPC17_GPDMA_BASE+LPC17_DMACH7_LLI_OFFSET)
-#define LPC17_DMACH7_CONTROL (LPC17_GPDMA_BASE+LPC17_DMACH7_CONTROL_OFFSET)
-#define LPC17_DMACH7_CONFIG (LPC17_GPDMA_BASE+LPC17_DMACH7_CONFIG_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* DMA request connections */
-
-#define DMA_REQ_SSP0TX (0)
-#define DMA_REQ_SSP0RX (1)
-#define DMA_REQ_SSP1TX (2)
-#define DMA_REQ_SSP1RX (3)
-#define DMA_REQ_ADC (4)
-#define DMA_REQ_I2SCH0 (5)
-#define DMA_REQ_I2SCH1 (6)
-#define DMA_REQ_DAC (7)
-
-#define DMA_REQ_UART0TX (8)
-#define DMA_REQ_UART0RX (9)
-#define DMA_REQ_UART1TX (10)
-#define DMA_REQ_UART1RX (11)
-#define DMA_REQ_UART2TX (12)
-#define DMA_REQ_UART2RX (13)
-#define DMA_REQ_UART3TX (14)
-#define DMA_REQ_UART3RX (15)
-
-#define DMA_REQ_MAT0p0 (8)
-#define DMA_REQ_MAT0p1 (9)
-#define DMA_REQ_MAT1p0 (10)
-#define DMA_REQ_MAT1p1 (11)
-#define DMA_REQ_MAT2p0 (12)
-#define DMA_REQ_MAT2p1 (13)
-#define DMA_REQ_MAT3p0 (14)
-#define DMA_REQ_MAT3p1 (15)
-
-/* General registers (see also LPC17_SYSCON_DMAREQSEL in lpc17_syscon.h) */
-/* Fach of the following registers, bits 0-7 controls DMA channels 9-7,
- * respectively. Bits 8-31 are reserved.
- *
- * DMA Interrupt Status Register
- * DMA Interrupt Terminal Count Request Status Register
- * DMA Interrupt Terminal Count Request Clear Register
- * DMA Interrupt Error Status Register
- * DMA Interrupt Error Clear Register
- * DMA Raw Interrupt Terminal Count Status Register
- * DMA Raw Error Interrupt Status Register
- * DMA Enabled Channel Register
- */
-
-#define DMACH(n) (1 << (n)) /* n=0,1,...7 */
-
-/* For each of the following registers, bits 0-15 represent a set of encoded
- * DMA sources. Bits 16-31 are reserved in each case.
- *
- * DMA Software Burst Request Register
- * DMA Software Single Request Register
- * DMA Software Last Burst Request Register
- * DMA Software Last Single Request Register
- * DMA Synchronization Register
- */
-
-#define DMA_REQ_SSP0TX_BIT (1 << DMA_REQ_SSP0TX)
-#define DMA_REQ_SSP0RX_BIT (1 << DMA_REQ_SSP0RX)
-#define DMA_REQ_SSP1TX_BIT (1 << DMA_REQ_SSP1TX)
-#define DMA_REQ_SSP1RX_BIT (1 << DMA_REQ_SSP0RX)
-#define DMA_REQ_ADC_BIT (1 << DMA_REQ_ADC)
-#define DMA_REQ_I2SCH0_BIT (1 << DMA_REQ_I2SCH0)
-#define DMA_REQ_I2SCH1_BIT (1 << DMA_REQ_I2SCH1)
-#define DMA_REQ_DAC_BIT (1 << DMA_REQ_DAC)
-
-#define DMA_REQ_UART0TX_BIT (1 << DMA_REQ_UART0TX)
-#define DMA_REQ_UART0RX_BIT (1 << DMA_REQ_UART0RX)
-#define DMA_REQ_UART1TX_BIT (1 << DMA_REQ_UART1TX)
-#define DMA_REQ_UART1RX_BIT (1 << DMA_REQ_UART1RX)
-#define DMA_REQ_UART2TX_BIT (1 << DMA_REQ_UART2TX)
-#define DMA_REQ_UART2RX_BIT (1 << DMA_REQ_UART2RX)
-#define DMA_REQ_UART3TX_BIT (1 << DMA_REQ_UART3TX)
-#define DMA_REQ_UART3RX_BIT (1 << DMA_REQ_UART3RX)
-
-#define DMA_REQ_MAT0p0_BIT (1 << DMA_REQ_MAT0p0)
-#define DMA_REQ_MAT0p1_BIT (1 << DMA_REQ_MAT0p1)
-#define DMA_REQ_MAT1p0_BIT (1 << DMA_REQ_MAT1p0)
-#define DMA_REQ_MAT1p1_BIT (1 << DMA_REQ_MAT1p1)
-#define DMA_REQ_MAT2p0_BIT (1 << DMA_REQ_MAT2p0)
-#define DMA_REQ_MAT2p1_BIT (1 << DMA_REQ_MAT2p1)
-#define DMA_REQ_MAT3p0_BIT (1 << DMA_REQ_MAT3p0)
-#define DMA_REQ_MAT3p1_BIT (1 << DMA_REQ_MAT3p1)
-
-/* DMA Configuration Register */
-
-#define DMA_CONFIG_E (1 << 0) /* Bit 0: DMA Controller enable */
-#define DMA_CONFIG_M (1 << 1) /* Bit 1: AHB Master endianness configuration */
- /* Bits 2-31: Reserved */
-/* Channel Registers */
-
-/* DMA Channel Source Address Register (Bits 0-31: Source Address) */
-/* DMA Channel Destination Address Register Bits 0-31: Destination Address) */
-/* DMA Channel Linked List Item Register (Bits 0-31: Address of next link list
- * item. Bits 0-1 must be zero.
- */
-
-/* DMA Channel Control Register */
-
-#define DMACH_CONTROL_XFRSIZE_SHIFT (0) /* Bits 0-11: Transfer size */
-#define DMACH_CONTROL_XFRSIZE_MASK (0x0fff << DMACH_CONTROL_XFRSIZE_SHIFT)
-#define DMACH_CONTROL_SBSIZE_SHIFT (12) /* Bits 12-14: Source burst size */
-#define DMACH_CONTROL_SBSIZE_MASK (7 << DMACH_CONTROL_SBSIZE_SHIFT)
-# define DMACH_CONTROL_SBSIZE_1 (0 << DMACH_CONTROL_SBSIZE_SHIFT)
-# define DMACH_CONTROL_SBSIZE_4 (1 << DMACH_CONTROL_SBSIZE_SHIFT)
-# define DMACH_CONTROL_SBSIZE_8 (2 << DMACH_CONTROL_SBSIZE_SHIFT)
-# define DMACH_CONTROL_SBSIZE_16 (3 << DMACH_CONTROL_SBSIZE_SHIFT)
-# define DMACH_CONTROL_SBSIZE_32 (4 << DMACH_CONTROL_SBSIZE_SHIFT)
-# define DMACH_CONTROL_SBSIZE_64 (5 << DMACH_CONTROL_SBSIZE_SHIFT)
-# define DMACH_CONTROL_SBSIZE_128 (6 << DMACH_CONTROL_SBSIZE_SHIFT)
-# define DMACH_CONTROL_SBSIZE_256 (7 << DMACH_CONTROL_SBSIZE_SHIFT)
-#define DMACH_CONTROL_DBSIZE_SHIFT (15) /* Bits 15-17: Destination burst size */
-#define DMACH_CONTROL_DBSIZE_MASK (7 << DMACH_CONTROL_DBSIZE_SHIFT)
-# define DMACH_CONTROL_DBSIZE_1 (0 << DMACH_CONTROL_DBSIZE_SHIFT)
-# define DMACH_CONTROL_DBSIZE_4 (1 << DMACH_CONTROL_DBSIZE_SHIFT)
-# define DMACH_CONTROL_DBSIZE_8 (2 << DMACH_CONTROL_DBSIZE_SHIFT)
-# define DMACH_CONTROL_DBSIZE_16 (3 << DMACH_CONTROL_DBSIZE_SHIFT)
-# define DMACH_CONTROL_DBSIZE_32 (4 << DMACH_CONTROL_DBSIZE_SHIFT)
-# define DMACH_CONTROL_DBSIZE_64 (5 << DMACH_CONTROL_DBSIZE_SHIFT)
-# define DMACH_CONTROL_DBSIZE_128 (6 << DMACH_CONTROL_DBSIZE_SHIFT)
-# define DMACH_CONTROL_DBSIZE_256 (7 << DMACH_CONTROL_DBSIZE_SHIFT)
-#define DMACH_CONTROL_SWIDTH_SHIFT (18) /* Bits 18-20: Source transfer width */
-#define DMACH_CONTROL_SWIDTH_MASK (7 << DMACH_CONTROL_SWIDTH_SHIFT)
-#define DMACH_CONTROL_DWIDTH_SHIFT (21) /* Bits 21-23: Destination transfer width */
-#define DMACH_CONTROL_DWIDTH_MASK (7 << DMACH_CONTROL_DWIDTH_SHIFT)
-#define DMACH_CONTROL_SI (1 << 26) /* Bit 26: Source increment */
-#define DMACH_CONTROL_DI (1 << 27) /* Bit 27: Destination increment */
-#define DMACH_CONTROL_PROT1 (1 << 28) /* Bit 28: User/priviledged mode */
-#define DMACH_CONTROL_PROT2 (1 << 29) /* Bit 29: Bufferable */
-#define DMACH_CONTROL_PROT3 (1 << 30) /* Bit 30: Cacheable */
-#define DMACH_CONTROL_I (1 << 31) /* Bit 31: Terminal count interrupt enable */
-
-/* DMA Channel Configuration Register */
-
-
-#define DMACH_CONFIG_E (1 << 0) /* Bit 0: Channel enable */
-#define DMACH_CONFIG_SRCPER_SHIFT (1) /* Bits 1-5: Source peripheral */
-#define DMACH_CONFIG_SRCPER_MASK (31 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_SSP0TX (DMA_REQ_SSP0TX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_SSP0RX (DMA_REQ_SSP0RX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_SSP1TX (DMA_REQ_SSP1TX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_SSP1RX (DMA_REQ_SSP0RX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_ADC (DMA_REQ_ADC << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_I2SCH0 (DMA_REQ_I2SCH0 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_I2SCH1 (DMA_REQ_I2SCH1 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_DAC (DMA_REQ_DAC << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_UART0TX (DMA_REQ_UART0TX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_UART0RX (DMA_REQ_UART0RX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_UART1TX (DMA_REQ_UART1TX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_UART1RX (DMA_REQ_UART1RX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_UART2TX (DMA_REQ_UART2TX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_UART2RX (DMA_REQ_UART2RX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_UART3TX (DMA_REQ_UART3TX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_UART3RX (DMA_REQ_UART3RX << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_MAT0p0 (DMA_REQ_MAT0p0 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_MAT0p1 (DMA_REQ_MAT0p1 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_MAT1p0 (DMA_REQ_MAT1p0 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_MAT1p1 (DMA_REQ_MAT1p1 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_MAT2p0 (DMA_REQ_MAT2p0 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_MAT2p1 (DMA_REQ_MAT2p1 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_MAT3p0 (DMA_REQ_MAT3p0 << DMACH_CONFIG_SRCPER_SHIFT)
-# define DMACH_CONFIG_SRCPER_MAT3p1 (DMA_REQ_MAT3p1 << DMACH_CONFIG_SRCPER_SHIFT)
-#define DMACH_CONFIG_DSTPER_SHIFT (6) /* Bits 6-10: Source peripheral */
-#define DMACH_CONFIG_DSTPER_MASK (31 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_SSP0TX (DMA_REQ_SSP0TX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_SSP0RX (DMA_REQ_SSP0RX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_SSP1TX (DMA_REQ_SSP1TX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_SSP1RX (DMA_REQ_SSP0RX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_ADC (DMA_REQ_ADC << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_I2SCH0 (DMA_REQ_I2SCH0 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_I2SCH1 (DMA_REQ_I2SCH1 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_DAC (DMA_REQ_DAC << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_UART0TX (DMA_REQ_UART0TX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_UART0RX (DMA_REQ_UART0RX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_UART1TX (DMA_REQ_UART1TX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_UART1RX (DMA_REQ_UART1RX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_UART2TX (DMA_REQ_UART2TX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_UART2RX (DMA_REQ_UART2RX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_UART3TX (DMA_REQ_UART3TX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_UART3RX (DMA_REQ_UART3RX << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_MAT0p0 (DMA_REQ_MAT0p0 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_MAT0p1 (DMA_REQ_MAT0p1 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_MAT1p0 (DMA_REQ_MAT1p0 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_MAT1p1 (DMA_REQ_MAT1p1 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_MAT2p0 (DMA_REQ_MAT2p0 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_MAT2p1 (DMA_REQ_MAT2p1 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_MAT3p0 (DMA_REQ_MAT3p0 << DMACH_CONFIG_DSTPER_SHIFT)
-# define DMACH_CONFIG_DSTPER_MAT3p1 (DMA_REQ_MAT3p1 << DMACH_CONFIG_DSTPER_SHIFT)
-#define DMACH_CONFIG_XFRTYPE_SHIFT (11) /* Bits 11-13: Type of transfer */
-#define DMACH_CONFIG_XFRTYPE_MASK (7 << DMACH_CONFIG_XFRTYPE_SHIFT)
-# define DMACH_CONFIG_XFRTYPE_M2M (0 << DMACH_CONFIG_XFRTYPE_SHIFT) /* Memory to memory DMA */
-# define DMACH_CONFIG_XFRTYPE_M2P (1 << DMACH_CONFIG_XFRTYPE_SHIFT) /* Memory to peripheral DMA */
-# define DMACH_CONFIG_XFRTYPE_P2M (2 << DMACH_CONFIG_XFRTYPE_SHIFT) /* Peripheral to memory DMA */
-# define DMACH_CONFIG_XFRTYPE_P2P (3 << DMACH_CONFIG_XFRTYPE_SHIFT) /* Peripheral to peripheral DMA */
-#define DMACH_CONFIG_IE (1 << 14) /* Bit 14: Interrupt error mask */
-#define DMACH_CONFIG_ ITC (1 << 15) /* Bit 15: Terminal count interrupt mask */
-#define DMACH_CONFIG_L (1 << 16) /* Bit 16: Lock */
-#define DMACH_CONFIG_A (1 << 17) /* Bit 17: Active */
-#define DMACH_CONFIG_H (1 << 18) /* Bit 18: Halt */
- /* Bits 19-31: Reserved */
-
/************************************************************************************
* Public Types
************************************************************************************/
+#ifdef CONFIG_LPC17_GPDMA
+
+typedef FAR void *DMA_HANDLE;
+typedef void (*dma_callback_t)(DMA_HANDLE handle, void *arg, int result);
+
+/* The following is used for sampling DMA registers when CONFIG DEBUG_DMA is selected */
+
+#ifdef CONFIG_DEBUG_DMA
+struct lpc17_dmaglobalregs_s
+{
+ /* Global Registers */
+
+ uint32_t intst; /* DMA Interrupt Status Register */
+ uint32_t inttcst; /* DMA Interrupt Terminal Count Request Status Register */
+ uint32_t interrst; /* DMA Interrupt Error Status Register */
+ uint32_t rawinttcst; /* DMA Raw Interrupt Terminal Count Status Register */
+ uint32_t rawinterrst; /* DMA Raw Error Interrupt Status Register */
+ uint32_t enbldchns; /* DMA Enabled Channel Register */
+ uint32_t softbreq; /* DMA Software Burst Request Register */
+ uint32_t softsreq; /* DMA Software Single Request Register */
+ uint32_t softlbreq; /* DMA Software Last Burst Request Register */
+ uint32_t softlsreq; /* DMA Software Last Single Request Register */
+ uint32_t config; /* DMA Configuration Register */
+ uint32_t sync; /* DMA Synchronization Register */
+};
+
+struct lpc17_dmachanregs_s
+{
+ /* Channel Registers */
+
+ uint32_t srcaddr; /* DMA Channel Source Address Register */
+ uint32_t destaddr; /* DMA Channel Destination Address Register */
+ uint32_t lli; /* DMA Channel Linked List Item Register */
+ uint32_t control; /* DMA Channel Control Register */
+ uint32_t config; /* DMA Channel Configuration Register */
+};
+
+struct lpc17_dmaregs_s
+{
+ /* Global Registers */
+
+ struct lpc17_dmaglobalregs_s gbl;
+
+ /* Channel Registers */
+
+ struct lpc17_dmachanregs_s ch;
+};
+
+#endif /* CONFIG_DEBUG_DMA */
+
/************************************************************************************
* Public Data
************************************************************************************/
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
/************************************************************************************
* Public Functions
************************************************************************************/
+/****************************************************************************
+ * Name: lpc17_dmainitialize
+ *
+ * Description:
+ * Initialize the GPDMA subsystem.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void lpc17_dmainitilaize(void);
+
+/****************************************************************************
+ * Name: lpc17_dmachannel
+ *
+ * Description:
+ * Allocate a DMA channel. This function sets aside a DMA channel and
+ * gives the caller exclusive access to the DMA channel.
+ *
+ * Returned Value:
+ * One success, this function returns a non-NULL, void* DMA channel
+ * handle. NULL is returned on any failure. This function can fail only
+ * if no DMA channel is available.
+ *
+ ****************************************************************************/
+
+DMA_HANDLE lpc17_dmachannel(void);
+
+/****************************************************************************
+ * Name: lpc17_dmafree
+ *
+ * Description:
+ * Release a DMA channel. NOTE: The 'handle' used in this argument must
+ * NEVER be used again until lpc17_dmachannel() is called again to re-gain
+ * a valid handle.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void lpc17_dmafree(DMA_HANDLE handle);
+
+/****************************************************************************
+ * Name: lpc17_dmasetup
+ *
+ * Description:
+ * Configure DMA for one transfer.
+ *
+ ****************************************************************************/
+
+int lpc17_dmarxsetup(DMA_HANDLE handle, uint32_t control, uint32_t config,
+ uint32_t srcaddr, uint32_t destaddr, size_t nbytes);
+
+/****************************************************************************
+ * Name: lpc17_dmastart
+ *
+ * Description:
+ * Start the DMA transfer
+ *
+ ****************************************************************************/
+
+int lpc17_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg);
+
+/****************************************************************************
+ * Name: lpc17_dmastop
+ *
+ * Description:
+ * Cancel the DMA. After lpc17_dmastop() is called, the DMA channel is
+ * reset and lpc17_dmasetup() must be called before lpc17_dmastart() can be
+ * called again
+ *
+ ****************************************************************************/
+
+void lpc17_dmastop(DMA_HANDLE handle);
+
+/****************************************************************************
+ * Name: lpc17_dmasample
+ *
+ * Description:
+ * Sample DMA register contents
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG_DMA
+EXTERN void lpc17_dmasample(DMA_HANDLE handle, struct lpc17_dmaregs_s *regs);
+#else
+# define lpc17_dmasample(handle,regs)
+#endif
+
+/****************************************************************************
+ * Name: lpc17_dmadump
+ *
+ * Description:
+ * Dump previously sampled DMA register contents
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG_DMA
+EXTERN void lpc17_dmadump(DMA_HANDLE handle, const struct lpc17_dmaregs_s *regs,
+ const char *msg);
+#else
+# define lpc17_dmadump(handle,regs,msg)
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_LPC17_GPDMA */
#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_GPDMA_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
index 4cc73a3fc..9db9b136b 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
+#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <errno.h>
@@ -49,8 +50,7 @@
#include "up_arch.h"
#include "chip.h"
#include "lpc17_gpio.h"
-#include "lpc17_pinconn.h"
-#include "lpc17_internal.h"
+
/****************************************************************************
* Pre-processor Definitions
@@ -199,6 +199,7 @@ static int lpc17_pinsel(unsigned int port, unsigned int pin, unsigned int value)
putreg32(regval, regaddr);
return OK;
}
+
return -EINVAL;
}
@@ -265,6 +266,7 @@ static int lpc17_pullup(uint16_t cfgset, unsigned int port, unsigned int pin)
putreg32(regval, regaddr);
return OK;
}
+
return -EINVAL;
}
@@ -518,6 +520,7 @@ static int lpc17_configalternate(uint16_t cfgset, unsigned int port,
lpc17_setopendrain(port, pin);
}
+
return OK;
}
@@ -582,6 +585,7 @@ int lpc17_configgpio(uint16_t cfgset)
break;
}
}
+
return ret;
}
@@ -651,5 +655,6 @@ bool lpc17_gpioread(uint16_t pinset)
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
return ((getreg32(fiobase + LPC17_FIO_PIN_OFFSET) & (1 << pin)) != 0);
}
- return 0;
+
+ return false;
}
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h
index 002ef3faf..dad14bc9e 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_gpio.h
*
- * 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
@@ -42,144 +42,128 @@
#include <nuttx/config.h>
-#include "chip.h"
-#include "lpc17_memorymap.h"
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+
+#include "chip/lpc17_gpio.h"
+#include "chip/lpc17_pinconn.h"
+#include "chip/lpc17_pinconfig.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
+/* Bit-encoded input to lpc17_configgpio() ******************************************/
-/* Register offsets *****************************************************************/
-/* GPIO block register offsets ******************************************************/
-
-#define LPC17_FIO0_OFFSET 0x0000
-#define LPC17_FIO1_OFFSET 0x0020
-#define LPC17_FIO2_OFFSET 0x0040
-#define LPC17_FIO3_OFFSET 0x0060
-#define LPC17_FIO4_OFFSET 0x0080
-
-#define LPC17_FIO_DIR_OFFSET 0x0000 /* Fast GPIO Port Direction control */
-#define LPC17_FIO_MASK_OFFSET 0x0010 /* Fast Mask register for ports */
-#define LPC17_FIO_PIN_OFFSET 0x0014 /* Fast Port Pin value registers */
-#define LPC17_FIO_SET_OFFSET 0x0018 /* Fast Port Output Set registers */
-#define LPC17_FIO_CLR_OFFSET 0x001c /* Fast Port Output Clear register */
-
-/* GPIO interrupt block register offsets ********************************************/
-
-#define LPC17_GPIOINT_OFFSET(n) (0x10*(n) + 0x80)
-#define LPC17_GPIOINT0_OFFSET 0x0080
-#define LPC17_GPIOINT2_OFFSET 0x00a0
-
-#define LPC17_GPIOINT_IOINTSTATUS_OFFSET 0x0000 /* GPIO overall Interrupt Status */
-#define LPC17_GPIOINT_INTSTATR_OFFSET 0x0004 /* GPIO Interrupt Status Rising edge */
-#define LPC17_GPIOINT_INTSTATF_OFFSET 0x0008 /* GPIO Interrupt Status Falling edge */
-#define LPC17_GPIOINT_INTCLR_OFFSET 0x000c /* GPIO Interrupt Clear */
-#define LPC17_GPIOINT_INTENR_OFFSET 0x0010 /* GPIO Interrupt Enable Rising edge */
-#define LPC17_GPIOINT_INTENF_OFFSET 0x0014 /* GPIO Interrupt Enable Falling edge */
-
-/* Register addresses ***************************************************************/
-/* GPIO block register addresses ****************************************************/
-
-#define LPC17_FIO_BASE(n) (LPC17_GPIO_BASE+LPC17_GPIOINT_OFFSET(n))
-#define LPC17_FIO0_BASE (LPC17_GPIO_BASE+LPC17_FIO0_OFFSET)
-#define LPC17_FIO1_BASE (LPC17_GPIO_BASE+LPC17_FIO1_OFFSET)
-#define LPC17_FIO2_BASE (LPC17_GPIO_BASE+LPC17_FIO2_OFFSET)
-#define LPC17_FIO3_BASE (LPC17_GPIO_BASE+LPC17_FIO3_OFFSET)
-#define LPC17_FIO4_BASE (LPC17_GPIO_BASE+LPC17_FIO4_OFFSET)
-
-#define LPC17_FIO_DIR(n) (LPC17_FIO_BASE(n)+LPC17_FIO_DIR_OFFSET)
-#define LPC17_FIO_MASK(n) (LPC17_FIO_BASE(n)+LPC17_FIO_MASK_OFFSET)
-#define LPC17_FIO_PIN(n) (LPC17_FIO_BASE(n)+LPC17_FIO_PIN_OFFSET)
-#define LPC17_FIO_SET(n) (LPC17_FIO_BASE(n)+LPC17_FIO_SET_OFFSET)
-#define LPC17_FIO_CLR(n) (LPC17_FIO_BASE(n)+LPC17_FIO_CLR_OFFSET)
-
-#define LPC17_FIO0_DIR (LPC17_FIO0_BASE+LPC17_FIO_DIR_OFFSET)
-#define LPC17_FIO0_MASK (LPC17_FIO0_BASE+LPC17_FIO_MASK_OFFSET)
-#define LPC17_FIO0_PIN (LPC17_FIO0_BASE+LPC17_FIO_PIN_OFFSET)
-#define LPC17_FIO0_SET (LPC17_FIO0_BASE+LPC17_FIO_SET_OFFSET)
-#define LPC17_FIO0_CLR (LPC17_FIO0_BASE+LPC17_FIO_CLR_OFFSET)
-
-#define LPC17_FIO1_DIR (LPC17_FIO1_BASE+LPC17_FIO_DIR_OFFSET)
-#define LPC17_FIO1_MASK (LPC17_FIO1_BASE+LPC17_FIO_MASK_OFFSET)
-#define LPC17_FIO1_PIN (LPC17_FIO1_BASE+LPC17_FIO_PIN_OFFSET)
-#define LPC17_FIO1_SET (LPC17_FIO1_BASE+LPC17_FIO_SET_OFFSET)
-#define LPC17_FIO1_CLR (LPC17_FIO1_BASE+LPC17_FIO_CLR_OFFSET)
-
-#define LPC17_FIO2_DIR (LPC17_FIO2_BASE+LPC17_FIO_DIR_OFFSET)
-#define LPC17_FIO2_MASK (LPC17_FIO2_BASE+LPC17_FIO_MASK_OFFSET)
-#define LPC17_FIO2_PIN (LPC17_FIO2_BASE+LPC17_FIO_PIN_OFFSET)
-#define LPC17_FIO2_SET (LPC17_FIO2_BASE+LPC17_FIO_SET_OFFSET)
-#define LPC17_FIO2_CLR (LPC17_FIO2_BASE+LPC17_FIO_CLR_OFFSET)
-
-#define LPC17_FIO3_DIR (LPC17_FIO3_BASE+LPC17_FIO_DIR_OFFSET)
-#define LPC17_FIO3_MASK (LPC17_FIO3_BASE+LPC17_FIO_MASK_OFFSET)
-#define LPC17_FIO3_PIN (LPC17_FIO3_BASE+LPC17_FIO_PIN_OFFSET)
-#define LPC17_FIO3_SET (LPC17_FIO3_BASE+LPC17_FIO_SET_OFFSET)
-#define LPC17_FIO3_CLR (LPC17_FIO3_BASE+LPC17_FIO_CLR_OFFSET)
-
-#define LPC17_FIO4_DIR (LPC17_FIO4_BASE+LPC17_FIO_DIR_OFFSET)
-#define LPC17_FIO4_MASK (LPC17_FIO4_BASE+LPC17_FIO_MASK_OFFSET)
-#define LPC17_FIO4_PIN (LPC17_FIO4_BASE+LPC17_FIO_PIN_OFFSET)
-#define LPC17_FIO4_SET (LPC17_FIO4_BASE+LPC17_FIO_SET_OFFSET)
-#define LPC17_FIO4_CLR (LPC17_FIO4_BASE+LPC17_FIO_CLR_OFFSET)
-
-/* GPIO interrupt block register addresses ******************************************/
-
-#define LPC17_GPIOINTn_BASE(n) (LPC17_GPIOINT_BASE+LPC17_GPIOINT_OFFSET(n))
-#define LPC17_GPIOINT0_BASE (LPC17_GPIOINT_BASE+LPC17_GPIOINT0_OFFSET)
-#define LPC17_GPIOINT2_BASE (LPC17_GPIOINT_BASE+LPC17_GPIOINT2_OFFSET)
-
-#define LPC17_GPIOINT_IOINTSTATUS (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_IOINTSTATUS_OFFSET)
-
-#define LPC17_GPIOINT_INTSTATR(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTSTATR_OFFSET)
-#define LPC17_GPIOINT_INTSTATF(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTSTATF_OFFSET)
-#define LPC17_GPIOINT_INTCLR(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTCLR_OFFSET)
-#define LPC17_GPIOINT_INTENR(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTENR_OFFSET)
-#define LPC17_GPIOINT_INTENF(n) (LPC17_GPIOINTn_BASE(n)+LPC17_GPIOINT_INTENF_OFFSET)
-
-/* Pins P0.0-31 (P0.12-14 nad P0.31 are reserved) */
-
-#define LPC17_GPIOINT0_INTSTATR (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTSTATR_OFFSET)
-#define LPC17_GPIOINT0_INTSTATF (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTSTATF_OFFSET)
-#define LPC17_GPIOINT0_INTCLR (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTCLR_OFFSET)
-#define LPC17_GPIOINT0_INTENR (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTENR_OFFSET)
-#define LPC17_GPIOINT0_INTENF (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTENF_OFFSET)
-
-/* Pins P2.0-13 (P0.14-31 are reserved) */
-
-#define LPC17_GPIOINT2_INTSTATR (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTSTATR_OFFSET)
-#define LPC17_GPIOINT2_INTSTATF (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTSTATF_OFFSET)
-#define LPC17_GPIOINT2_INTCLR (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTCLR_OFFSET)
-#define LPC17_GPIOINT2_INTENR (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTENR_OFFSET)
-#define LPC17_GPIOINT2_INTENF (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTENF_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* GPIO block register bit definitions **********************************************/
-
-/* Fast GPIO Port Direction control registers (FIODIR) */
-/* Fast Mask register for ports (FIOMASK) */
-/* Fast Port Pin value registers using FIOMASK (FIOPIN) */
-/* Fast Port Output Set registers using FIOMASK (FIOSET) */
-/* Fast Port Output Clear register using FIOMASK (FIOCLR) */
-
-#define FIO(n) (1 << (n)) /* n=0,1,..31 */
-
-/* GPIO interrupt block register bit definitions ************************************/
-
-/* GPIO overall Interrupt Status (IOINTSTATUS) */
-#define GPIOINT_IOINTSTATUS_P0INT (1 << 0) /* Bit 0: Port 0 GPIO interrupt pending */
- /* Bit 1: Reserved */
-#define GPIOINT_IOINTSTATUS_P2INT (1 << 2) /* Bit 2: Port 2 GPIO interrupt pending */
- /* Bits 3-31: Reserved */
-
-/* GPIO Interrupt Status for Rising edge (INTSTATR)
- * GPIO Interrupt Status for Falling edge (INTSTATF)
- * GPIO Interrupt Clear (INTCLR)
- * GPIO Interrupt Enable for Rising edge (INTENR)
- * GPIO Interrupt Enable for Falling edge (INTENF)
+/* Encoding: FFFx MMOV PPPN NNNN
+ *
+ * Pin Function: FFF
+ * Pin Mode bits: MM
+ * Open drain: O (output pins)
+ * Initial value: V (output pins)
+ * Port number: PPP (0-4)
+ * Pin number: NNNNN (0-31)
+ */
+
+/* Pin Function bits: FFF
+ * Only meaningful when the GPIO function is GPIO_PIN
*/
-#define GPIOINT(n) (1 << (n)) /* n=0,1,..31 */
+#define GPIO_FUNC_SHIFT (13) /* Bits 13-15: GPIO mode */
+#define GPIO_FUNC_MASK (7 << GPIO_FUNC_SHIFT)
+# define GPIO_INPUT (0 << GPIO_FUNC_SHIFT) /* 000 GPIO input pin */
+# define GPIO_INTFE (1 << GPIO_FUNC_SHIFT) /* 001 GPIO interrupt falling edge */
+# define GPIO_INTRE (2 << GPIO_FUNC_SHIFT) /* 010 GPIO interrupt rising edge */
+# define GPIO_INTBOTH (3 << GPIO_FUNC_SHIFT) /* 011 GPIO interrupt both edges */
+# define GPIO_OUTPUT (4 << GPIO_FUNC_SHIFT) /* 100 GPIO outpout pin */
+# define GPIO_ALT1 (5 << GPIO_FUNC_SHIFT) /* 101 Alternate function 1 */
+# define GPIO_ALT2 (6 << GPIO_FUNC_SHIFT) /* 110 Alternate function 2 */
+# define GPIO_ALT3 (7 << GPIO_FUNC_SHIFT) /* 111 Alternate function 3 */
+
+#define GPIO_EDGE_SHIFT (13) /* Bits 13-14: Interrupt edge bits */
+#define GPIO_EDGE_MASK (3 << GPIO_EDGE_SHIFT)
+
+#define GPIO_INOUT_MASK GPIO_OUTPUT
+#define GPIO_FE_MASK GPIO_INTFE
+#define GPIO_RE_MASK GPIO_INTRE
+
+#define GPIO_ISGPIO(ps) ((uint16_t(ps) & GPIO_FUNC_MASK) <= GPIO_OUTPUT)
+#define GPIO_ISALT(ps) ((uint16_t(ps) & GPIO_FUNC_MASK) > GPIO_OUTPUT)
+#define GPIO_ISINPUT(ps) (((ps) & GPIO_FUNC_MASK) == GPIO_INPUT)
+#define GPIO_ISOUTPUT(ps) (((ps) & GPIO_FUNC_MASK) == GPIO_OUTPUT)
+#define GPIO_ISINORINT(ps) (((ps) & GPIO_INOUT_MASK) == 0)
+#define GPIO_ISOUTORALT(ps) (((ps) & GPIO_INOUT_MASK) != 0)
+#define GPIO_ISINTERRUPT(ps) (GPIO_ISOUTPUT(ps) && !GPIO_ISINPUT(ps))
+#define GPIO_ISFE(ps) (((ps) & GPIO_FE_MASK) != 0)
+#define GPIO_ISRE(ps) (((ps) & GPIO_RE_MASK) != 0)
+
+/* Pin Mode: MM */
+
+#define GPIO_PUMODE_SHIFT (10) /* Bits 10-11: Pin pull-up mode */
+#define GPIO_PUMODE_MASK (3 << GPIO_PUMODE_SHIFT)
+# define GPIO_PULLUP (0 << GPIO_PUMODE_SHIFT) /* Pull-up resistor enabled */
+# define GPIO_REPEATER (1 << GPIO_PUMODE_SHIFT) /* Repeater mode enabled */
+# define GPIO_FLOAT (2 << GPIO_PUMODE_SHIFT) /* Neither pull-up nor -down */
+# define GPIO_PULLDN (3 << GPIO_PUMODE_SHIFT) /* Pull-down resistor enabled */
+
+/* Open drain: O */
+
+#define GPIO_OPEN_DRAIN (1 << 9) /* Bit 9: Open drain mode */
+
+/* Initial value: V */
+
+#define GPIO_VALUE (1 << 8) /* Bit 8: Initial GPIO output value */
+#define GPIO_VALUE_ONE GPIO_VALUE
+#define GPIO_VALUE_ZERO (0)
+
+/* Port number: PPP (0-4) */
+
+#define GPIO_PORT_SHIFT (5) /* Bit 5-7: Port number */
+#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT)
+# define GPIO_PORT0 (0 << GPIO_PORT_SHIFT)
+# define GPIO_PORT1 (1 << GPIO_PORT_SHIFT)
+# define GPIO_PORT2 (2 << GPIO_PORT_SHIFT)
+# define GPIO_PORT3 (3 << GPIO_PORT_SHIFT)
+# define GPIO_PORT4 (4 << GPIO_PORT_SHIFT)
+
+#define GPIO_NPORTS 5
+
+/* Pin number: NNNNN (0-31) */
+
+#define GPIO_PIN_SHIFT 0 /* Bits 0-4: GPIO number: 0-31 */
+#define GPIO_PIN_MASK (31 << GPIO_PIN_SHIFT)
+#define GPIO_PIN0 (0 << GPIO_PIN_SHIFT)
+#define GPIO_PIN1 (1 << GPIO_PIN_SHIFT)
+#define GPIO_PIN2 (2 << GPIO_PIN_SHIFT)
+#define GPIO_PIN3 (3 << GPIO_PIN_SHIFT)
+#define GPIO_PIN4 (4 << GPIO_PIN_SHIFT)
+#define GPIO_PIN5 (5 << GPIO_PIN_SHIFT)
+#define GPIO_PIN6 (6 << GPIO_PIN_SHIFT)
+#define GPIO_PIN7 (7 << GPIO_PIN_SHIFT)
+#define GPIO_PIN8 (8 << GPIO_PIN_SHIFT)
+#define GPIO_PIN9 (9 << GPIO_PIN_SHIFT)
+#define GPIO_PIN10 (10 << GPIO_PIN_SHIFT)
+#define GPIO_PIN11 (11 << GPIO_PIN_SHIFT)
+#define GPIO_PIN12 (12 << GPIO_PIN_SHIFT)
+#define GPIO_PIN13 (13 << GPIO_PIN_SHIFT)
+#define GPIO_PIN14 (14 << GPIO_PIN_SHIFT)
+#define GPIO_PIN15 (15 << GPIO_PIN_SHIFT)
+#define GPIO_PIN16 (16 << GPIO_PIN_SHIFT)
+#define GPIO_PIN17 (17 << GPIO_PIN_SHIFT)
+#define GPIO_PIN18 (18 << GPIO_PIN_SHIFT)
+#define GPIO_PIN19 (19 << GPIO_PIN_SHIFT)
+#define GPIO_PIN20 (20 << GPIO_PIN_SHIFT)
+#define GPIO_PIN21 (21 << GPIO_PIN_SHIFT)
+#define GPIO_PIN22 (22 << GPIO_PIN_SHIFT)
+#define GPIO_PIN23 (23 << GPIO_PIN_SHIFT)
+#define GPIO_PIN24 (24 << GPIO_PIN_SHIFT)
+#define GPIO_PIN25 (25 << GPIO_PIN_SHIFT)
+#define GPIO_PIN26 (26 << GPIO_PIN_SHIFT)
+#define GPIO_PIN27 (27 << GPIO_PIN_SHIFT)
+#define GPIO_PIN28 (28 << GPIO_PIN_SHIFT)
+#define GPIO_PIN29 (29 << GPIO_PIN_SHIFT)
+#define GPIO_PIN30 (30 << GPIO_PIN_SHIFT)
+#define GPIO_PIN31 (31 << GPIO_PIN_SHIFT)
/************************************************************************************
* Public Types
@@ -189,8 +173,40 @@
* Public Data
************************************************************************************/
-/************************************************************************************
+#ifndef __ASSEMBLY__
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/* These tables have global scope only because they are shared between lpc17_gpio.c,
+ * lpc17_gpioint.c, and lpc17_gpiodbg.c
+ */
+
+#ifdef CONFIG_GPIO_IRQ
+EXTERN uint64_t g_intedge0;
+EXTERN uint64_t g_intedge2;
+#endif
+
+EXTERN const uint32_t g_fiobase[GPIO_NPORTS];
+EXTERN const uint32_t g_intbase[GPIO_NPORTS];
+EXTERN const uint32_t g_lopinsel[GPIO_NPORTS];
+EXTERN const uint32_t g_hipinsel[GPIO_NPORTS];
+EXTERN const uint32_t g_lopinmode[GPIO_NPORTS];
+EXTERN const uint32_t g_hipinmode[GPIO_NPORTS];
+EXTERN const uint32_t g_odmode[GPIO_NPORTS];
+
+/****************************************************************************
* Public Functions
- ************************************************************************************/
+ ****************************************************************************/
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_GPIO_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpiodbg.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpiodbg.c
index dc4dac33a..9b16ce697 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpiodbg.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpiodbg.c
@@ -47,7 +47,7 @@
#include "up_arch.h"
#include "chip.h"
#include "lpc17_gpio.h"
-#include "lpc17_internal.h"
+
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c
index 66988b0b9..7f18a33b4 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c
@@ -50,8 +50,7 @@
#include "up_arch.h"
#include "chip.h"
#include "lpc17_gpio.h"
-#include "lpc17_pinconn.h"
-#include "lpc17_internal.h"
+
#ifdef CONFIG_GPIO_IRQ
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.c b/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.c
index 935dbfa0c..866a668ab 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.c
@@ -53,6 +53,7 @@
#include <stdlib.h>
#include <string.h>
#include <errno.h>
+#include <wdog.h>
#include <debug.h>
#include <nuttx/arch.h>
@@ -61,15 +62,13 @@
#include <arch/irq.h>
#include <arch/board/board.h>
-#include "wdog.h"
-#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "os_internal.h"
-#include "lpc17_internal.h"
-#include "lpc17_syscon.h"
-#include "lpc17_pinconn.h"
+#include "chip.h"
+#include "chip/lpc17_syscon.h"
+#include "lpc17_gpio.h"
#include "lpc17_i2c.h"
#if defined(CONFIG_LPC17_I2C0) || defined(CONFIG_LPC17_I2C1) || defined(CONFIG_LPC17_I2C2)
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.h b/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.h
index 10e1fbeac..5d229f452 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_i2c.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_i2c.h
*
- * 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
@@ -41,158 +41,12 @@
************************************************************************************/
#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_i2c.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-
-#define LPC17_I2C_CONSET_OFFSET 0x0000 /* I2C Control Set Register */
-#define LPC17_I2C_STAT_OFFSET 0x0004 /* I2C Status Register */
-#define LPC17_I2C_DAT_OFFSET 0x0008 /* I2C Data Register */
-#define LPC17_I2C_ADR0_OFFSET 0x000c /* I2C Slave Address Register 0 */
-#define LPC17_I2C_SCLH_OFFSET 0x0010 /* SCH Duty Cycle Register High Half Word */
-#define LPC17_I2C_SCLL_OFFSET 0x0014 /* SCL Duty Cycle Register Low Half Word */
-#define LPC17_I2C_CONCLR_OFFSET 0x0018 /* I2C Control Clear Register */
-#define LPC17_I2C_MMCTRL_OFFSET 0x001c /* Monitor mode control register */
-#define LPC17_I2C_ADR1_OFFSET 0x0020 /* I2C Slave Address Register 1 */
-#define LPC17_I2C_ADR2_OFFSET 0x0024 /* I2C Slave Address Register 2 */
-#define LPC17_I2C_ADR3_OFFSET 0x0028 /* I2C Slave Address Register 3 */
-#define LPC17_I2C_BUFR_OFFSET 0x002c /* Data buffer register */
-#define LPC17_I2C_MASK0_OFFSET 0x0030 /* I2C Slave address mask register 0 */
-#define LPC17_I2C_MASK1_OFFSET 0x0034 /* I2C Slave address mask register 1 */
-#define LPC17_I2C_MASK2_OFFSET 0x0038 /* I2C Slave address mask register 2 */
-#define LPC17_I2C_MASK3_OFFSET 0x003c /* I2C Slave address mask register */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_I2C0_CONSET (LPC17_I2C0_BASE+LPC17_I2C_CONSET_OFFSET)
-#define LPC17_I2C0_STAT (LPC17_I2C0_BASE+LPC17_I2C_STAT_OFFSET)
-#define LPC17_I2C0_DAT (LPC17_I2C0_BASE+LPC17_I2C_DAT_OFFSET)
-#define LPC17_I2C0_ADR0 (LPC17_I2C0_BASE+LPC17_I2C_ADR0_OFFSET)
-#define LPC17_I2C0_SCLH (LPC17_I2C0_BASE+LPC17_I2C_SCLH_OFFSET)
-#define LPC17_I2C0_SCLL (LPC17_I2C0_BASE+LPC17_I2C_SCLL_OFFSET)
-#define LPC17_I2C0_CONCLR (LPC17_I2C0_BASE+LPC17_I2C_CONCLR_OFFSET)
-#define LPC17_I2C0_MMCTRL (LPC17_I2C0_BASE+LPC17_I2C_MMCTRL_OFFSET)
-#define LPC17_I2C0_ADR1 (LPC17_I2C0_BASE+LPC17_I2C_ADR1_OFFSET)
-#define LPC17_I2C0_ADR2 (LPC17_I2C0_BASE+LPC17_I2C_ADR2_OFFSET)
-#define LPC17_I2C0_ADR3 (LPC17_I2C0_BASE+LPC17_I2C_ADR3_OFFSET)
-#define LPC17_I2C0_BUFR (LPC17_I2C0_BASE+LPC17_I2C_BUFR_OFFSET)
-#define LPC17_I2C0_MASK0 (LPC17_I2C0_BASE+LPC17_I2C_MASK0_OFFSET)
-#define LPC17_I2C0_MASK1 (LPC17_I2C0_BASE+LPC17_I2C_MASK1_OFFSET)
-#define LPC17_I2C0_MASK2 (LPC17_I2C0_BASE+LPC17_I2C_MASK2_OFFSET)
-#define LPC17_I2C0_MASK3 (LPC17_I2C0_BASE+LPC17_I2C_MASK3_OFFSET)
-
-#define LPC17_I2C1_CONSET (LPC17_I2C1_BASE+LPC17_I2C_CONSET_OFFSET)
-#define LPC17_I2C1_STAT (LPC17_I2C1_BASE+LPC17_I2C_STAT_OFFSET)
-#define LPC17_I2C1_DAT (LPC17_I2C1_BASE+LPC17_I2C_DAT_OFFSET)
-#define LPC17_I2C1_ADR0 (LPC17_I2C1_BASE+LPC17_I2C_ADR0_OFFSET)
-#define LPC17_I2C1_SCLH (LPC17_I2C1_BASE+LPC17_I2C_SCLH_OFFSET)
-#define LPC17_I2C1_SCLL (LPC17_I2C1_BASE+LPC17_I2C_SCLL_OFFSET)
-#define LPC17_I2C1_CONCLR (LPC17_I2C1_BASE+LPC17_I2C_CONCLR_OFFSET)
-#define LPC17_I2C1_MMCTRL (LPC17_I2C1_BASE+LPC17_I2C_MMCTRL_OFFSET)
-#define LPC17_I2C1_ADR1 (LPC17_I2C1_BASE+LPC17_I2C_ADR1_OFFSET)
-#define LPC17_I2C1_ADR2 (LPC17_I2C1_BASE+LPC17_I2C_ADR2_OFFSET)
-#define LPC17_I2C1_ADR3 (LPC17_I2C1_BASE+LPC17_I2C_ADR3_OFFSET)
-#define LPC17_I2C1_BUFR (LPC17_I2C1_BASE+LPC17_I2C_BUFR_OFFSET)
-#define LPC17_I2C1_MASK0 (LPC17_I2C1_BASE+LPC17_I2C_MASK0_OFFSET)
-#define LPC17_I2C1_MASK1 (LPC17_I2C1_BASE+LPC17_I2C_MASK1_OFFSET)
-#define LPC17_I2C1_MASK2 (LPC17_I2C1_BASE+LPC17_I2C_MASK2_OFFSET)
-#define LPC17_I2C1_MASK3 (LPC17_I2C1_BASE+LPC17_I2C_MASK3_OFFSET)
-
-#define LPC17_I2C2_CONSET (LPC17_I2C2_BASE+LPC17_I2C_CONSET_OFFSET)
-#define LPC17_I2C2_STAT (LPC17_I2C2_BASE+LPC17_I2C_STAT_OFFSET)
-#define LPC17_I2C2_DAT (LPC17_I2C2_BASE+LPC17_I2C_DAT_OFFSET)
-#define LPC17_I2C2_ADR0 (LPC17_I2C2_BASE+LPC17_I2C_ADR0_OFFSET)
-#define LPC17_I2C2_SCLH (LPC17_I2C2_BASE+LPC17_I2C_SCLH_OFFSET)
-#define LPC17_I2C2_SCLL (LPC17_I2C2_BASE+LPC17_I2C_SCLL_OFFSET)
-#define LPC17_I2C2_CONCLR (LPC17_I2C2_BASE+LPC17_I2C_CONCLR_OFFSET)
-#define LPC17_I2C2_MMCTRL (LPC17_I2C2_BASE+LPC17_I2C_MMCTRL_OFFSET)
-#define LPC17_I2C2_ADR1 (LPC17_I2C2_BASE+LPC17_I2C_ADR1_OFFSET)
-#define LPC17_I2C2_ADR2 (LPC17_I2C2_BASE+LPC17_I2C_ADR2_OFFSET)
-#define LPC17_I2C2_ADR3 (LPC17_I2C2_BASE+LPC17_I2C_ADR3_OFFSET)
-#define LPC17_I2C2_BUFR (LPC17_I2C2_BASE+LPC17_I2C_BUFR_OFFSET)
-#define LPC17_I2C2_MASK0 (LPC17_I2C2_BASE+LPC17_I2C_MASK0_OFFSET)
-#define LPC17_I2C2_MASK1 (LPC17_I2C2_BASE+LPC17_I2C_MASK1_OFFSET)
-#define LPC17_I2C2_MASK2 (LPC17_I2C2_BASE+LPC17_I2C_MASK2_OFFSET)
-#define LPC17_I2C2_MASK3 (LPC17_I2C2_BASE+LPC17_I2C_MASK3_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* I2C Control Set Register */
- /* Bits 0-1: Reserved */
-#define I2C_CONSET_AA (1 << 2) /* Bit 2: Assert acknowledge flag */
-#define I2C_CONSET_SI (1 << 3) /* Bit 3: I2C interrupt flag */
-#define I2C_CONSET_STO (1 << 4) /* Bit 4: STOP flag */
-#define I2C_CONSET_STA (1 << 5) /* Bit 5: START flag */
-#define I2C_CONSET_I2EN (1 << 6) /* Bit 6: I2C interface enable */
- /* Bits 7-31: Reserved */
-/* I2C Control Clear Register */
- /* Bits 0-1: Reserved */
-#define I2C_CONCLR_AAC (1 << 2) /* Bit 2: Assert acknowledge Clear bit */
-#define I2C_CONCLR_SIC (1 << 3) /* Bit 3: I2C interrupt Clear bit */
- /* Bit 4: Reserved */
-#define I2C_CONCLR_STAC (1 << 5) /* Bit 5: START flag Clear bit */
-#define I2C_CONCLRT_I2ENC (1 << 6) /* Bit 6: I2C interface Disable bit */
- /* Bits 7-31: Reserved */
-/* I2C Status Register
- *
- * See tables 399-402 in the "LPC17xx User Manual" (UM10360), Rev. 01, 4 January
- * 2010, NXP for definitions of status codes.
- */
-
-#define I2C_STAT_MASK (0xff) /* Bits 0-7: I2C interface status
- * Bits 0-1 always zero */
- /* Bits 8-31: Reserved */
-/* I2C Data Register */
-
-#define I2C_DAT_MASK (0xff) /* Bits 0-7: I2C data */
- /* Bits 8-31: Reserved */
-/* Monitor mode control register */
-
-#define I2C_MMCTRL_MMENA (1 << 0) /* Bit 0: Monitor mode enable */
-#define I2C_MMCTRL_ENASCL (1 << 1) /* Bit 1: SCL output enable */
-#define I2C_MMCTRL_MATCHALL (1 << 2) /* Bit 2: Select interrupt register match */
- /* Bits 3-31: Reserved */
-/* Data buffer register */
-
-#define I2C_BUFR_MASK (0xff) /* Bits 0-7: 8 MSBs of the I2DAT shift register */
- /* Bits 8-31: Reserved */
-/* I2C Slave address registers:
- *
- * I2C Slave Address Register 0
- * I2C Slave Address Register 1
- * I2C Slave Address Register 2
- * I2C Slave Address Register 3
- */
-
-#define I2C_ADR_GC (1 << 0) /* Bit 0: GC General Call enable bit */
-#define I2C_ADR_ADDR_SHIFT (1) /* Bits 1-7: I2C slave address */
-#define I2C_ADR_ADDR_MASK (0x7f << I2C_ADR_ADDR_SHIFT)
- /* Bits 8-31: Reserved */
-/* I2C Slave address mask registers:
- *
- * I2C Slave address mask register 0
- * I2C Slave address mask register 1
- * I2C Slave address mask register 2
- * I2C Slave address mask register 3
- */
- /* Bit 0: Reserved */
-#define I2C_MASK_SHIFT (1) /* Bits 1-7: I2C mask bits */
-#define I2C_MASK_MASK (0x7f << I2C_ADR_ADDR_SHIFT)
- /* Bits 8-31: Reserved */
-/* SCH Duty Cycle Register High Half Word */
-
-#define I2C_SCLH_MASK (0xffff) /* Bit 0-15: Count for SCL HIGH time period selection */
- /* Bits 16-31: Reserved */
-/* SCL Duty Cycle Register Low Half Word */
-
-#define I2C_SCLL_MASK (0xffff) /* Bit 0-15: Count for SCL LOW time period selection */
- /* Bits 16-31: Reserved */
-
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_i2s.h b/nuttx/arch/arm/src/lpc17xx/lpc17_i2s.h
index 638d40178..9b5e390d0 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_i2s.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_i2s.h
@@ -1,190 +1,190 @@
-/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_i2s
- *
- * Copyright (C) 2010, 2012 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_LPC17XX_LPC17_I2S_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_I2S_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
-
-/************************************************************************************
- * Pre-processor Definitions
- ************************************************************************************/
-
-/* Register offsets *****************************************************************/
-
-#define LPC17_I2S_DAO_OFFSET 0x0000 /* Digital Audio Output Register */
-#define LPC17_I2S_DAI_OFFSET 0x0004 /* Digital Audio Input Register */
-#define LPC17_I2S_TXFIFO_OFFSET 0x0008 /* Transmit FIFO */
-#define LPC17_I2S_RXFIFO_OFFSET 0x000c /* Receive FIFO */
-#define LPC17_I2S_STATE_OFFSET 0x0010 /* Status Feedback Register */
-#define LPC17_I2S_DMA1_OFFSET 0x0014 /* DMA Configuration Register 1 */
-#define LPC17_I2S_DMA2_OFFSET 0x0018 /* DMA Configuration Register 2 */
-#define LPC17_I2S_IRQ_OFFSET 0x001c /* Interrupt Request Control Register */
-#define LPC17_I2S_TXRATE_OFFSET 0x0020 /* Transmit MCLK divider */
-#define LPC17_I2S_RXRATE_OFFSET 0x0024 /* Receive MCLK divider */
-#define LPC17_I2S_TXBITRATE_OFFSET 0x0028 /* Transmit bit rate divider */
-#define LPC17_I2S_RXBITRATE_OFFSET 0x002c /* Receive bit rate divider */
-#define LPC17_I2S_TXMODE_OFFSET 0x0030 /* Transmit mode control */
-#define LPC17_I2S_RXMODE_OFFSET 0x0034 /* Receive mode control */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_I2S_DAO (LPC17_I2S_BASE+LPC17_I2S_DAO_OFFSET)
-#define LPC17_I2S_DAI (LPC17_I2S_BASE+LPC17_I2S_DAI_OFFSET)
-#define LPC17_I2S_TXFIFO (LPC17_I2S_BASE+LPC17_I2S_TXFIFO_OFFSET)
-#define LPC17_I2S_RXFIFO (LPC17_I2S_BASE+LPC17_I2S_RXFIFO_OFFSET)
-#define LPC17_I2S_STATE (LPC17_I2S_BASE+LPC17_I2S_STATE_OFFSET)
-#define LPC17_I2S_DMA1 (LPC17_I2S_BASE+LPC17_I2S_DMA1_OFFSET)
-#define LPC17_I2S_DMA2 (LPC17_I2S_BASE+LPC17_I2S_DMA2_OFFSET)
-#define LPC17_I2S_IRQ (LPC17_I2S_BASE+LPC17_I2S_IRQ_OFFSET)
-#define LPC17_I2S_TXRATE (LPC17_I2S_BASE+LPC17_I2S_TXRATE_OFFSET)
-#define LPC17_I2S_RXRATE (LPC17_I2S_BASE+LPC17_I2S_RXRATE_OFFSET)
-#define LPC17_I2S_TXBITRATE (LPC17_I2S_BASE+LPC17_I2S_TXBITRATE_OFFSET)
-#define LPC17_I2S_RXBITRATE (LPC17_I2S_BASE+LPC17_I2S_RXBITRATE_OFFSET)
-#define LPC17_I2S_TXMODE (LPC17_I2S_BASE+LPC17_I2S_TXMODE_OFFSET)
-#define LPC17_I2S_RXMODE (LPC17_I2S_BASE+LPC17_I2S_RXMODE_OFFSET)
-
-/* Register bit definitions *********************************************************/
-
-/* Digital Audio Output Register */
-
-#define I2S_DAO_WDWID_SHIFT (0) /* Bits 0-1: Selects the number of bytes in data */
-#define I2S_DAO_WDWID_MASK (3 << I2S_DAO_WDWID_SHIFT)
-# define I2S_DAO_WDWID_8BITS (0 << I2S_DAO_WDWID_SHIFT)
-# define I2S_DAO_WDWID_16BITS (1 << I2S_DAO_WDWID_SHIFT)
-# define I2S_DAO_WDWID_32BITS (3 << I2S_DAO_WDWID_SHIFT)
-#define I2S_DAO_MONO (1 << 2) /* Bit 2: Mono format */
-#define I2S_DAO_STOP (1 << 3) /* Bit 3: Disable FIFOs / mute mode */
-#define I2S_DAO_RESET (1 << 4) /* Bit 4: Reset TX channel and FIFO */
-#define I2S_DAO_WSSEL (1 << 5) /* Bit 5: Slave mode select */
-#define I2S_DAO_WSHALFPER_SHIFT (6) /* Bits 6-14: Word select half period minus 1 */
-#define I2S_DAO_WSHALFPER_MASK (0x01ff << I2S_DAO_WSHALFPER_SHIFT)
-#define I2S_DAO_MUTE (1 << 15) /* Bit 15: Send only zeros on channel */
- /* Bits 16-31: Reserved */
-/* Digital Audio Input Register */
-
-#define I2S_DAI_WDWID_SHIFT (0) /* Bits 0-1: Selects the number of bytes in data */
-#define I2S_DAI_WDWID_MASK (3 << I2S_DAI_WDWID_SHIFT)
-# define I2S_DAI_WDWID_8BITS (0 << I2S_DAI_WDWID_SHIFT)
-# define I2S_DAI_WDWID_16BITS (1 << I2S_DAI_WDWID_SHIFT)
-# define I2S_DAI_WDWID_32BITS (3 << I2S_DAI_WDWID_SHIFT)
-#define I2S_DAI_MONO (1 << 2) /* Bit 2: Mono format */
-#define I2S_DAI_STOP (1 << 3) /* Bit 3: Disable FIFOs / mute mode */
-#define I2S_DAI_RESET (1 << 4) /* Bit 4: Reset TX channel and FIFO */
-#define I2S_DAI_WSSEL (1 << 5) /* Bit 5: Slave mode select */
-#define I2S_DAI_WSHALFPER_SHIFT (6) /* Bits 6-14: Word select half period minus 1 */
-#define I2S_DAI_WSHALFPER_MASK (0x01ff << I2S_DAI_WSHALFPER_SHIFT)
- /* Bits 15-31: Reserved */
-/* Transmit FIFO: 8 × 32-bit transmit FIFO */
-/* Receive FIFO: 8 × 32-bit receive FIFO */
-
-/* Status Feedback Register */
-
-#define I2S_STATE_IRQ (1 << 0) /* Bit 0: Receive Transmit Interrupt */
-#define I2S_STATE_DMAREQ1 (1 << 1) /* Bit 1: Receive or Transmit DMA Request 1 */
-#define I2S_STATE_DMAREQ2 (1 << 2) /* Bit 2: Receive or Transmit DMA Request 2 */
- /* Bits 3-7: Reserved */
-#define I2S_STATE_RXLEVEL_SHIFT (8) /* Bits 8-11: Current level of the Receive FIFO */
-#define I2S_STATE_RXLEVEL_MASK (15 << I2S_STATE_RXLEVEL_SHIFT)
- /* Bits 12-15: Reserved */
-#define I2S_STATE_TXLEVEL_SHIFT (16) /* Bits 16-19: Current level of the Transmit FIFO */
-#define I2S_STATE_TXLEVEL_MASK (15 << I2S_STATE_TXLEVEL_SHIFT)
- /* Bits 20-31: Reserved */
-/* DMA Configuration Register 1 and 2 */
-
-#define I2S_DMA_RXDMAEN (1 << 0) /* Bit 0: Enable DMA1 for I2S receive */
-#define I2S_DMA_TXDMAEN (1 << 1) /* Bit 1: Enable DMA1 for I2S transmit */
- /* Bits 2-7: Reserved */
-#define I2S_DMA_RXDEPTH_SHIFT (8) /* Bits 8-11: FIFO level that triggers RX request on DMA1 */
-#define I2S_DMA_RXDEPTH_MASK (15 << I2S_DMA_RXDEPTH_SHIFT)
- /* Bits 12-15: Reserved */
-#define I2S_DMA_TXDEPTH_SHIFT (16) /* Bits 16-19: FIFO level that triggers a TX request on DMA1 */
-#define I2S_DMA_TXDEPTH_MASK (15 << I2S_DMA_TXDEPTH_SHIFT)
- /* Bits 20-31: Reserved */
-/* Interrupt Request Control Register */
-
-#define I2S_IRQ_RXEN (1 << 0) /* Bit 0: Enable I2S receive interrupt */
-#define I2S_IRQ_TXEN (1 << 1) /* Bit 1: Enable I2S transmit interrupt */
- /* Bits 2-7: Reserved */
-#define I2S_IRQ_RXDEPTH_SHIFT (8) /* Bits 8-11: Set FIFO level for irq request */
-#define I2S_IRQ_RXDEPTH_MASK (15 << I2S_IRQ_RXDEPTH_SHIFT)
- /* Bits 12-15: Reserved */
-#define I2S_IRQ_TXDEPTH_SHIFT (16) /* Bits 16-19: Set FIFO level for irq request */
-#define I2S_IRQ_TXDEPTH_MASK (15 << I2S_IRQ_TXDEPTH_SHIFT)
- /* Bits 20-31: Reserved */
-/* Transmit and Receive MCLK divider */
-
-#define I2S_RATE_YDIV_SHIFT (0) /* Bits 0-7: I2S transmit MCLK rate denominator */
-#define I2S_RATE_YDIV_MASK (0xff << I2S_RATE_YDIV_SHIFT)
-#define I2S_RATE_XDIV_SHIFT (8) /* Bits 8-15: I2S transmit MCLK rate numerator */
-#define I2S_RATE_XDIV_MASK (0xff << I2S_RATE_XDIV_SHIFT)
- /* Bits 16-31: Reserved */
-
-/* Transmit and received bit rate divider */
-
-#define I2S_BITRATE_SHIFT (0) /* Bits 0-5: I2S transmit bit rate */
-#define I2S_BITRATE_MASK (0x3f << I2S_BITRATE_SHIFT)
- /* Bits 6-31: Reserved */
-/* Transmit and Receive mode control */
-
-#define I2S_MODE_CLKSEL_SHIFT (0) /* Bits 0-1: Clock source for bit clock divider */
-#define I2S_MODE_CLKSEL_MASK (3 << I2S_MODE_CLKSEL_SHIFT)
-# define I2S_MODE_CLKSEL_FRACDIV (0 << I2S_MODE_CLKSEL_SHIFT) /* TX/RX fractional rate divider */
-# define I2S_MODE_CLKSEL_RXMCLK (2 << I2S_MODE_CLKSEL_SHIFT) /* RX_CLCK for TX_MCLK source */
-# define I2S_MODE_CLKSEL_TXMCLK (2 << I2S_MODE_CLKSEL_SHIFT) /* TX_CLCK for RX_MCLK source */
-#define I2S_MODE_4PIN (1 << 2) /* Bit 2: Transmit/Receive 4-pin mode selection */
-#define I2S_MODE_MCENA (1 << 3) /* Bit 3: Enable for the TX/RX_MCLK output */
- /* Bits 4-31: Reserved */
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
- * Public Data
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_I2S_H */
+/************************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_i2s
+ *
+ * Copyright (C) 2010, 2012 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_LPC17XX_LPC17_I2S_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_I2S_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+
+#define LPC17_I2S_DAO_OFFSET 0x0000 /* Digital Audio Output Register */
+#define LPC17_I2S_DAI_OFFSET 0x0004 /* Digital Audio Input Register */
+#define LPC17_I2S_TXFIFO_OFFSET 0x0008 /* Transmit FIFO */
+#define LPC17_I2S_RXFIFO_OFFSET 0x000c /* Receive FIFO */
+#define LPC17_I2S_STATE_OFFSET 0x0010 /* Status Feedback Register */
+#define LPC17_I2S_DMA1_OFFSET 0x0014 /* DMA Configuration Register 1 */
+#define LPC17_I2S_DMA2_OFFSET 0x0018 /* DMA Configuration Register 2 */
+#define LPC17_I2S_IRQ_OFFSET 0x001c /* Interrupt Request Control Register */
+#define LPC17_I2S_TXRATE_OFFSET 0x0020 /* Transmit MCLK divider */
+#define LPC17_I2S_RXRATE_OFFSET 0x0024 /* Receive MCLK divider */
+#define LPC17_I2S_TXBITRATE_OFFSET 0x0028 /* Transmit bit rate divider */
+#define LPC17_I2S_RXBITRATE_OFFSET 0x002c /* Receive bit rate divider */
+#define LPC17_I2S_TXMODE_OFFSET 0x0030 /* Transmit mode control */
+#define LPC17_I2S_RXMODE_OFFSET 0x0034 /* Receive mode control */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_I2S_DAO (LPC17_I2S_BASE+LPC17_I2S_DAO_OFFSET)
+#define LPC17_I2S_DAI (LPC17_I2S_BASE+LPC17_I2S_DAI_OFFSET)
+#define LPC17_I2S_TXFIFO (LPC17_I2S_BASE+LPC17_I2S_TXFIFO_OFFSET)
+#define LPC17_I2S_RXFIFO (LPC17_I2S_BASE+LPC17_I2S_RXFIFO_OFFSET)
+#define LPC17_I2S_STATE (LPC17_I2S_BASE+LPC17_I2S_STATE_OFFSET)
+#define LPC17_I2S_DMA1 (LPC17_I2S_BASE+LPC17_I2S_DMA1_OFFSET)
+#define LPC17_I2S_DMA2 (LPC17_I2S_BASE+LPC17_I2S_DMA2_OFFSET)
+#define LPC17_I2S_IRQ (LPC17_I2S_BASE+LPC17_I2S_IRQ_OFFSET)
+#define LPC17_I2S_TXRATE (LPC17_I2S_BASE+LPC17_I2S_TXRATE_OFFSET)
+#define LPC17_I2S_RXRATE (LPC17_I2S_BASE+LPC17_I2S_RXRATE_OFFSET)
+#define LPC17_I2S_TXBITRATE (LPC17_I2S_BASE+LPC17_I2S_TXBITRATE_OFFSET)
+#define LPC17_I2S_RXBITRATE (LPC17_I2S_BASE+LPC17_I2S_RXBITRATE_OFFSET)
+#define LPC17_I2S_TXMODE (LPC17_I2S_BASE+LPC17_I2S_TXMODE_OFFSET)
+#define LPC17_I2S_RXMODE (LPC17_I2S_BASE+LPC17_I2S_RXMODE_OFFSET)
+
+/* Register bit definitions *********************************************************/
+
+/* Digital Audio Output Register */
+
+#define I2S_DAO_WDWID_SHIFT (0) /* Bits 0-1: Selects the number of bytes in data */
+#define I2S_DAO_WDWID_MASK (3 << I2S_DAO_WDWID_SHIFT)
+# define I2S_DAO_WDWID_8BITS (0 << I2S_DAO_WDWID_SHIFT)
+# define I2S_DAO_WDWID_16BITS (1 << I2S_DAO_WDWID_SHIFT)
+# define I2S_DAO_WDWID_32BITS (3 << I2S_DAO_WDWID_SHIFT)
+#define I2S_DAO_MONO (1 << 2) /* Bit 2: Mono format */
+#define I2S_DAO_STOP (1 << 3) /* Bit 3: Disable FIFOs / mute mode */
+#define I2S_DAO_RESET (1 << 4) /* Bit 4: Reset TX channel and FIFO */
+#define I2S_DAO_WSSEL (1 << 5) /* Bit 5: Slave mode select */
+#define I2S_DAO_WSHALFPER_SHIFT (6) /* Bits 6-14: Word select half period minus 1 */
+#define I2S_DAO_WSHALFPER_MASK (0x01ff << I2S_DAO_WSHALFPER_SHIFT)
+#define I2S_DAO_MUTE (1 << 15) /* Bit 15: Send only zeros on channel */
+ /* Bits 16-31: Reserved */
+/* Digital Audio Input Register */
+
+#define I2S_DAI_WDWID_SHIFT (0) /* Bits 0-1: Selects the number of bytes in data */
+#define I2S_DAI_WDWID_MASK (3 << I2S_DAI_WDWID_SHIFT)
+# define I2S_DAI_WDWID_8BITS (0 << I2S_DAI_WDWID_SHIFT)
+# define I2S_DAI_WDWID_16BITS (1 << I2S_DAI_WDWID_SHIFT)
+# define I2S_DAI_WDWID_32BITS (3 << I2S_DAI_WDWID_SHIFT)
+#define I2S_DAI_MONO (1 << 2) /* Bit 2: Mono format */
+#define I2S_DAI_STOP (1 << 3) /* Bit 3: Disable FIFOs / mute mode */
+#define I2S_DAI_RESET (1 << 4) /* Bit 4: Reset TX channel and FIFO */
+#define I2S_DAI_WSSEL (1 << 5) /* Bit 5: Slave mode select */
+#define I2S_DAI_WSHALFPER_SHIFT (6) /* Bits 6-14: Word select half period minus 1 */
+#define I2S_DAI_WSHALFPER_MASK (0x01ff << I2S_DAI_WSHALFPER_SHIFT)
+ /* Bits 15-31: Reserved */
+/* Transmit FIFO: 8 × 32-bit transmit FIFO */
+/* Receive FIFO: 8 × 32-bit receive FIFO */
+
+/* Status Feedback Register */
+
+#define I2S_STATE_IRQ (1 << 0) /* Bit 0: Receive Transmit Interrupt */
+#define I2S_STATE_DMAREQ1 (1 << 1) /* Bit 1: Receive or Transmit DMA Request 1 */
+#define I2S_STATE_DMAREQ2 (1 << 2) /* Bit 2: Receive or Transmit DMA Request 2 */
+ /* Bits 3-7: Reserved */
+#define I2S_STATE_RXLEVEL_SHIFT (8) /* Bits 8-11: Current level of the Receive FIFO */
+#define I2S_STATE_RXLEVEL_MASK (15 << I2S_STATE_RXLEVEL_SHIFT)
+ /* Bits 12-15: Reserved */
+#define I2S_STATE_TXLEVEL_SHIFT (16) /* Bits 16-19: Current level of the Transmit FIFO */
+#define I2S_STATE_TXLEVEL_MASK (15 << I2S_STATE_TXLEVEL_SHIFT)
+ /* Bits 20-31: Reserved */
+/* DMA Configuration Register 1 and 2 */
+
+#define I2S_DMA_RXDMAEN (1 << 0) /* Bit 0: Enable DMA1 for I2S receive */
+#define I2S_DMA_TXDMAEN (1 << 1) /* Bit 1: Enable DMA1 for I2S transmit */
+ /* Bits 2-7: Reserved */
+#define I2S_DMA_RXDEPTH_SHIFT (8) /* Bits 8-11: FIFO level that triggers RX request on DMA1 */
+#define I2S_DMA_RXDEPTH_MASK (15 << I2S_DMA_RXDEPTH_SHIFT)
+ /* Bits 12-15: Reserved */
+#define I2S_DMA_TXDEPTH_SHIFT (16) /* Bits 16-19: FIFO level that triggers a TX request on DMA1 */
+#define I2S_DMA_TXDEPTH_MASK (15 << I2S_DMA_TXDEPTH_SHIFT)
+ /* Bits 20-31: Reserved */
+/* Interrupt Request Control Register */
+
+#define I2S_IRQ_RXEN (1 << 0) /* Bit 0: Enable I2S receive interrupt */
+#define I2S_IRQ_TXEN (1 << 1) /* Bit 1: Enable I2S transmit interrupt */
+ /* Bits 2-7: Reserved */
+#define I2S_IRQ_RXDEPTH_SHIFT (8) /* Bits 8-11: Set FIFO level for irq request */
+#define I2S_IRQ_RXDEPTH_MASK (15 << I2S_IRQ_RXDEPTH_SHIFT)
+ /* Bits 12-15: Reserved */
+#define I2S_IRQ_TXDEPTH_SHIFT (16) /* Bits 16-19: Set FIFO level for irq request */
+#define I2S_IRQ_TXDEPTH_MASK (15 << I2S_IRQ_TXDEPTH_SHIFT)
+ /* Bits 20-31: Reserved */
+/* Transmit and Receive MCLK divider */
+
+#define I2S_RATE_YDIV_SHIFT (0) /* Bits 0-7: I2S transmit MCLK rate denominator */
+#define I2S_RATE_YDIV_MASK (0xff << I2S_RATE_YDIV_SHIFT)
+#define I2S_RATE_XDIV_SHIFT (8) /* Bits 8-15: I2S transmit MCLK rate numerator */
+#define I2S_RATE_XDIV_MASK (0xff << I2S_RATE_XDIV_SHIFT)
+ /* Bits 16-31: Reserved */
+
+/* Transmit and received bit rate divider */
+
+#define I2S_BITRATE_SHIFT (0) /* Bits 0-5: I2S transmit bit rate */
+#define I2S_BITRATE_MASK (0x3f << I2S_BITRATE_SHIFT)
+ /* Bits 6-31: Reserved */
+/* Transmit and Receive mode control */
+
+#define I2S_MODE_CLKSEL_SHIFT (0) /* Bits 0-1: Clock source for bit clock divider */
+#define I2S_MODE_CLKSEL_MASK (3 << I2S_MODE_CLKSEL_SHIFT)
+# define I2S_MODE_CLKSEL_FRACDIV (0 << I2S_MODE_CLKSEL_SHIFT) /* TX/RX fractional rate divider */
+# define I2S_MODE_CLKSEL_RXMCLK (2 << I2S_MODE_CLKSEL_SHIFT) /* RX_CLCK for TX_MCLK source */
+# define I2S_MODE_CLKSEL_TXMCLK (2 << I2S_MODE_CLKSEL_SHIFT) /* TX_CLCK for RX_MCLK source */
+#define I2S_MODE_4PIN (1 << 2) /* Bit 2: Transmit/Receive 4-pin mode selection */
+#define I2S_MODE_MCENA (1 << 3) /* Bit 3: Enable for the TX/RX_MCLK output */
+ /* Bits 4-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_I2S_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_internal.h b/nuttx/arch/arm/src/lpc17xx/lpc17_internal.h
deleted file mode 100644
index 8b4358196..000000000
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_internal.h
+++ /dev/null
@@ -1,854 +0,0 @@
-/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_internal.h
- *
- * Copyright (C) 2009-2011 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_LPC17XX_LPC17_INTERNAL_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_INTERNAL_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/compiler.h>
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <stdbool.h>
-
-#if defined(CONFIG_LPC17_SPI) || defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
-# include <nuttx/spi.h>
-#endif
-
-#include "up_internal.h"
-#include "chip.h"
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/* Configuration ********************************************************************/
-
-/* Bit-encoded input to lpc17_configgpio() ******************************************/
-
-/* Encoding: FFFx MMOV PPPN NNNN
- *
- * Pin Function: FFF
- * Pin Mode bits: MM
- * Open drain: O (output pins)
- * Initial value: V (output pins)
- * Port number: PPP (0-4)
- * Pin number: NNNNN (0-31)
- */
-
-/* Pin Function bits: FFF
- * Only meaningful when the GPIO function is GPIO_PIN
- */
-
-#define GPIO_FUNC_SHIFT (13) /* Bits 13-15: GPIO mode */
-#define GPIO_FUNC_MASK (7 << GPIO_FUNC_SHIFT)
-# define GPIO_INPUT (0 << GPIO_FUNC_SHIFT) /* 000 GPIO input pin */
-# define GPIO_INTFE (1 << GPIO_FUNC_SHIFT) /* 001 GPIO interrupt falling edge */
-# define GPIO_INTRE (2 << GPIO_FUNC_SHIFT) /* 010 GPIO interrupt rising edge */
-# define GPIO_INTBOTH (3 << GPIO_FUNC_SHIFT) /* 011 GPIO interrupt both edges */
-# define GPIO_OUTPUT (4 << GPIO_FUNC_SHIFT) /* 100 GPIO outpout pin */
-# define GPIO_ALT1 (5 << GPIO_FUNC_SHIFT) /* 101 Alternate function 1 */
-# define GPIO_ALT2 (6 << GPIO_FUNC_SHIFT) /* 110 Alternate function 2 */
-# define GPIO_ALT3 (7 << GPIO_FUNC_SHIFT) /* 111 Alternate function 3 */
-
-#define GPIO_EDGE_SHIFT (13) /* Bits 13-14: Interrupt edge bits */
-#define GPIO_EDGE_MASK (3 << GPIO_EDGE_SHIFT)
-
-#define GPIO_INOUT_MASK GPIO_OUTPUT
-#define GPIO_FE_MASK GPIO_INTFE
-#define GPIO_RE_MASK GPIO_INTRE
-
-#define GPIO_ISGPIO(ps) ((uint16_t(ps) & GPIO_FUNC_MASK) <= GPIO_OUTPUT)
-#define GPIO_ISALT(ps) ((uint16_t(ps) & GPIO_FUNC_MASK) > GPIO_OUTPUT)
-#define GPIO_ISINPUT(ps) (((ps) & GPIO_FUNC_MASK) == GPIO_INPUT)
-#define GPIO_ISOUTPUT(ps) (((ps) & GPIO_FUNC_MASK) == GPIO_OUTPUT)
-#define GPIO_ISINORINT(ps) (((ps) & GPIO_INOUT_MASK) == 0)
-#define GPIO_ISOUTORALT(ps) (((ps) & GPIO_INOUT_MASK) != 0)
-#define GPIO_ISINTERRUPT(ps) (GPIO_ISOUTPUT(ps) && !GPIO_ISINPUT(ps))
-#define GPIO_ISFE(ps) (((ps) & GPIO_FE_MASK) != 0)
-#define GPIO_ISRE(ps) (((ps) & GPIO_RE_MASK) != 0)
-
-/* Pin Mode: MM */
-
-#define GPIO_PUMODE_SHIFT (10) /* Bits 10-11: Pin pull-up mode */
-#define GPIO_PUMODE_MASK (3 << GPIO_PUMODE_SHIFT)
-# define GPIO_PULLUP (0 << GPIO_PUMODE_SHIFT) /* Pull-up resistor enabled */
-# define GPIO_REPEATER (1 << GPIO_PUMODE_SHIFT) /* Repeater mode enabled */
-# define GPIO_FLOAT (2 << GPIO_PUMODE_SHIFT) /* Neither pull-up nor -down */
-# define GPIO_PULLDN (3 << GPIO_PUMODE_SHIFT) /* Pull-down resistor enabled */
-
-/* Open drain: O */
-
-#define GPIO_OPEN_DRAIN (1 << 9) /* Bit 9: Open drain mode */
-
-/* Initial value: V */
-
-#define GPIO_VALUE (1 << 8) /* Bit 8: Initial GPIO output value */
-#define GPIO_VALUE_ONE GPIO_VALUE
-#define GPIO_VALUE_ZERO (0)
-
-/* Port number: PPP (0-4) */
-
-#define GPIO_PORT_SHIFT (5) /* Bit 5-7: Port number */
-#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT)
-# define GPIO_PORT0 (0 << GPIO_PORT_SHIFT)
-# define GPIO_PORT1 (1 << GPIO_PORT_SHIFT)
-# define GPIO_PORT2 (2 << GPIO_PORT_SHIFT)
-# define GPIO_PORT3 (3 << GPIO_PORT_SHIFT)
-# define GPIO_PORT4 (4 << GPIO_PORT_SHIFT)
-
-#define GPIO_NPORTS 5
-
-/* Pin number: NNNNN (0-31) */
-
-#define GPIO_PIN_SHIFT 0 /* Bits 0-4: GPIO number: 0-31 */
-#define GPIO_PIN_MASK (31 << GPIO_PIN_SHIFT)
-#define GPIO_PIN0 (0 << GPIO_PIN_SHIFT)
-#define GPIO_PIN1 (1 << GPIO_PIN_SHIFT)
-#define GPIO_PIN2 (2 << GPIO_PIN_SHIFT)
-#define GPIO_PIN3 (3 << GPIO_PIN_SHIFT)
-#define GPIO_PIN4 (4 << GPIO_PIN_SHIFT)
-#define GPIO_PIN5 (5 << GPIO_PIN_SHIFT)
-#define GPIO_PIN6 (6 << GPIO_PIN_SHIFT)
-#define GPIO_PIN7 (7 << GPIO_PIN_SHIFT)
-#define GPIO_PIN8 (8 << GPIO_PIN_SHIFT)
-#define GPIO_PIN9 (9 << GPIO_PIN_SHIFT)
-#define GPIO_PIN10 (10 << GPIO_PIN_SHIFT)
-#define GPIO_PIN11 (11 << GPIO_PIN_SHIFT)
-#define GPIO_PIN12 (12 << GPIO_PIN_SHIFT)
-#define GPIO_PIN13 (13 << GPIO_PIN_SHIFT)
-#define GPIO_PIN14 (14 << GPIO_PIN_SHIFT)
-#define GPIO_PIN15 (15 << GPIO_PIN_SHIFT)
-#define GPIO_PIN16 (16 << GPIO_PIN_SHIFT)
-#define GPIO_PIN17 (17 << GPIO_PIN_SHIFT)
-#define GPIO_PIN18 (18 << GPIO_PIN_SHIFT)
-#define GPIO_PIN19 (19 << GPIO_PIN_SHIFT)
-#define GPIO_PIN20 (20 << GPIO_PIN_SHIFT)
-#define GPIO_PIN21 (21 << GPIO_PIN_SHIFT)
-#define GPIO_PIN22 (22 << GPIO_PIN_SHIFT)
-#define GPIO_PIN23 (23 << GPIO_PIN_SHIFT)
-#define GPIO_PIN24 (24 << GPIO_PIN_SHIFT)
-#define GPIO_PIN25 (25 << GPIO_PIN_SHIFT)
-#define GPIO_PIN26 (26 << GPIO_PIN_SHIFT)
-#define GPIO_PIN27 (27 << GPIO_PIN_SHIFT)
-#define GPIO_PIN28 (28 << GPIO_PIN_SHIFT)
-#define GPIO_PIN29 (29 << GPIO_PIN_SHIFT)
-#define GPIO_PIN30 (30 << GPIO_PIN_SHIFT)
-#define GPIO_PIN31 (31 << GPIO_PIN_SHIFT)
-
-/* GPIO pin definitions *************************************************************/
-/* NOTE that functions have a alternate pins that can be selected. These alternates
- * are identified with a numerica suffix like _1, _2, or _3. Your board.h file
- * should select the correct alternative for your board by including definitions
- * such as:
- *
- * #define GPIO_UART1_RXD GPIO_UART1_RXD_1
- *
- * (without the suffix)
- */
-
-#define GPIO_CAN1_RD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN0)
-#define GPIO_UART3_TXD_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN0)
-#define GPIO_I2C1_SDA_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN0)
-#define GPIO_CAN1_TD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN1)
-#define GPIO_UART3_RXD_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN1)
-#define GPIO_I2C1_SCL_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN1)
-#define GPIO_UART0_TXD (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN2)
-#define GPIO_AD0p7 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN2)
-#define GPIO_UART0_RXD (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN3)
-#define GPIO_AD0p6 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN3)
-#define GPIO_I2S_RXCLK_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
-#define GPIO_CAN2_RD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
-#define GPIO_CAP2p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
-#define GPIO_I2S_RXWS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
-#define GPIO_CAN2_TD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
-#define GPIO_CAP2p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
-#define GPIO_I2S_RXSDA_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
-#define GPIO_SSP1_SSEL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
-#define GPIO_MAT2p0_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
-#define GPIO_I2S_TXCLK_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
-#define GPIO_SSP1_SCK_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
-#define GPIO_MAT2p1_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
-#define GPIO_I2S_TXWS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
-#define GPIO_SSP1_MISO (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
-#define GPIO_MAT2p2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
-#define GPIO_I2S_TXSDA_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
-#define GPIO_SSP1_MOSI (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
-#define GPIO_MAT2p3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
-#define GPIO_UART2_TXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN10)
-#define GPIO_I2C2_SDA (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN10)
-#define GPIO_MAT3p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN10)
-#define GPIO_UART2_RXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN11)
-#define GPIO_I2C2_SCL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN11)
-#define GPIO_MAT3p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN11)
-#define GPIO_UART1_TXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
-#define GPIO_SSP0_SCK_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
-#define GPIO_SPI_SCK (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
-#define GPIO_UART1_RXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
-#define GPIO_SSP0_SSEL_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
-#define GPIO_SPI_SSEL (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
-#define GPIO_UART1_CTS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
-#define GPIO_SSP0_MISO_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
-#define GPIO_SPI_MISO (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
-#define GPIO_UART1_DCD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
-#define GPIO_SSP0_MOSI_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
-#define GPIO_SPI_MOSI (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
-#define GPIO_UART1_DSR_1 (GPIO_ALT1 | 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_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_CAN1_RD_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
-#define GPIO_UART1_RTS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
-#define GPIO_CAN1_TD_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
-#define GPIO_AD0p0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN23)
-#define GPIO_I2S_RXCLK_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN23)
-#define GPIO_CAP3p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN23)
-#define GPIO_AD0p1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN24)
-#define GPIO_I2S_RXWS_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN24)
-#define GPIO_CAP3p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN24)
-#define GPIO_AD0p2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN25)
-#define GPIO_I2S_RXSDA_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN25)
-#define GPIO_UART3_TXD_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN25)
-#define GPIO_AD0p3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN26)
-#define GPIO_AOUT (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN26)
-#define GPIO_UART3_RXD_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN26)
-#define GPIO_I2C0_SDA (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN27)
-#define GPIO_USB_SDA (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN27)
-#define GPIO_I2C0_SCL (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN28)
-#define GPIO_USB_SCL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN28)
-#define GPIO_USB_DP (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN29)
-#define GPIO_USB_DM (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN30)
-#define GPIO_ENET_TXD0 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN0)
-#define GPIO_ENET_TXD1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN1)
-#define GPIO_ENET_TXEN (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN4)
-#define GPIO_ENET_CRS (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN8)
-#define GPIO_ENET_RXD0 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN9)
-#define GPIO_ENET_RXD1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN10)
-#define GPIO_ENET_RXER (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN14)
-#define GPIO_ENET_REFCLK (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN15)
-#define GPIO_ENET_MDC_1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN16)
-#define GPIO_ENET_MDIO_1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN17)
-#define GPIO_USB_UPLED (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN18)
-#define GPIO_PWM1p1_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN18)
-#define GPIO_CAP1p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN18)
-#define GPIO_MCPWM_MCOA0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
-#define GPIO_USB_PPWR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
-#define GPIO_CAP1p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
-#define GPIO_MCPWM_MCI0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
-#define GPIO_PWM1p2_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
-#define GPIO_SSP0_SCK_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
-#define GPIO_MCPWM_MCABORT (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN21)
-#define GPIO_PWM1p3_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN21)
-#define GPIO_SSP0_SSEL_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN21)
-#define GPIO_MCPWM_MCOB0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
-#define GPIO_USB_PWRD (GPIO_ALT2 | GPIO_PULLDN | GPIO_PORT1 | GPIO_PIN22)
-#define GPIO_MAT1p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
-#define GPIO_MCPWM_MCI1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
-#define GPIO_PWM1p4_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
-#define GPIO_SSP0_MISO_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
-#define GPIO_MCPWM_MCI2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
-#define GPIO_PWM1p5_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
-#define GPIO_SSP0_MOSI_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
-#define GPIO_MCPWM_MCOA1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
-#define GPIO_MAT1p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
-#define GPIO_MCPWM_MCOB1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
-#define GPIO_PWM1p6_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
-#define GPIO_CAP0p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
-#define GPIO_CLKOUT (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
-#define GPIO_USB_OVRCR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
-#define GPIO_CAP0p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
-#define GPIO_MCPWM_MCOA2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
-#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_MCOB2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
-#define GPIO_PCAP1p1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
-#define GPIO_MAT0p1_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
-#define GPIO_USB_VBUS (GPIO_ALT2 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN30)
-#define GPIO_AD0p4 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN30)
-#define GPIO_SSP1_SCK_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN31)
-#define GPIO_AD0p5 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN31)
-#define GPIO_PWM1p1_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN0)
-#define GPIO_UART1_TXD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN0)
-#define GPIO_PWM1p2_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN1)
-#define GPIO_UART1_RXD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN1)
-#define GPIO_PWM1p3_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN2)
-#define GPIO_UART1_CTS_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN2)
-#define GPIO_PWM1p4_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN3)
-#define GPIO_UART1_DCD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN3)
-#define GPIO_PWM1p5_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN4)
-#define GPIO_UART1_DSR_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN4)
-#define GPIO_PWM1p6_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN5)
-#define GPIO_UART1_DTR_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN5)
-#define GPIO_PCAP1p0_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN6)
-#define GPIO_UART1_RI_2 (GPIO_ALT2 | 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_CAN2_TD_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN8)
-#define GPIO_UART2_TXD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN8)
-#define GPIO_ENET_MDC_2 (GPIO_ALT3 | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN8)
-#define GPIO_USB_CONNECT (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
-#define GPIO_UART2_RXD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
-#define GPIO_ENET_MDIO_2 (GPIO_ALT3 | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN9)
-#define GPIO_EINT0 (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_I2S_TXCLK_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
-#define GPIO_PEINT2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
-#define GPIO_I2S_TXWS_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
-#define GPIO_EINT3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
-#define GPIO_I2S_TXSDA_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
-#define GPIO_MAT0p0_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN25)
-#define GPIO_PWM1p2_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN25)
-#define GPIO_STCLK (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
-#define GPIO_MAT0p1_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
-#define GPIO_PWM1p3_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
-#define GPIO_RXMCLK (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
-#define GPIO_MAT2p0_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
-#define GPIO_UART3_TXD_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
-#define GPIO_TXMCLK (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
-#define GPIO_MAT2p1_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
-#define GPIO_UART3_RXD_3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-typedef FAR void *DMA_HANDLE;
-typedef void (*dma_callback_t)(DMA_HANDLE handle, void *arg, int result);
-
-/* The following is used for sampling DMA registers when CONFIG DEBUG_DMA is selected */
-
-#ifdef CONFIG_DEBUG_DMA
-struct lpc17_dmaglobalregs_s
-{
- /* Global Registers */
-
- uint32_t intst; /* DMA Interrupt Status Register */
- uint32_t inttcst; /* DMA Interrupt Terminal Count Request Status Register */
- uint32_t interrst; /* DMA Interrupt Error Status Register */
- uint32_t rawinttcst; /* DMA Raw Interrupt Terminal Count Status Register */
- uint32_t rawinterrst; /* DMA Raw Error Interrupt Status Register */
- uint32_t enbldchns; /* DMA Enabled Channel Register */
- uint32_t softbreq; /* DMA Software Burst Request Register */
- uint32_t softsreq; /* DMA Software Single Request Register */
- uint32_t softlbreq; /* DMA Software Last Burst Request Register */
- uint32_t softlsreq; /* DMA Software Last Single Request Register */
- uint32_t config; /* DMA Configuration Register */
- uint32_t sync; /* DMA Synchronization Register */
-};
-
-struct lpc17_dmachanregs_s
-{
- /* Channel Registers */
-
- uint32_t srcaddr; /* DMA Channel Source Address Register */
- uint32_t destaddr; /* DMA Channel Destination Address Register */
- uint32_t lli; /* DMA Channel Linked List Item Register */
- uint32_t control; /* DMA Channel Control Register */
- uint32_t config; /* DMA Channel Configuration Register */
-};
-
-struct lpc17_dmaregs_s
-{
- /* Global Registers */
-
- struct lpc17_dmaglobalregs_s gbl;
-
- /* Channel Registers */
-
- struct lpc17_dmachanregs_s ch;
-};
-#endif
-
-/************************************************************************************
- * Inline Functions
- ************************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/************************************************************************************
- * Public Data
- ************************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/* These tables have global scope only because they are shared between lpc17_gpio.c,
- * lpc17_gpioint.c, and lpc17_gpiodbg.c
- */
-
-#ifdef CONFIG_GPIO_IRQ
-EXTERN uint64_t g_intedge0;
-EXTERN uint64_t g_intedge2;
-#endif
-
-EXTERN const uint32_t g_fiobase[GPIO_NPORTS];
-EXTERN const uint32_t g_intbase[GPIO_NPORTS];
-EXTERN const uint32_t g_lopinsel[GPIO_NPORTS];
-EXTERN const uint32_t g_hipinsel[GPIO_NPORTS];
-EXTERN const uint32_t g_lopinmode[GPIO_NPORTS];
-EXTERN const uint32_t g_hipinmode[GPIO_NPORTS];
-EXTERN const uint32_t g_odmode[GPIO_NPORTS];
-
-/************************************************************************************
- * Public Function Prototypes
- ************************************************************************************/
-
-/************************************************************************************
- * Name: lpc17_clockconfig
- *
- * Description:
- * Called to initialize the LPC17XX. This does whatever setup is needed to put the
- * MCU in a usable state. This includes the initialization of clocking using the
- * settings in board.h.
- *
- ************************************************************************************/
-
-EXTERN void lpc17_clockconfig(void);
-
-/************************************************************************************
- * Name: lpc17_lowsetup
- *
- * Description:
- * Called at the very beginning of _start. Performs low level initialization
- * including setup of the console UART. This UART done early so that the serial
- * console is available for debugging very early in the boot sequence.
- *
- ************************************************************************************/
-
-EXTERN void lpc17_lowsetup(void);
-
-/************************************************************************************
- * Name: lpc17_gpioirqinitialize
- *
- * Description:
- * Initialize logic to support a second level of interrupt decoding for GPIO pins.
- *
- ************************************************************************************/
-
-#ifdef CONFIG_GPIO_IRQ
-EXTERN void lpc17_gpioirqinitialize(void);
-#else
-# define lpc17_gpioirqinitialize()
-#endif
-
-/************************************************************************************
- * Name: lpc17_configgpio
- *
- * Description:
- * Configure a GPIO pin based on bit-encoded description of the pin.
- *
- ************************************************************************************/
-
-EXTERN int lpc17_configgpio(uint16_t cfgset);
-
-/************************************************************************************
- * Name: lpc17_gpiowrite
- *
- * Description:
- * Write one or zero to the selected GPIO pin
- *
- ************************************************************************************/
-
-EXTERN void lpc17_gpiowrite(uint16_t pinset, bool value);
-
-/************************************************************************************
- * Name: lpc17_gpioread
- *
- * Description:
- * Read one or zero from the selected GPIO pin
- *
- ************************************************************************************/
-
-EXTERN bool lpc17_gpioread(uint16_t pinset);
-
-/************************************************************************************
- * Name: lpc17_gpioirqenable
- *
- * Description:
- * Enable the interrupt for specified GPIO IRQ
- *
- ************************************************************************************/
-
-#ifdef CONFIG_GPIO_IRQ
-EXTERN void lpc17_gpioirqenable(int irq);
-#else
-# define lpc17_gpioirqenable(irq)
-#endif
-
-/************************************************************************************
- * Name: lpc17_gpioirqdisable
- *
- * Description:
- * Disable the interrupt for specified GPIO IRQ
- *
- ************************************************************************************/
-
-#ifdef CONFIG_GPIO_IRQ
-EXTERN void lpc17_gpioirqdisable(int irq);
-#else
-# define lpc17_gpioirqdisable(irq)
-#endif
-
-/************************************************************************************
- * Function: lpc17_dumpgpio
- *
- * Description:
- * Dump all GPIO registers associated with the base address of the provided pinset.
- *
- ************************************************************************************/
-
-#ifdef CONFIG_DEBUG_GPIO
-EXTERN int lpc17_dumpgpio(uint16_t pinset, const char *msg);
-#else
-# define lpc17_dumpgpio(p,m)
-#endif
-
-/************************************************************************************
- * Name: lpc17_clrpend
- *
- * Description:
- * Clear a pending interrupt at the NVIC. This does not seem to be required
- * for most interrupts. Don't know why... but the LPC1766 Ethernet EMAC
- * interrupt definitely needs it!
- *
- ************************************************************************************/
-
-EXTERN void lpc17_clrpend(int irq);
-
-/************************************************************************************
- * Name: lpc17_spi/ssp0/ssp1select, lpc17_spi/ssp0/ssp1status, and
- * lpc17_spi/ssp0/ssp1cmddata
- *
- * Description:
- * These external functions must be provided by board-specific logic. They are
- * implementations of the select, status, and cmddata methods of the SPI interface
- * defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods
- * including up_spiinitialize()) are provided by common LPC17xx logic. To use
- * this common SPI logic on your board:
- *
- * 1. Provide logic in lpc17_boardinitialize() to configure SPI/SSP chip select
- * pins.
- * 2. Provide lpc17_spi/ssp0/ssp1select() and lpc17_spi/ssp0/ssp1status() functions
- * in your board-specific logic. These functions will perform chip selection
- * and status operations using GPIOs in the way your board is configured.
- * 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
- * lpc17_spi/ssp0/ssp1cmddata() functions in your board-specific logic. These
- * functions will perform cmd/data selection operations using GPIOs in the way
- * your board is configured.
- * 3. Add a call to up_spiinitialize() in your low level application
- * initialization logic
- * 4. The handle returned by up_spiinitialize() may then be used to bind the
- * SPI driver to higher level logic (e.g., calling
- * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
- * the SPI MMC/SD driver).
- *
- ************************************************************************************/
-
-#ifdef CONFIG_LPC17_SPI
-EXTERN void lpc17_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
-EXTERN uint8_t lpc17_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
-#ifdef CONFIG_SPI_CMDDATA
-EXTERN int lpc17_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
-#endif
-#endif
-
-#ifdef CONFIG_LPC17_SSP0
-EXTERN void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
-EXTERN uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
-#ifdef CONFIG_SPI_CMDDATA
-EXTERN int lpc17_ssp0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
-#endif
-#endif
-
-#ifdef CONFIG_LPC17_SSP1
-EXTERN void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
-EXTERN uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
-#ifdef CONFIG_SPI_CMDDATA
-EXTERN int lpc17_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
-#endif
-#endif
-
-/****************************************************************************
- * Name: spi_flush
- *
- * Description:
- * Flush and discard any words left in the RX fifo. This can be called
- * from ssp0/1select after a device is deselected (if you worry about such
- * things).
- *
- * Input Parameters:
- * dev - Device-specific state data
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_SPI
-EXTERN void spi_flush(FAR struct spi_dev_s *dev);
-#endif
-
-#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
-EXTERN void ssp_flush(FAR struct spi_dev_s *dev);
-#endif
-
-/****************************************************************************
- * Name: lpc17_spi/ssp0/1register
- *
- * Description:
- * If the board supports a card detect callback to inform the SPI-based
- * MMC/SD drvier when an SD card is inserted or removed, then
- * CONFIG_SPI_CALLBACK should be defined and the following function(s) must
- * must be implemented. These functiosn implements the registercallback
- * method of the SPI interface (see include/nuttx/spi.h for details)
- *
- * Input Parameters:
- * dev - Device-specific state data
- * callback - The funtion to call on the media change
- * arg - A caller provided value to return with the callback
- *
- * Returned Value:
- * 0 on success; negated errno on failure.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_SPI_CALLBACK
-#ifdef CONFIG_LPC17_SPI
-EXTERN int lpc17_spiregister(FAR struct spi_dev_s *dev,
- spi_mediachange_t callback, void *arg);
-#endif
-
-#ifdef CONFIG_LPC17_SSP0
-EXTERN int lpc17_ssp0register(FAR struct spi_dev_s *dev,
- spi_mediachange_t callback, void *arg);
-#endif
-
-#ifdef CONFIG_LPC17_SSP1
-EXTERN int lpc17_ssp1register(FAR struct spi_dev_s *dev,
- spi_mediachange_t callback, void *arg);
-#endif
-#endif
-
-/****************************************************************************
- * Name: lpc17_dmainitialize
- *
- * Description:
- * Initialize the GPDMA subsystem.
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_GPDMA
-EXTERN void lpc17_dmainitilaize(void);
-#endif
-
-/****************************************************************************
- * Name: lpc17_dmachannel
- *
- * Description:
- * Allocate a DMA channel. This function sets aside a DMA channel and
- * gives the caller exclusive access to the DMA channel.
- *
- * Returned Value:
- * One success, this function returns a non-NULL, void* DMA channel
- * handle. NULL is returned on any failure. This function can fail only
- * if no DMA channel is available.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_GPDMA
-EXTERN DMA_HANDLE lpc17_dmachannel(void);
-#endif
-
-/****************************************************************************
- * Name: lpc17_dmafree
- *
- * Description:
- * Release a DMA channel. NOTE: The 'handle' used in this argument must
- * NEVER be used again until lpc17_dmachannel() is called again to re-gain
- * a valid handle.
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_GPDMA
-EXTERN void lpc17_dmafree(DMA_HANDLE handle);
-#endif
-
-/****************************************************************************
- * Name: lpc17_dmasetup
- *
- * Description:
- * Configure DMA for one transfer.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_GPDMA
-EXTERN int lpc17_dmarxsetup(DMA_HANDLE handle,
- uint32_t control, uint32_t config,
- uint32_t srcaddr, uint32_t destaddr,
- size_t nbytes);
-#endif
-
-/****************************************************************************
- * Name: lpc17_dmastart
- *
- * Description:
- * Start the DMA transfer
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_GPDMA
-EXTERN int lpc17_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg);
-#endif
-
-/****************************************************************************
- * Name: lpc17_dmastop
- *
- * Description:
- * Cancel the DMA. After lpc17_dmastop() is called, the DMA channel is
- * reset and lpc17_dmasetup() must be called before lpc17_dmastart() can be
- * called again
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_GPDMA
-EXTERN void lpc17_dmastop(DMA_HANDLE handle);
-#endif
-
-/****************************************************************************
- * Name: lpc17_dmasample
- *
- * Description:
- * Sample DMA register contents
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_GPDMA
-#ifdef CONFIG_DEBUG_DMA
-EXTERN void lpc17_dmasample(DMA_HANDLE handle, struct lpc17_dmaregs_s *regs);
-#else
-# define lpc17_dmasample(handle,regs)
-#endif
-#endif
-
-/****************************************************************************
- * Name: lpc17_dmadump
- *
- * Description:
- * Dump previously sampled DMA register contents
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_GPDMA
-#ifdef CONFIG_DEBUG_DMA
-EXTERN void lpc17_dmadump(DMA_HANDLE handle, const struct lpc17_dmaregs_s *regs,
- const char *msg);
-#else
-# define lpc17_dmadump(handle,regs,msg)
-#endif
-#endif
-
-/****************************************************************************
- * Name: lpc17_adcinitialize
- *
- * Description:
- * Initialize the adc
- *
- * Returned Value:
- * Valid can device structure reference on succcess; a NULL on failure
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_ADC
-FAR struct adc_dev_s *lpc17_adcinitialize(void);
-#endif
-
-/****************************************************************************
- * Name: lpc17_dacinitialize
- *
- * Description:
- * Initialize the DAC
- *
- * Returned Value:
- * Valid dac device structure reference on succcess; a NULL on failure
- *
- ****************************************************************************/
-
-#ifdef CONFIG_LPC17_DAC
-EXTERN FAR struct dac_dev_s *lpc17_dacinitialize(void);
-#endif
-
-/****************************************************************************
- * Name: lpc17_caninitialize
- *
- * Description:
- * Initialize the selected can port
- *
- * Input Parameter:
- * Port number (for hardware that has mutiple can interfaces)
- *
- * Returned Value:
- * Valid can device structure reference on succcess; a NULL on failure
- *
- ****************************************************************************/
-
-#if defined(CONFIG_CAN) && (defined(CONFIG_LPC17_CAN1) || defined(CONFIG_LPC17_CAN2))
-struct can_dev_s;
-EXTERN FAR struct can_dev_s *lpc17_caninitialize(int port);
-#endif
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __ASSEMBLY__ */
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_INTERNAL_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_irq.c b/nuttx/arch/arm/src/lpc17xx/lpc17_irq.c
index 8af2adafe..f3e93ffc2 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_irq.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_irq.c
@@ -51,7 +51,9 @@
#include "up_arch.h"
#include "os_internal.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+
+#include "lpc17_gpio.h"
+#include "lpc17_clrpend.h"
/****************************************************************************
* Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c b/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c
index ba90c1ff6..5c34bda1b 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.c
@@ -47,9 +47,11 @@
#include "up_internal.h"
#include "up_arch.h"
-#include "lpc17_internal.h"
-#include "lpc17_syscon.h"
-#include "lpc17_uart.h"
+#include "chip/lpc17_syscon.h"
+#include "chip/lpc17_uart.h"
+
+#include "lpc17_gpio.h"
+#include "lpc17_lowputc.h"
#include "lpc17_serial.h"
/**************************************************************************
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.h b/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.h
new file mode 100644
index 000000000..b1b226e03
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_lowputc.h
@@ -0,0 +1,84 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_lowputc.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_LPC17XX_LPC17_LOWPUTC_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_LOWPUTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc17_lowsetup
+ *
+ * Description:
+ * Called at the very beginning of _start. Performs low level initialization
+ * including setup of the console UART. This UART done early so that the serial
+ * console is available for debugging very early in the boot sequence.
+ *
+ ************************************************************************************/
+
+void lpc17_lowsetup(void);
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_LOWPUTC_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ohciram.h b/nuttx/arch/arm/src/lpc17xx/lpc17_ohciram.h
index 1e0564a87..c508ddf6a 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ohciram.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ohciram.h
@@ -42,7 +42,7 @@
#include <nuttx/config.h>
#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h b/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h
index 6555ce616..d16c61210 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h
@@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_qei.h b/nuttx/arch/arm/src/lpc17xx/lpc17_qei.h
index d1637f943..e2515b102 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_qei.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_qei.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_qei.h
*
- * 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
@@ -41,140 +41,12 @@
************************************************************************************/
#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_qei.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-/* Control registers */
-
-#define LPC17_QEI_CON_OFFSET 0x0000 /* Control register */
-#define LPC17_QEI_STAT_OFFSET 0x0004 /* Encoder status register */
-#define LPC17_QEI_CONF_OFFSET 0x0008 /* Configuration register */
-
-/* Position, index, and timer registers */
-
-#define LPC17_QEI_POS_OFFSET 0x000c /* Position register */
-#define LPC17_QEI_MAXPOS_OFFSET 0x0010 /* Maximum position register */
-#define LPC17_QEI_CMPOS0_OFFSET 0x0014 /* Position compare register */
-#define LPC17_QEI_CMPOS1_OFFSET 0x0018 /* Position compare register */
-#define LPC17_QEI_CMPOS2_OFFSET 0x001c /* Position compare register */
-#define LPC17_QEI_INXCNT_OFFSET 0x0020 /* Index count register */
-#define LPC17_QEI_INXCMP_OFFSET 0x0024 /* Index compare register */
-#define LPC17_QEI_LOAD_OFFSET 0x0028 /* Velocity timer reload register */
-#define LPC17_QEI_TIME_OFFSET 0x002c /* Velocity timer register */
-#define LPC17_QEI_VEL_OFFSET 0x0030 /* Velocity counter register */
-#define LPC17_QEI_CAP_OFFSET 0x0034 /* Velocity capture register */
-#define LPC17_QEI_VELCOMP_OFFSET 0x0038 /* Velocity compare register */
-#define LPC17_QEI_FILTER_OFFSET 0x003c /* Digital filter register */
-
-/* Interrupt registers */
-
-#define LPC17_QEI_IEC_OFFSET 0x0fd8 /* Interrupt enable clear register */
-#define LPC17_QEI_IES_OFFSET 0x0fdc /* Interrupt enable set register */
-#define LPC17_QEI_INTSTAT_OFFSET 0x0fe0 /* Interrupt status register */
-#define LPC17_QEI_IE_OFFSET 0x0fe4 /* Interrupt enable register */
-#define LPC17_QEI_CLR_OFFSET 0x0fe8 /* Interrupt status clear register */
-#define LPC17_QEI_SET_OFFSET 0x0fec /* Interrupt status set register */
-
-/* Register addresses ***************************************************************/
-/* Control registers */
-
-#define LPC17_QEI_CON (LPC17_QEI_BASE+LPC17_QEI_CON_OFFSET)
-#define LPC17_QEI_STAT (LPC17_QEI_BASE+LPC17_QEI_STAT_OFFSET)
-#define LPC17_QEI_CONF (LPC17_QEI_BASE+LPC17_QEI_CONF_OFFSET)
-
-/* Position, index, and timer registers */
-
-#define LPC17_QEI_POS (LPC17_QEI_BASE+LPC17_QEI_POS_OFFSET)
-#define LPC17_QEI_MAXPOS (LPC17_QEI_BASE+LPC17_QEI_MAXPOS_OFFSET)
-#define LPC17_QEI_CMPOS0 (LPC17_QEI_BASE+LPC17_QEI_CMPOS0_OFFSET)
-#define LPC17_QEI_CMPOS1 (LPC17_QEI_BASE+LPC17_QEI_CMPOS1_OFFSET)
-#define LPC17_QEI_CMPOS2 (LPC17_QEI_BASE+LPC17_QEI_CMPOS2_OFFSET)
-#define LPC17_QEI_INXCNT (LPC17_QEI_BASE+LPC17_QEI_INXCNT_OFFSET)
-#define LPC17_QEI_INXCMP (LPC17_QEI_BASE+LPC17_QEI_INXCMP_OFFSET)
-#define LPC17_QEI_LOAD (LPC17_QEI_BASE+LPC17_QEI_LOAD_OFFSET)
-#define LPC17_QEI_TIME (LPC17_QEI_BASE+LPC17_QEI_TIME_OFFSET)
-#define LPC17_QEI_VEL (LPC17_QEI_BASE+LPC17_QEI_VEL_OFFSET)
-#define LPC17_QEI_CAP (LPC17_QEI_BASE+LPC17_QEI_CAP_OFFSET)
-#define LPC17_QEI_VELCOMP (LPC17_QEI_BASE+LPC17_QEI_VELCOMP_OFFSET)
-#define LPC17_QEI_FILTER (LPC17_QEI_BASE+LPC17_QEI_FILTER_OFFSET)
-
-/* Interrupt registers */
-
-#define LPC17_QEI_IEC (LPC17_QEI_BASE+LPC17_QEI_IEC_OFFSET)
-#define LPC17_QEI_IES (LPC17_QEI_BASE+LPC17_QEI_IES_OFFSET)
-#define LPC17_QEI_INTSTAT (LPC17_QEI_BASE+LPC17_QEI_INTSTAT_OFFSET)
-#define LPC17_QEI_IE (LPC17_QEI_BASE+LPC17_QEI_IE_OFFSET)
-#define LPC17_QEI_CLR (LPC17_QEI_BASE+LPC17_QEI_CLR_OFFSET)
-#define LPC17_QEI_SET (LPC17_QEI_BASE+LPC17_QEI_SET_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* The following registers hold 32-bit integer values and have no bit fields defined
- * in this section:
- *
- * Position register (POS)
- * Maximum position register (MAXPOS)
- * Position compare register 0 (CMPOS0)
- * Position compare register 1 (CMPOS)
- * Position compare register 2 (CMPOS2)
- * Index count register (INXCNT)
- * Index compare register (INXCMP)
- * Velocity timer reload register (LOAD)
- * Velocity timer register (TIME)
- * Velocity counter register (VEL)
- * Velocity capture register (CAP)
- * Velocity compare register (VELCOMP)
- * Digital filter register (FILTER)
- */
-
-/* Control registers */
-/* Control register */
-
-#define QEI_CON_RESP (1 << 0) /* Bit 0: Reset position counter */
-#define QEI_CON_RESPI (1 << 1) /* Bit 1: Reset position counter on index */
-#define QEI_CON_RESV (1 << 2) /* Bit 2: Reset velocity */
-#define QEI_CON_RESI (1 << 3) /* Bit 3: Reset index counter */
- /* Bits 4-31: reserved */
-/* Encoder status register */
-
-#define QEI_STAT_DIR (1 << 0) /* Bit 0: Direction bit */
- /* Bits 1-31: reserved */
-/* Configuration register */
-
-#define QEI_CONF_DIRINV (1 << 0) /* Bit 0: Direction invert */
-#define QEI_CONF_SIGMODE (1 << 1) /* Bit 1: Signal Mode */
-#define QEI_CONF_CAPMODE (1 << 2) /* Bit 2: Capture Mode */
-#define QEI_CONF_INVINX (1 << 3) /* Bit 3: Invert Index */
- /* Bits 4-31: reserved */
-/* Position, index, and timer registers (all 32-bit integer values with not bit fields */
-
-/* Interrupt registers */
-/* Interrupt enable clear register (IEC), Interrupt enable set register (IES),
- * Interrupt status register (INTSTAT), Interrupt enable register (IE), Interrupt
- * status clear register (CLR), and Interrupt status set register (SET) common
- * bit definitions.
- */
-
-#define QEI_INT_INX (1 << 0) /* Bit 0: Index pulse detected */
-#define QEI_INT_TIM (1 << 1) /* Bit 1: Velocity timer overflow occurred */
-#define QEI_INT_VELC (1 << 2) /* Bit 2: Captured velocity less than compare velocity */
-#define QEI_INT_DIR (1 << 3) /* Bit 3: Change of direction detected */
-#define QEI_INT_ERR (1 << 4) /* Bit 4: Encoder phase error detected */
-#define QEI_INT_ENCLK (1 << 5) /* Bit 5: Eencoder clock pulse detected */
-#define QEI_INT_POS0 (1 << 6) /* Bit 6: Position 0 compare equal to current position */
-#define QEI_INT_POS1 (1 << 7) /* Bit 7: Position 1 compare equal to current position */
-#define QEI_INT_POS2 (1 << 8) /* Bit 8: Position 2 compare equal to current position */
-#define QEI_INT_REV (1 << 9) /* Bit 9: Index compare value equal to current index count */
-#define QEI_INT_POS0REV (1 << 10) /* Bit 10: Combined position 0 and revolution count interrupt */
-#define QEI_INT_POS1REV (1 << 11) /* Bit 11: Position 1 and revolution count interrupt */
-#define QEI_INT_POS2REV (1 << 12) /* Bit 12: Position 2 and revolution count interrupt */
- /* Bits 13-31: reserved */
-
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_rit.h b/nuttx/arch/arm/src/lpc17xx/lpc17_rit.h
index 2da0164bd..4c0949a46 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_rit.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_rit.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_rit.h
*
- * 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
@@ -41,42 +41,12 @@
************************************************************************************/
#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_rit.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-
-#define LPC17_RIT_COMPVAL_OFFSET 0x0000 /* Compare register */
-#define LPC17_RIT_MASK_OFFSET 0x0004 /* Mask register */
-#define LPC17_RIT_CTRL_OFFSET 0x0008 /* Control register */
-#define LPC17_RIT_COUNTER_OFFSET 0x000c /* 32-bit counter */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_RIT_COMPVAL (LPC17_RIT_BASE+LPC17_RIT_COMPVAL_OFFSET)
-#define LPC17_RIT_MASK (LPC17_RIT_BASE+LPC17_RIT_MASK_OFFSET)
-#define LPC17_RIT_CTRL (LPC17_RIT_BASE+LPC17_RIT_CTRL_OFFSET)
-#define LPC17_RIT_COUNTER (LPC17_RIT_BASE+LPC17_RIT_COUNTER_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* Compare register (Bits 0-31: value compared to the counter) */
-
-/* Mask register (Bits 0-31: 32-bit mask value) */
-
-/* Control register */
-
-#define RIT_CTRL_INT (1 << 0) /* Bit 0: Interrupt flag */
-#define RIT_CTRL_ENCLR (1 << 1) /* Bit 1: Timer enable clear */
-#define RIT_CTRL_ENBR (1 << 2) /* Bit 2: Timer enable for debug */
-#define RIT_CTRL_EN (1 << 3) /* Bit 3: Timer enable */
- /* Bits 4-31: Reserved */
-/* 32-bit counter (Bits 0-31: 32-bit up counter) */
-
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_rtc.h b/nuttx/arch/arm/src/lpc17xx/lpc17_rtc.h
index 195e403c1..9011cd84a 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_rtc.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_rtc.h
@@ -1,270 +1,62 @@
-/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_rtc.h
- *
- * Copyright (C) 2010, 2012 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_LPC17XX_LPC17_RTC_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_RTC_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
-
-/************************************************************************************
- * Pre-processor Definitions
- ************************************************************************************/
-
-/* Register offsets *****************************************************************/
-/* Miscellaneous registers */
-
-#define LPC17_RTC_ILR_OFFSET 0x0000 /* Interrupt Location Register */
-#define LPC17_RTC_CCR_OFFSET 0x0008 /* Clock Control Register */
-#define LPC17_RTC_CIIR_OFFSET 0x000c /* Counter Increment Interrupt Register */
-#define LPC17_RTC_AMR_OFFSET 0x0010 /* Alarm Mask Register */
-#define LPC17_RTC_AUXEN_OFFSET 0x0058 /* RTC Auxiliary Enable register */
-#define LPC17_RTC_AUX_OFFSET 0x005c /* RTC Auxiliary control register */
-
-/* Consolidated time registers */
-
-#define LPC17_RTC_CTIME0_OFFSET 0x0014 /* Consolidated Time Register 0 */
-#define LPC17_RTC_CTIME1_OFFSET 0x0018 /* Consolidated Time Register 1 */
-#define LPC17_RTC_CTIME2_OFFSET 0x001c /* Consolidated Time Register 2 */
-
-/* Time counter registers */
-
-#define LPC17_RTC_SEC_OFFSET 0x0020 /* Seconds Counter */
-#define LPC17_RTC_MIN_OFFSET 0x0024 /* Minutes Register */
-#define LPC17_RTC_HOUR_OFFSET 0x0028 /* Hours Register */
-#define LPC17_RTC_DOM_OFFSET 0x002c /* Day of Month Register */
-#define LPC17_RTC_DOW_OFFSET 0x0030 /* Day of Week Register */
-#define LPC17_RTC_DOY_OFFSET 0x0034 /* Day of Year Register */
-#define LPC17_RTC_MONTH_OFFSET 0x0038 /* Months Register */
-#define LPC17_RTC_YEAR_OFFSET 0x003c /* Years Register */
-#define LPC17_RTC_CALIB_OFFSET 0x0040 /* Calibration Value Register */
-
-/* General purpose registers */
-
-#define LPC17_RTC_GPREG0_OFFSET 0x0044 /* General Purpose Register 0 */
-#define LPC17_RTC_GPREG1_OFFSET 0x0048 /* General Purpose Register 1 */
-#define LPC17_RTC_GPREG2_OFFSET 0x004c /* General Purpose Register 2 */
-#define LPC17_RTC_GPREG3_OFFSET 0x0050 /* General Purpose Register 3 */
-#define LPC17_RTC_GPREG4_OFFSET 0x0054 /* General Purpose Register 4 */
-
-/* Alarm register group */
-
-#define LPC17_RTC_ALSEC_OFFSET 0x0060 /* Alarm value for Seconds */
-#define LPC17_RTC_ALMIN_OFFSET 0x0064 /* Alarm value for Minutes */
-#define LPC17_RTC_ALHOUR_OFFSET 0x0068 /* Alarm value for Hours */
-#define LPC17_RTC_ALDOM_OFFSET 0x006c /* Alarm value for Day of Month */
-#define LPC17_RTC_ALDOW_OFFSET 0x0070 /* Alarm value for Day of Week */
-#define LPC17_RTC_ALDOY_OFFSET 0x0074 /* Alarm value for Day of Year */
-#define LPC17_RTC_ALMON_OFFSET 0x0078 /* Alarm value for Months */
-#define LPC17_RTC_ALYEAR_OFFSET 0x007c /* Alarm value for Year */
-
-/* Register addresses ***************************************************************/
-/* Miscellaneous registers */
-
-#define LPC17_RTC_ILR (LPC17_RTC_BASE+LPC17_RTC_ILR_OFFSET)
-#define LPC17_RTC_CCR (LPC17_RTC_BASE+LPC17_RTC_CCR_OFFSET)
-#define LPC17_RTC_CIIR (LPC17_RTC_BASE+LPC17_RTC_CIIR_OFFSET)
-#define LPC17_RTC_AMR (LPC17_RTC_BASE+LPC17_RTC_AMR_OFFSET)
-#define LPC17_RTC_AUXEN (LPC17_RTC_BASE+LPC17_RTC_AUXEN_OFFSET)
-#define LPC17_RTC_AUX (LPC17_RTC_BASE+LPC17_RTC_AUX_OFFSET)
-
-/* Consolidated time registers */
-
-#define LPC17_RTC_CTIME0 (LPC17_RTC_BASE+LPC17_RTC_CTIME0_OFFSET)
-#define LPC17_RTC_CTIME1 (LPC17_RTC_BASE+LPC17_RTC_CTIME1_OFFSET)
-#define LPC17_RTC_CTIME2 (LPC17_RTC_BASE+LPC17_RTC_CTIME2_OFFSET)
-
-/* Time counter registers */
-
-#define LPC17_RTC_SEC (LPC17_RTC_BASE+LPC17_RTC_SEC_OFFSET)
-#define LPC17_RTC_MIN (LPC17_RTC_BASE+LPC17_RTC_MIN_OFFSET)
-#define LPC17_RTC_HOUR (LPC17_RTC_BASE+LPC17_RTC_HOUR_OFFSET)
-#define LPC17_RTC_DOM (LPC17_RTC_BASE+LPC17_RTC_DOM_OFFSET)
-#define LPC17_RTC_DOW (LPC17_RTC_BASE+LPC17_RTC_DOW_OFFSET)
-#define LPC17_RTC_DOY (LPC17_RTC_BASE+LPC17_RTC_DOY_OFFSET)
-#define LPC17_RTC_MONTH (LPC17_RTC_BASE+LPC17_RTC_MONTH_OFFSET)
-#define LPC17_RTC_YEAR (LPC17_RTC_BASE+LPC17_RTC_YEAR_OFFSET)
-#define LPC17_RTC_CALIB (LPC17_RTC_BASE+LPC17_RTC_CALIB_OFFSET)
-
-/* General purpose registers */
-
-#define LPC17_RTC_GPREG0 (LPC17_RTC_BASE+LPC17_RTC_GPREG0_OFFSET)
-#define LPC17_RTC_GPREG1 (LPC17_RTC_BASE+LPC17_RTC_GPREG1_OFFSET)
-#define LPC17_RTC_GPREG2 (LPC17_RTC_BASE+LPC17_RTC_GPREG2_OFFSET)
-#define LPC17_RTC_GPREG3 (LPC17_RTC_BASE+LPC17_RTC_GPREG3_OFFSET)
-#define LPC17_RTC_GPREG4 (LPC17_RTC_BASE+LPC17_RTC_GPREG4_OFFSET)
-
-/* Alarm register group */
-
-#define LPC17_RTC_ALSEC (LPC17_RTC_BASE+LPC17_RTC_ALSEC_OFFSET)
-#define LPC17_RTC_ALMIN (LPC17_RTC_BASE+LPC17_RTC_ALMIN_OFFSET)
-#define LPC17_RTC_ALHOUR (LPC17_RTC_BASE+LPC17_RTC_ALHOUR_OFFSET)
-#define LPC17_RTC_ALDOM (LPC17_RTC_BASE+LPC17_RTC_ALDOM_OFFSET)
-#define LPC17_RTC_ALDOW (LPC17_RTC_BASE+LPC17_RTC_ALDOW_OFFSET)
-#define LPC17_RTC_ALDOY (LPC17_RTC_BASE+LPC17_RTC_ALDOY_OFFSET)
-#define LPC17_RTC_ALMON (LPC17_RTC_BASE+LPC17_RTC_ALMON_OFFSET)
-#define LPC17_RTC_ALYEAR (LPC17_RTC_BASE+LPC17_RTC_ALYEAR_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* The following registers hold 32-bit values and have no bit fields to be defined:
- *
- * General Purpose Register 0
- * General Purpose Register 1
- * General Purpose Register 2
- * General Purpose Register 3
- * General Purpose Register 4
- */
-
-/* Miscellaneous registers */
-/* Interrupt Location Register */
-
-#define RTC_ILR_RTCCIF (1 << 0) /* Bit 0: Counter Increment Interrupt */
-#define RTC_ILR_RTCALF (1 << 1) /* Bit 1: Alarm interrupt */
- /* Bits 2-31: Reserved */
-/* Clock Control Register */
-
-#define RTC_CCR_CLKEN (1 << 0) /* Bit 0: Clock Enable */
-#define RTC_CCR_CTCRST (1 << 1) /* Bit 1: CTC Reset */
- /* Bits 2-3: Internal test mode controls */
-#define RTC_CCR_CCALEN (1 << 4) /* Bit 4: Calibration counter enable */
- /* Bits 5-31: Reserved */
-/* Counter Increment Interrupt Register */
-
-#define RTC_CIIR_IMSEC (1 << 0) /* Bit 0: Second interrupt */
-#define RTC_CIIR_IMMIN (1 << 1) /* Bit 1: Minute interrupt */
-#define RTC_CIIR_IMHOUR (1 << 2) /* Bit 2: Hour interrupt */
-#define RTC_CIIR_IMDOM (1 << 3) /* Bit 3: Day of Month value interrupt */
-#define RTC_CIIR_IMDOW (1 << 4) /* Bit 4: Day of Week value interrupt */
-#define RTC_CIIR_IMDOY (1 << 5) /* Bit 5: Day of Year interrupt */
-#define RTC_CIIR_IMMON (1 << 6) /* Bit 6: Month interrupt */
-#define RTC_CIIR_IMYEAR (1 << 7) /* Bit 7: Yearinterrupt */
- /* Bits 8-31: Reserved */
-/* Alarm Mask Register */
-
-#define RTC_AMR_SEC (1 << 0) /* Bit 0: Second not compared for alarm */
-#define RTC_AMR_MIN (1 << 1) /* Bit 1: Minutes not compared for alarm */
-#define RTC_AMR_HOUR (1 << 2) /* Bit 2: Hour not compared for alarm */
-#define RTC_AMR_DOM (1 << 3) /* Bit 3: Day of Monthnot compared for alarm */
-#define RTC_AMR_DOW (1 << 4) /* Bit 4: Day of Week not compared for alarm */
-#define RTC_AMR_DOY (1 << 5) /* Bit 5: Day of Year not compared for alarm */
-#define RTC_AMR_MON (1 << 6) /* Bit 6: Month not compared for alarm */
-#define RTC_AMR_YEAR (1 << 7) /* Bit 7: Year not compared for alarm */
- /* Bits 8-31: Reserved */
-/* RTC Auxiliary Enable register */
- /* Bits 0-3: Reserved */
-#define RTC_AUXEN_RTCOSCF (1 << 4) /* Bit 4: RTC Oscillator Fail detect flag */
- /* Bits 5-31: Reserved */
-/* RTC Auxiliary control register */
- /* Bits 0-3: Reserved */
-#define RTC_AUX_OSCFEN (1 << 4) /* Bit 4: Oscillator Fail Detect interrupt enable */
- /* Bits 5-31: Reserved */
-/* Consolidated time registers */
-/* Consolidated Time Register 0 */
-
-#define RTC_CTIME0_SEC_SHIFT (0) /* Bits 0-5: Seconds */
-#define RTC_CTIME0_SEC_MASK (63 << RTC_CTIME0_SEC_SHIFT)
- /* Bits 6-7: Reserved */
-#define RTC_CTIME0_MIN_SHIFT (8) /* Bits 8-13: Minutes */
-#define RTC_CTIME0_MIN_MASK (63 << RTC_CTIME0_MIN_SHIFT)
- /* Bits 14-15: Reserved */
-#define RTC_CTIME0_HOURS_SHIFT (16) /* Bits 16-20: Hours */
-#define RTC_CTIME0_HOURS_MASK (31 << RTC_CTIME0_HOURS_SHIFT)
- /* Bits 21-23: Reserved */
-#define RTC_CTIME0_DOW_SHIFT (24) /* Bits 24-26: Day of Week */
-#define RTC_CTIME0_DOW_MASK (7 << RTC_CTIME0_DOW_SHIFT)
- /* Bits 27-31: Reserved */
-/* Consolidated Time Register 1 */
-
-#define RTC_CTIME1_DOM_SHIFT (0) /* Bits 0-4: Day of Month */
-#define RTC_CTIME1_DOM_MASK (31 << RTC_CTIME1_DOM_SHIFT)
- /* Bits 5-7: Reserved */
-#define RTC_CTIME1_MON_SHIFT (8) /* Bits 8-11: Month */
-#define RTC_CTIME1_MON_MASK (15 << RTC_CTIME1_MON_SHIFT)
- /* Bits 12-15: Reserved */
-#define RTC_CTIME1_YEAR_SHIFT (16) /* Bits 16-27: Year */
-#define RTC_CTIME1_YEAR_MASK (0x0fff << RTC_CTIME1_YEAR_SHIFT)
- /* Bits 28-31: Reserved */
-/* Consolidated Time Register 2 */
-
-#define RTC_CTIME2_DOY_SHIFT (0) /* Bits 0-11: Day of Year */
-#define RTC_CTIME2_DOY_MASK (0x0fff << RTC_CTIME2_DOY_SHIFT)
- /* Bits 12-31: Reserved */
-/* Time counter registers */
-
-#define RTC_SEC_MASK (0x003f)
-#define RTC_MIN_MASK (0x003f)
-#define RTC_HOUR_MASK (0x001f)
-#define RTC_DOM_MASK (0x001f)
-#define RTC_DOW_MASK (0x0007)
-#define RTC_DOY_MASK (0x01ff)
-#define RTC_MONTH_MASK (0x000f)
-#define RTC_YEAR_MASK (0x0fff)
-
-/* Calibration Value Register */
-
-#define RTC_CALIB_CALVAL_SHIFT (0) /* Bits 0-16: calibration counter counts to this value */
-#define RTC_CALIB_CALVAL_MASK (0xffff << RTC_CALIB_CALVAL_SHIFT)
-#define RTC_CALIB_CALDIR (1 << 17) /* Bit 17: Calibration direction */
- /* Bits 18-31: Reserved */
-/* Alarm register group */
-
-#define RTC_ALSEC_MASK (0x003f)
-#define RTC_ALMIN_MASK (0x003f)
-#define RTC_ALHOUR_MASK (0x001f)
-#define RTC_ALDOM_MASK (0x001f)
-#define RTC_ALDOW_MASK (0x0007)
-#define RTC_ALDOY_MASK (0x01ff)
-#define RTC_ALMON_MASK (0x000f)
-#define RTC_ALYEAR_MASK (0x0fff)
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
- * Public Data
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_RTC_H */
+/************************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_rtc.h
+ *
+ * Copyright (C) 2010, 2012-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_LPC17XX_LPC17_RTC_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_RTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/lpc17_rtc.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_RTC_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_serial.c b/nuttx/arch/arm/src/lpc17xx/lpc17_serial.c
index 5ea6348e0..c94f2ff60 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_serial.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_serial.c
@@ -58,13 +58,13 @@
#include <arch/serial.h>
#include <arch/board/board.h>
-#include "chip.h"
#include "up_arch.h"
#include "os_internal.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
-#include "lpc17_uart.h"
+#include "chip.h"
+#include "chip/lpc17_uart.h"
+#include "lpc17_gpio.h"
#include "lpc17_serial.h"
/****************************************************************************
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_serial.h b/nuttx/arch/arm/src/lpc17xx/lpc17_serial.h
index 27d7da9d1..95e8155de 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_serial.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_serial.h
@@ -43,8 +43,10 @@
#include <nuttx/config.h>
#include <arch/board/board.h>
-#include "lpc17_uart.h"
-#include "lpc17_syscon.h"
+#include "chip/lpc17_uart.h"
+#include "chip/lpc17_syscon.h"
+
+#include "lpc17_gpio.h"
/************************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_spi.c b/nuttx/arch/arm/src/lpc17xx/lpc17_spi.c
index a7bb15931..05e791434 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_spi.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_spi.c
@@ -54,9 +54,8 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
-#include "lpc17_syscon.h"
-#include "lpc17_pinconn.h"
+#include "chip/lpc17_syscon.h"
+#include "lpc17_gpio.h"
#include "lpc17_spi.h"
#ifdef CONFIG_LPC17_SPI
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_spi.h b/nuttx/arch/arm/src/lpc17xx/lpc17_spi.h
index 880966eb1..e6898aac7 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_spi.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_spi.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_spi.h
*
- * 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
@@ -42,90 +42,14 @@
#include <nuttx/config.h>
-#include "chip.h"
-#include "lpc17_memorymap.h"
+#include <nuttx/spi.h>
+
+#include "chip/lpc17_spi.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-
-#define LPC17_SPI_CR_OFFSET 0x0000 /* Control Register */
-#define LPC17_SPI_SR_OFFSET 0x0004 /* SPI Status Register */
-#define LPC17_SPI_DR_OFFSET 0x0008 /* SPI Data Register */
-#define LPC17_SPI_CCR_OFFSET 0x000c /* SPI Clock Counter Register */
-#define LPC17_SPI_TCR_OFFSET 0x0010 /* SPI Test Control Register */
-#define LPC17_SPI_TSR_OFFSET 0x0014 /* SPI Test Status Register */
-#define LPC17_SPI_INT_OFFSET 0x001c /* SPI Interrupt Register */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_SPI_CR (LPC17_SPI_BASE+LPC17_SPI_CR_OFFSET)
-#define LPC17_SPI_SR (LPC17_SPI_BASE+LPC17_SPI_SR_OFFSET)
-#define LPC17_SPI_DR (LPC17_SPI_BASE+LPC17_SPI_DR_OFFSET)
-#define LPC17_SPI_CCR (LPC17_SPI_BASE+LPC17_SPI_CCR_OFFSET)
-#define LPC17_TCR_CCR (LPC17_SPI_BASE+LPC17_SPI_TCR_OFFSET)
-#define LPC17_TSR_CCR (LPC17_SPI_BASE+LPC17_SPI_TSR_OFFSET)
-#define LPC17_SPI_INT (LPC17_SPI_BASE+LPC17_SPI_INT_OFFSET)
-
-/* Register bit definitions *********************************************************/
-
-/* Control Register */
- /* Bits 0-1: Reserved */
-#define SPI_CR_BITENABLE (1 << 2) /* Bit 2: Enable word size selected by BITS */
-#define SPI_CR_CPHA (1 << 3) /* Bit 3: Clock phase control */
-#define SPI_CR_CPOL (1 << 4) /* Bit 4: Clock polarity control */
-#define SPI_CR_MSTR (1 << 5) /* Bit 5: Master mode select */
-#define SPI_CR_LSBF (1 << 6) /* Bit 6: SPI data is transferred LSB first */
-#define SPI_CR_SPIE (1 << 7) /* Bit 7: Serial peripheral interrupt enable */
-#define SPI_CR_BITS_SHIFT (8) /* Bits 8-11: Number of bits per word (BITENABLE==1) */
-#define SPI_CR_BITS_MASK (15 << SPI_CR_BITS_SHIFT)
-# define SPI_CR_BITS_8BITS (8 << SPI_CR_BITS_SHIFT) /* 8 bits per transfer */
-# define SPI_CR_BITS_9BITS (9 << SPI_CR_BITS_SHIFT) /* 9 bits per transfer */
-# define SPI_CR_BITS_10BITS (10 << SPI_CR_BITS_SHIFT) /* 10 bits per transfer */
-# define SPI_CR_BITS_11BITS (11 << SPI_CR_BITS_SHIFT) /* 11 bits per transfer */
-# define SPI_CR_BITS_12BITS (12 << SPI_CR_BITS_SHIFT) /* 12 bits per transfer */
-# define SPI_CR_BITS_13BITS (13 << SPI_CR_BITS_SHIFT) /* 13 bits per transfer */
-# define SPI_CR_BITS_14BITS (14 << SPI_CR_BITS_SHIFT) /* 14 bits per transfer */
-# define SPI_CR_BITS_15BITS (15 << SPI_CR_BITS_SHIFT) /* 15 bits per transfer */
-# define SPI_CR_BITS_16BITS (0 << SPI_CR_BITS_SHIFT) /* 16 bits per transfer */
- /* Bits 12-31: Reserved */
-/* SPI Status Register */
- /* Bits 0-2: Reserved */
-#define SPI_SR_ABRT (1 << 3) /* Bit 3: Slave abort */
-#define SPI_SR_MODF (1 << 4) /* Bit 4: Mode fault */
-#define SPI_SR_ROVR (1 << 5) /* Bit 5: Read overrun */
-#define SPI_SR_WCOL (1 << 6) /* Bit 6: Write collision */
-#define SPI_SR_SPIF (1 << 7) /* Bit 7: SPI transfer complete */
- /* Bits 8-31: Reserved */
-/* SPI Data Register */
-
-#define SPI_DR_MASK (0xff) /* Bits 0-15: SPI Bi-directional data port */
-#define SPI_DR_MASKWIDE (0xffff) /* Bits 0-15: If SPI_CR_BITENABLE != 0 */
- /* Bits 8-31: Reserved */
-/* SPI Clock Counter Register */
-
-#define SPI_CCR_MASK (0xff) /* Bits 0-7: SPI Clock counter setting */
- /* Bits 8-31: Reserved */
-/* SPI Test Control Register */
- /* Bit 0: Reserved */
-#define SPI_TCR_TEST_SHIFT (1) /* Bits 1-7: SPI test mode */
-#define SPI_TCR_TEST_MASK (0x7f << SPI_TCR_TEST_SHIFT)
- /* Bits 8-31: Reserved */
-/* SPI Test Status Register */
- /* Bits 0-2: Reserved */
-#define SPI_TSR_ABRT (1 << 3) /* Bit 3: Slave abort */
-#define SPI_TSR_MODF (1 << 4) /* Bit 4: Mode fault */
-#define SPI_TSR_ROVR (1 << 5) /* Bit 5: Read overrun */
-#define SPI_TSR_WCOL (1 << 6) /* Bit 6: Write collision */
-#define SPI_TSR_SPIF (1 << 7) /* Bit 7: SPI transfer complete */
- /* Bits 8-31: Reserved */
-/* SPI Interrupt Register */
-
-#define SPI_INT_SPIF (1 << 0) /* SPI interrupt */
- /* Bits 1-31: Reserved */
-
/************************************************************************************
* Public Types
************************************************************************************/
@@ -134,8 +58,97 @@
* Public Data
************************************************************************************/
+#ifdef CONFIG_LPC17_SPI
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
/************************************************************************************
* Public Functions
************************************************************************************/
+/************************************************************************************
+ * Name: lpc17_spiselect, lpc17_status, and lpc17_spicmddata
+ *
+ * Description:
+ * These external functions must be provided by board-specific logic. They are
+ * implementations of the select, status, and cmddata methods of the SPI interface
+ * defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods
+ * including up_spiinitialize()) are provided by common LPC17xx logic. To use
+ * this common SPI logic on your board:
+ *
+ * 1. Provide logic in lpc17_boardinitialize() to configure SPI chip select pins.
+ * 2. Provide lpc17_spiselect() and lpc17_spistatus() functions in your board-
+ * specific logic. These functions will perform chip selection and status
+ * operations using GPIOs in the way your board is configured.
+ * 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
+ * lpc17_spicmddata() functions in your board-specific logic. This function
+ * will perform cmd/data selection operations using GPIOs in the way your
+ * board is configured.
+ * 3. Add a call to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling mmcsd_spislotinitialize(),
+ * for example, will bind the SPI driver to the SPI MMC/SD driver).
+ *
+ ************************************************************************************/
+
+void lpc17_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+uint8_t lpc17_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_SPI_CMDDATA
+int lpc17_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+#endif
+
+/****************************************************************************
+ * Name: spi_flush
+ *
+ * Description:
+ * Flush and discard any words left in the RX fifo. This can be called
+ * from spiselect after a device is deselected (if you worry about such
+ * things).
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void spi_flush(FAR struct spi_dev_s *dev);
+
+/****************************************************************************
+ * Name: lpc17_spiregister
+ *
+ * Description:
+ * If the board supports a card detect callback to inform the SPI-based
+ * MMC/SD drvier when an SD card is inserted or removed, then
+ * CONFIG_SPI_CALLBACK should be defined and the following function must
+ * must be implemented. These functions implements the registercallback
+ * method of the SPI interface (see include/nuttx/spi.h for details)
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * callback - The funtion to call on the media change
+ * arg - A caller provided value to return with the callback
+ *
+ * Returned Value:
+ * 0 on success; negated errno on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SPI_CALLBACK
+nt lpc17_spiregister(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
+ FAR void *arg);
+#endif
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_LPC17_SPI */
#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_SPI_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.c b/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.c
index db6fbe1f8..96b66d7a1 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.c
@@ -54,9 +54,8 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
-#include "lpc17_syscon.h"
-#include "lpc17_pinconn.h"
+#include "chip/lpc17_syscon.h"
+#include "lpc17_gpio.h"
#include "lpc17_ssp.h"
#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.h b/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.h
index 52b88da68..edc6846ba 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.h
@@ -1,174 +1,173 @@
-/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_ssp.h
- *
- * Copyright (C) 2010, 2012 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_LPC17XX_LPC17_SSP_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_SSP_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
-
-/************************************************************************************
- * Pre-processor Definitions
- ************************************************************************************/
-/* 8 frame FIFOs for both transmit and receive */
-
-#define LPC17_SSP_FIFOSZ 8
-
-/* Register offsets *****************************************************************/
-
-#define LPC17_SSP_CR0_OFFSET 0x0000 /* Control Register 0 */
-#define LPC17_SSP_CR1_OFFSET 0x0004 /* Control Register 1 */
-#define LPC17_SSP_DR_OFFSET 0x0008 /* Data Register */
-#define LPC17_SSP_SR_OFFSET 0x000c /* Status Register */
-#define LPC17_SSP_CPSR_OFFSET 0x0010 /* Clock Prescale Register */
-#define LPC17_SSP_IMSC_OFFSET 0x0014 /* Interrupt Mask Set and Clear Register */
-#define LPC17_SSP_RIS_OFFSET 0x0018 /* Raw Interrupt Status Register */
-#define LPC17_SSP_MIS_OFFSET 0x001c /* Masked Interrupt Status Register */
-#define LPC17_SSP_ICR_OFFSET 0x0020 /* Interrupt Clear Register */
-#define LPC17_SSP_DMACR_OFFSET 0x0024 /* DMA Control Register */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_SSP0_CR0 (LPC17_SSP0_BASE+LPC17_SSP_CR0_OFFSET)
-#define LPC17_SSP0_CR1 (LPC17_SSP0_BASE+LPC17_SSP_CR1_OFFSET)
-#define LPC17_SSP0_DR (LPC17_SSP0_BASE+LPC17_SSP_DR_OFFSET)
-#define LPC17_SSP0_SR (LPC17_SSP0_BASE+LPC17_SSP_SR_OFFSET)
-#define LPC17_SSP0_CPSR (LPC17_SSP0_BASE+LPC17_SSP_CPSR_OFFSET)
-#define LPC17_SSP0_IMSC (LPC17_SSP0_BASE+LPC17_SSP_IMSC_OFFSET)
-#define LPC17_SSP0_RIS (LPC17_SSP0_BASE+LPC17_SSP_RIS_OFFSET)
-#define LPC17_SSP0_MIS (LPC17_SSP0_BASE+LPC17_SSP_MIS_OFFSET)
-#define LPC17_SSP0_ICR (LPC17_SSP0_BASE+LPC17_SSP_ICR_OFFSET)
-#define LPC17_SSP0_DMACR (LPC17_SSP0_BASE+LPC17_SSP_DMACR_OFFSET)
-
-#define LPC17_SSP1_CR0 (LPC17_SSP1_BASE+LPC17_SSP_CR0_OFFSET)
-#define LPC17_SSP1_CR1 (LPC17_SSP1_BASE+LPC17_SSP_CR1_OFFSET)
-#define LPC17_SSP1_DR (LPC17_SSP1_BASE+LPC17_SSP_DR_OFFSET)
-#define LPC17_SSP1_SR (LPC17_SSP1_BASE+LPC17_SSP_SR_OFFSET)
-#define LPC17_SSP1_CPSR (LPC17_SSP1_BASE+LPC17_SSP_CPSR_OFFSET)
-#define LPC17_SSP1_IMSC (LPC17_SSP1_BASE+LPC17_SSP_IMSC_OFFSET)
-#define LPC17_SSP1_RIS (LPC17_SSP1_BASE+LPC17_SSP_RIS_OFFSET)
-#define LPC17_SSP1_MIS (LPC17_SSP1_BASE+LPC17_SSP_MIS_OFFSET)
-#define LPC17_SSP1_ICR (LPC17_SSP1_BASE+LPC17_SSP_ICR_OFFSET)
-#define LPC17_SSP1_DMACR (LPC17_SSP1_BASE+LPC17_SSP_DMACR_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* Control Register 0 */
-
-#define SSP_CR0_DSS_SHIFT (0) /* Bits 0-3: DSS Data Size Select */
-#define SSP_CR0_DSS_MASK (15 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_4BIT (3 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_5BIT (4 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_6BIT (5 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_7BIT (6 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_8BIT (7 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_9BIT (8 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_10BIT (9 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_11BIT (10 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_12BIT (11 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_13BIT (12 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_14BIT (13 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_15BIT (14 << SSP_CR0_DSS_SHIFT)
-# define SSP_CR0_DSS_16BIT (15 << SSP_CR0_DSS_SHIFT)
-#define SSP_CR0_FRF_SHIFT (4) /* Bits 4-5: FRF Frame Format */
-#define SSP_CR0_FRF_MASK (3 << SSP_CR0_FRF_SHIFT)
-# define SSP_CR0_FRF_SPI (0 << SSP_CR0_FRF_SHIFT)
-# define SSP_CR0_FRF_TI (1 << SSP_CR0_FRF_SHIFT)
-# define SSP_CR0_FRF_UWIRE (2 << SSP_CR0_FRF_SHIFT)
-#define SSP_CR0_CPOL (1 << 6) /* Bit 6: Clock Out Polarity */
-#define SSP_CR0_CPHA (1 << 7) /* Bit 7: Clock Out Phase */
-#define SSP_CR0_SCR_SHIFT (8) /* Bits 8-15: Serial Clock Rate */
-#define SSP_CR0_SCR_MASK (0xff << SSP_CR0_SCR_SHIFT)
- /* Bits 8-31: Reserved */
-/* Control Register 1 */
-
-#define SSP_CR1_LBM (1 << 0) /* Bit 0: Loop Back Mode */
-#define SSP_CR1_SSE (1 << 1) /* Bit 1: SSP Enable */
-#define SSP_CR1_MS (1 << 2) /* Bit 2: Master/Slave Mode */
-#define SSP_CR1_SOD (1 << 3) /* Bit 3: Slave Output Disable */
- /* Bits 4-31: Reserved */
-/* Data Register */
-
-#define SSP_DR_MASK (0xffff) /* Bits 0-15: Data */
- /* Bits 16-31: Reserved */
-/* Status Register */
-
-#define SSP_SR_TFE (1 << 0) /* Bit 0: Transmit FIFO Empty */
-#define SSP_SR_TNF (1 << 1) /* Bit 1: Transmit FIFO Not Full */
-#define SSP_SR_RNE (1 << 2) /* Bit 2: Receive FIFO Not Empty */
-#define SSP_SR_RFF (1 << 3) /* Bit 3: Receive FIFO Full */
-#define SSP_SR_BSY (1 << 4) /* Bit 4: Busy */
- /* Bits 5-31: Reserved */
-/* Clock Prescale Register */
-
-#define SSP_CPSR_DVSR_MASK (0xff) /* Bits 0-7: clock = SSP_PCLK/DVSR */
- /* Bits 8-31: Reserved */
-/* Common format for interrupt control registers:
- *
- * Interrupt Mask Set and Clear Register (IMSC)
- * Raw Interrupt Status Register (RIS)
- * Masked Interrupt Status Register (MIS)
- * Interrupt Clear Register (ICR)
- */
-
-#define SSP_INT_ROR (1 << 0) /* Bit 0: RX FIFO overrun */
-#define SSP_INT_RT (1 << 1) /* Bit 1: RX FIFO timeout */
-#define SSP_INT_RX (1 << 2) /* Bit 2: RX FIFO at least half full (not ICR) */
-#define SSP_INT_TX (1 << 3 ) /* Bit 3: TX FIFO at least half empy (not ICR) */
- /* Bits 4-31: Reserved */
-/* DMA Control Register */
-
-#define SSP_DMACR_RXDMAE (1 << 0) /* Bit 0: Receive DMA Enable */
-#define SSP_DMACR_TXDMAE (1 << 1) /* Bit 1: Transmit DMA Enable */
- /* Bits 2-31: Reserved */
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
- * Public Data
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_SSP_H */
+/************************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_ssp.h
+ *
+ * Copyright (C) 2010, 2012-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_LPC17XX_LPC17_SSP_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_SSP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/spi.h>
+
+#include "chip/lpc17_ssp.h"
+
+#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc17_ssp0/ssp1select, lpc17_ssp0/ssp1status, and lpc17_ssp0/ssp1cmddata
+ *
+ * Description:
+ * These external functions must be provided by board-specific logic. They are
+ * implementations of the select, status, and cmddata methods of the SPI interface
+ * defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods
+ * including up_spiinitialize()) are provided by common LPC17xx logic. To use
+ * this common SPI logic on your board:
+ *
+ * 1. Provide logic in lpc17_boardinitialize() to configure SSP chip select pins.
+ * 2. Provide lpc17_ssp0/ssp1select() and lpc17_ssp0/ssp1status() functions
+ * in your board-specific logic. These functions will perform chip selection
+ * and status operations using GPIOs in the way your board is configured.
+ * 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
+ * lpc17_ssp0/ssp1cmddata() functions in your board-specific logic. These
+ * functions will perform cmd/data selection operations using GPIOs in the way
+ * your board is configured.
+ * 3. Add a call to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SSP driver to higher level logic (e.g., calling mmcsd_spislotinitialize(),
+ * for example, will bind the SSP driver to the SPI MMC/SD driver).
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_LPC17_SSP0
+void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_SPI_CMDDATA
+int lpc17_ssp0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+#endif
+#endif
+
+#ifdef CONFIG_LPC17_SSP1
+void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_SPI_CMDDATA
+int lpc17_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+#endif
+#endif
+
+/****************************************************************************
+ * Name: ssp_flush
+ *
+ * Description:
+ * Flush and discard any words left in the RX fifo. This can be called
+ * from ssp0/1select after a device is deselected (if you worry about such
+ * things).
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
+void ssp_flush(FAR struct spi_dev_s *dev);
+#endif
+
+/****************************************************************************
+ * Name: lpc17_ssp0/1register
+ *
+ * Description:
+ * If the board supports a card detect callback to inform the SPI-based
+ * MMC/SD drvier when an SD card is inserted or removed, then
+ * CONFIG_SPI_CALLBACK should be defined and the following function(s) must
+ * must be implemented. These functiosn implements the registercallback
+ * method of the SPI interface (see include/nuttx/spi.h for details)
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * callback - The funtion to call on the media change
+ * arg - A caller provided value to return with the callback
+ *
+ * Returned Value:
+ * 0 on success; negated errno on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SPI_CALLBACK
+#ifdef CONFIG_LPC17_SSP0
+int lpc17_ssp0register(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
+ FAR void *arg);
+#endif
+
+#ifdef CONFIG_LPC17_SSP1
+int lpc17_ssp1register(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
+ FAR void *arg);
+#endif
+#endif
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_LPC17_SSP0 || CONFIG_LPC17_SSP1 */
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_SSP_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_start.c b/nuttx/arch/arm/src/lpc17xx/lpc17_start.c
index abbe6e213..45e5b4551 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_start.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_start.c
@@ -50,7 +50,8 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_clockconfig.h"
+#include "lpc17_lowputc.h"
/****************************************************************************
* Private Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_timer.h b/nuttx/arch/arm/src/lpc17xx/lpc17_timer.h
index 207c6d5cc..d548fada5 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_timer.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_timer.h
@@ -1,250 +1,62 @@
-/************************************************************************************
- * arch/arm/src/lpc17xx/lpc17_timer.h
- *
- * Copyright (C) 2010, 2012 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_LPC17XX_LPC17_TIMER_H
-#define __ARCH_ARM_SRC_LPC17XX_LPC17_TIMER_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
-
-/************************************************************************************
- * Pre-processor Definitions
- ************************************************************************************/
-
-/* Register offsets *****************************************************************/
-
-#define LPC17_TMR_IR_OFFSET 0x0000 /* Interrupt Register */
-#define LPC17_TMR_TCR_OFFSET 0x0004 /* Timer Control Register */
-#define LPC17_TMR_TC_OFFSET 0x0008 /* Timer Counter */
-#define LPC17_TMR_PR_OFFSET 0x000c /* Prescale Register */
-#define LPC17_TMR_PC_OFFSET 0x0010 /* Prescale Counter */
-#define LPC17_TMR_MCR_OFFSET 0x0014 /* Match Control Register */
-#define LPC17_TMR_MR0_OFFSET 0x0018 /* Match Register 0 */
-#define LPC17_TMR_MR1_OFFSET 0x001c /* Match Register 1 */
-#define LPC17_TMR_MR2_OFFSET 0x0020 /* Match Register 2 */
-#define LPC17_TMR_MR3_OFFSET 0x0024 /* Match Register 3 */
-#define LPC17_TMR_CCR_OFFSET 0x0028 /* Capture Control Register */
-#define LPC17_TMR_CR0_OFFSET 0x002c /* Capture Register 0 */
-#define LPC17_TMR_CR1_OFFSET 0x0030 /* Capture Register 1 */
-#define LPC17_TMR_EMR_OFFSET 0x003c /* External Match Register */
-#define LPC17_TMR_CTCR_OFFSET 0x0070 /* Count Control Register */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_TMR0_IR (LPC17_TMR0_BASE+LPC17_TMR_IR_OFFSET)
-#define LPC17_TMR0_TCR (LPC17_TMR0_BASE+LPC17_TMR_TCR_OFFSET)
-#define LPC17_TMR0_TC (LPC17_TMR0_BASE+LPC17_TMR_TC_OFFSET)
-#define LPC17_TMR0_PR (LPC17_TMR0_BASE+LPC17_TMR_PR_OFFSET)
-#define LPC17_TMR0_PC (LPC17_TMR0_BASE+LPC17_TMR_PC_OFFSET)
-#define LPC17_TMR0_MCR (LPC17_TMR0_BASE+LPC17_TMR_MCR_OFFSET)
-#define LPC17_TMR0_MR0 (LPC17_TMR0_BASE+LPC17_TMR_MR0_OFFSET)
-#define LPC17_TMR0_MR1 (LPC17_TMR0_BASE+LPC17_TMR_MR1_OFFSET)
-#define LPC17_TMR0_MR2 (LPC17_TMR0_BASE+LPC17_TMR_MR2_OFFSET)
-#define LPC17_TMR0_MR3 (LPC17_TMR0_BASE+LPC17_TMR_MR3_OFFSET)
-#define LPC17_TMR0_CCR (LPC17_TMR0_BASE+LPC17_TMR_CCR_OFFSET)
-#define LPC17_TMR0_CR0 (LPC17_TMR0_BASE+LPC17_TMR_CR0_OFFSET)
-#define LPC17_TMR0_CR1 (LPC17_TMR0_BASE+LPC17_TMR_CR1_OFFSET)
-#define LPC17_TMR0_EMR (LPC17_TMR0_BASE+LPC17_TMR_EMR_OFFSET)
-#define LPC17_TMR0_CTCR (LPC17_TMR0_BASE+LPC17_TMR_CTCR_OFFSET)
-
-#define LPC17_TMR1_IR (LPC17_TMR1_BASE+LPC17_TMR_IR_OFFSET)
-#define LPC17_TMR1_TCR (LPC17_TMR1_BASE+LPC17_TMR_TCR_OFFSET)
-#define LPC17_TMR1_TC (LPC17_TMR1_BASE+LPC17_TMR_TC_OFFSET)
-#define LPC17_TMR1_PR (LPC17_TMR1_BASE+LPC17_TMR_PR_OFFSET)
-#define LPC17_TMR1_PC (LPC17_TMR1_BASE+LPC17_TMR_PC_OFFSET)
-#define LPC17_TMR1_MCR (LPC17_TMR1_BASE+LPC17_TMR_MCR_OFFSET)
-#define LPC17_TMR1_MR0 (LPC17_TMR1_BASE+LPC17_TMR_MR0_OFFSET)
-#define LPC17_TMR1_MR1 (LPC17_TMR1_BASE+LPC17_TMR_MR1_OFFSET)
-#define LPC17_TMR1_MR2 (LPC17_TMR1_BASE+LPC17_TMR_MR2_OFFSET)
-#define LPC17_TMR1_MR3 (LPC17_TMR1_BASE+LPC17_TMR_MR3_OFFSET)
-#define LPC17_TMR1_CCR (LPC17_TMR1_BASE+LPC17_TMR_CCR_OFFSET)
-#define LPC17_TMR1_CR0 (LPC17_TMR1_BASE+LPC17_TMR_CR0_OFFSET)
-#define LPC17_TMR1_CR1 (LPC17_TMR1_BASE+LPC17_TMR_CR1_OFFSET)
-#define LPC17_TMR1_EMR (LPC17_TMR1_BASE+LPC17_TMR_EMR_OFFSET)
-#define LPC17_TMR1_CTCR (LPC17_TMR1_BASE+LPC17_TMR_CTCR_OFFSET)
-
-#define LPC17_TMR2_IR (LPC17_TMR2_BASE+LPC17_TMR_IR_OFFSET)
-#define LPC17_TMR2_TCR (LPC17_TMR2_BASE+LPC17_TMR_TCR_OFFSET)
-#define LPC17_TMR2_TC (LPC17_TMR2_BASE+LPC17_TMR_TC_OFFSET)
-#define LPC17_TMR2_PR (LPC17_TMR2_BASE+LPC17_TMR_PR_OFFSET)
-#define LPC17_TMR2_PC (LPC17_TMR2_BASE+LPC17_TMR_PC_OFFSET)
-#define LPC17_TMR2_MCR (LPC17_TMR2_BASE+LPC17_TMR_MCR_OFFSET)
-#define LPC17_TMR2_MR0 (LPC17_TMR2_BASE+LPC17_TMR_MR0_OFFSET)
-#define LPC17_TMR2_MR1 (LPC17_TMR2_BASE+LPC17_TMR_MR1_OFFSET)
-#define LPC17_TMR2_MR2 (LPC17_TMR2_BASE+LPC17_TMR_MR2_OFFSET)
-#define LPC17_TMR2_MR3 (LPC17_TMR2_BASE+LPC17_TMR_MR3_OFFSET)
-#define LPC17_TMR2_CCR (LPC17_TMR2_BASE+LPC17_TMR_CCR_OFFSET)
-#define LPC17_TMR2_CR0 (LPC17_TMR2_BASE+LPC17_TMR_CR0_OFFSET)
-#define LPC17_TMR2_CR1 (LPC17_TMR2_BASE+LPC17_TMR_CR1_OFFSET)
-#define LPC17_TMR2_EMR (LPC17_TMR2_BASE+LPC17_TMR_EMR_OFFSET)
-#define LPC17_TMR2_CTCR (LPC17_TMR2_BASE+LPC17_TMR_CTCR_OFFSET)
-
-#define LPC17_TMR3_IR (LPC17_TMR3_BASE+LPC17_TMR_IR_OFFSET)
-#define LPC17_TMR3_TCR (LPC17_TMR3_BASE+LPC17_TMR_TCR_OFFSET)
-#define LPC17_TMR3_TC (LPC17_TMR3_BASE+LPC17_TMR_TC_OFFSET)
-#define LPC17_TMR3_PR (LPC17_TMR3_BASE+LPC17_TMR_PR_OFFSET)
-#define LPC17_TMR3_PC (LPC17_TMR3_BASE+LPC17_TMR_PC_OFFSET)
-#define LPC17_TMR3_MCR (LPC17_TMR3_BASE+LPC17_TMR_MCR_OFFSET)
-#define LPC17_TMR3_MR0 (LPC17_TMR3_BASE+LPC17_TMR_MR0_OFFSET)
-#define LPC17_TMR3_MR1 (LPC17_TMR3_BASE+LPC17_TMR_MR1_OFFSET)
-#define LPC17_TMR3_MR2 (LPC17_TMR3_BASE+LPC17_TMR_MR2_OFFSET)
-#define LPC17_TMR3_MR3 (LPC17_TMR3_BASE+LPC17_TMR_MR3_OFFSET)
-#define LPC17_TMR3_CCR (LPC17_TMR3_BASE+LPC17_TMR_CCR_OFFSET)
-#define LPC17_TMR3_CR0 (LPC17_TMR3_BASE+LPC17_TMR_CR0_OFFSET)
-#define LPC17_TMR3_CR1 (LPC17_TMR3_BASE+LPC17_TMR_CR1_OFFSET)
-#define LPC17_TMR3_EMR (LPC17_TMR3_BASE+LPC17_TMR_EMR_OFFSET)
-#define LPC17_TMR3_CTCR (LPC17_TMR3_BASE+LPC17_TMR_CTCR_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* Registers holding 32-bit numeric values (no bit field definitions):
- *
- * Timer Counter (TC)
- * Prescale Register (PR)
- * Prescale Counter (PC)
- * Match Register 0 (MR0)
- * Match Register 1 (MR1)
- * Match Register 2 (MR2)
- * Match Register 3 (MR3)
- * Capture Register 0 (CR0)
- * Capture Register 1 (CR1)
- */
-
-/* Interrupt Register */
-
-#define TMR_IR_MR0 (1 << 0) /* Bit 0: Match channel 0 interrupt */
-#define TMR_IR_MR1 (1 << 1) /* Bit 1: Match channel 1 interrupt */
-#define TMR_IR_MR2 (1 << 2) /* Bit 2: Match channel 2 interrupt */
-#define TMR_IR_MR3 (1 << 3) /* Bit 3: Match channel 3 interrupt */
-#define TMR_IR_CR0 (1 << 4) /* Bit 4: Capture channel 0 interrupt */
-#define TMR_IR_CR1 (1 << 5) /* Bit 5: Capture channel 1 interrupt */
- /* Bits 6-31: Reserved */
-/* Timer Control Register */
-
-#define TMR_TCR_EN (1 << 0) /* Bit 0: Counter Enable */
-#define TMR_TCR_RESET (1 << 1) /* Bit 1: Counter Reset */
- /* Bits 2-31: Reserved */
-/* Match Control Register */
-
-#define TMR_MCR_MR0I (1 << 0) /* Bit 0: Interrupt on MR0 */
-#define TMR_MCR_MR0R (1 << 1) /* Bit 1: Reset on MR0 */
-#define TMR_MCR_MR0S (1 << 2) /* Bit 2: Stop on MR0 */
-#define TMR_MCR_MR1I (1 << 3) /* Bit 3: Interrupt on MR1 */
-#define TMR_MCR_MR1R (1 << 4) /* Bit 4: Reset on MR1 */
-#define TMR_MCR_MR1S (1 << 5) /* Bit 5: Stop on MR1 */
-#define TMR_MCR_MR2I (1 << 6) /* Bit 6: Interrupt on MR2 */
-#define TMR_MCR_MR2R (1 << 7) /* Bit 7: Reset on MR2 */
-#define TMR_MCR_MR2S (1 << 8) /* Bit 8: Stop on MR2 */
-#define TMR_MCR_MR3I (1 << 9) /* Bit 9: Interrupt on MR3 */
-#define TMR_MCR_MR3R (1 << 10) /* Bit 10: Reset on MR3 */
-#define TMR_MCR_MR3S (1 << 11) /* Bit 11: Stop on MR3 */
- /* Bits 12-31: Reserved */
-/* Capture Control Register */
-
-#define TMR_CCR_CAP0RE (1 << 0) /* Bit 0: Capture on CAPn.0 rising edge */
-#define TMR_CCR_CAP0FE (1 << 1) /* Bit 1: Capture on CAPn.0 falling edge */
-#define TMR_CCR_CAP0I (1 << 2) /* Bit 2: Interrupt on CAPn.0 */
-#define TMR_CCR_CAP1RE (1 << 3) /* Bit 3: Capture on CAPn.1 rising edge */
-#define TMR_CCR_CAP1FE (1 << 4) /* Bit 4: Capture on CAPn.1 falling edge */
-#define TMR_CCR_CAP1I (1 << 5) /* Bit 5: Interrupt on CAPn.1 */
- /* Bits 6-31: Reserved */
-/* External Match Register */
-
-#define TMR_EMR_NOTHING (0) /* Do Nothing */
-#define TMR_EMR_CLEAR (1) /* Clear external match bit MATn.m */
-#define TMR_EMR_SET (2) /* Set external match bit MATn.m */
-#define TMR_EMR_TOGGLE (3) /* Toggle external match bit MATn.m */
-
-#define TMR_EMR_EM0 (1 << 0) /* Bit 0: External Match 0 */
-#define TMR_EMR_EM1 (1 << 1) /* Bit 1: External Match 1 */
-#define TMR_EMR_EM2 (1 << 2) /* Bit 2: External Match 2 */
-#define TMR_EMR_EM3 (1 << 3) /* Bit 3: External Match 3 */
-#define TMR_EMR_EMC0_SHIFT (4) /* Bits 4-5: External Match Control 0 */
-#define TMR_EMR_EMC0_MASK (3 << TMR_EMR_EMC0_SHIFTy)
-# define TMR_EMR_EMC0_NOTHING (TMR_EMR_NOTHING << TMR_EMR_EMC0_SHIFT)
-# define TMR_EMR_EMC0_CLEAR (TMR_EMR_CLEAR << TMR_EMR_EMC0_SHIFT)
-# define TMR_EMR_EMC0_SET (TMR_EMR_SET << TMR_EMR_EMC0_SHIFT)
-# define TMR_EMR_EMC0_TOGGLE (TMR_EMR_TOGGLE << TMR_EMR_EMC0_SHIFT)
-#define TMR_EMR_EMC1_SHIFT (6) /* Bits 6-7: External Match Control 1 */
-#define TMR_EMR_EMC1_MASK (3 << TMR_EMR_EMC1_SHIFT)
-# define TMR_EMR_EMC1_NOTHING (TMR_EMR_NOTHING << TMR_EMR_EMC1_SHIFT)
-# define TMR_EMR_EMC1_CLEAR (TMR_EMR_CLEAR << TMR_EMR_EMC1_SHIFT)
-# define TMR_EMR_EMC1_SET (TMR_EMR_SET << TMR_EMR_EMC1_SHIFT)
-# define TMR_EMR_EMC1_TOGGLE (TMR_EMR_TOGGLE << TMR_EMR_EMC1_SHIFT)
-#define TMR_EMR_EMC2_SHIFT (8) /* Bits 8-9: External Match Control 2 */
-#define TMR_EMR_EMC2_MASK (3 << TMR_EMR_EMC2_SHIFT)
-# define TMR_EMR_EMC2_NOTHING (TMR_EMR_NOTHING << TMR_EMR_EMC2_SHIFT)
-# define TMR_EMR_EMC2_CLEAR (TMR_EMR_CLEAR << TMR_EMR_EMC2_SHIFT)
-# define TMR_EMR_EMC2_SET (TMR_EMR_SET << TMR_EMR_EMC2_SHIFT)
-# define TMR_EMR_EMC2_TOGGLE (TMR_EMR_TOGGLE << TMR_EMR_EMC2_SHIFT)
-#define TMR_EMR_EMC3_SHIFT (10) /* Bits 10-11: External Match Control 3 */
-#define TMR_EMR_EMC3_MASK (3 << TMR_EMR_EMC3_SHIFT)
-# define TMR_EMR_EMC3_NOTHING (TMR_EMR_NOTHING << TMR_EMR_EMC3_SHIFT)
-# define TMR_EMR_EMC3_CLEAR (TMR_EMR_CLEAR << TMR_EMR_EMC3_SHIFT)
-# define TMR_EMR_EMC3_SET (TMR_EMR_SET << TMR_EMR_EMC3_SHIFT)
-# define TMR_EMR_EMC3_TOGGLE (TMR_EMR_TOGGLE << TMR_EMR_EMC3_SHIFT)
- /* Bits 12-31: Reserved */
-/* Count Control Register */
-
-#define TMR_CTCR_MODE_SHIFT (0) /* Bits 0-1: Counter/Timer Mode */
-#define TMR_CTCR_MODE_MASK (3 << TMR_CTCR_MODE_SHIFT)
-# define TMR_CTCR_MODE_TIMER (0 << TMR_CTCR_MODE_SHIFT) /* Timer Mode, prescale match */
-# define TMR_CTCR_MODE_CNTRRE (1 << TMR_CTCR_MODE_SHIFT) /* Counter Mode, CAP rising edge */
-# define TMR_CTCR_MODE_CNTRFE (2 << TMR_CTCR_MODE_SHIFT) /* Counter Mode, CAP falling edge */
-# define TMR_CTCR_MODE_CNTRBE (3 << TMR_CTCR_MODE_SHIFT) /* Counter Mode, CAP both edges */
-#define TMR_CTCR_INPSEL_SHIFT (2) /* Bits 2-3: Count Input Select */
-#define TMR_CTCR_INPSEL_MASK (3 << TMR_CTCR_INPSEL_SHIFT)
-# define TMR_CTCR_INPSEL_CAPNp0 (0 << TMR_CTCR_INPSEL_SHIFT) /* CAPn.0 for TIMERn */
-# define TMR_CTCR_INPSEL_CAPNp1 (1 << TMR_CTCR_INPSEL_SHIFT) /* CAPn.1 for TIMERn */
- /* Bits 4-31: Reserved */
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
- * Public Data
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_TIMER_H */
+/************************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_timer.h
+ *
+ * Copyright (C) 2010, 2012-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_LPC17XX_LPC17_TIMER_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_TIMER_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/lpc17_timer.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_TIMER_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_timerisr.c b/nuttx/arch/arm/src/lpc17xx/lpc17_timerisr.c
index 918c153a4..ffe975e92 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_timerisr.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_timerisr.c
@@ -52,7 +52,7 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
+
/****************************************************************************
* Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c
index a5cb443e4..b1ddb5928 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c
@@ -55,13 +55,14 @@
#include <arch/irq.h>
#include <arch/board/board.h>
-#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
-#include "lpc17_usb.h"
-#include "lpc17_syscon.h"
+#include "chip.h"
+#include "chip/lpc17_usb.h"
+#include "chip/lpc17_syscon.h"
+#include "lpc17_gpio.h"
+#include "lpc17_gpdma.h"
/*******************************************************************************
* Definitions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
index de880cac1..b0e9958e9 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbhost.c
@@ -56,15 +56,15 @@
#include <arch/irq.h>
-#include "lpc17_internal.h" /* Includes default GPIO settings */
#include <arch/board/board.h> /* May redefine GPIO settings */
-#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_usb.h"
-#include "lpc17_syscon.h"
+#include "chip.h"
+#include "chip/lpc17_usb.h"
+#include "chip/lpc17_syscon.h"
+#include "lpc17_gpio.h"
#include "lpc17_ohciram.h"
/*******************************************************************************
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_wdt.h b/nuttx/arch/arm/src/lpc17xx/lpc17_wdt.h
index bd7790a6e..b9ef49fc3 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_wdt.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_wdt.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_wdt.h
*
- * 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
@@ -41,58 +41,12 @@
************************************************************************************/
#include <nuttx/config.h>
-
-#include "chip.h"
-#include "lpc17_memorymap.h"
+#include "chip/lpc17_wdt.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-
-#define LPC17_WDT_WDMOD_OFFSET 0x0000 /* Watchdog mode register */
-#define LPC17_WDT_WDTC_OFFSET 0x0004 /* Watchdog timer constant register */
-#define LPC17_WDT_WDFEED_OFFSET 0x0008 /* Watchdog feed sequence register */
-#define LPC17_WDT_WDTV_OFFSET 0x000c /* Watchdog timer value register */
-#define LPC17_WDT_WDCLKSEL_OFFSET 0x0010 /* Watchdog clock source selection register */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_WDT_WDMOD (LPC17_WDT_BASE+LPC17_WDT_WDMOD_OFFSET)
-#define LPC17_WDT_WDTC (LPC17_WDT_BASE+LPC17_WDT_WDTC_OFFSET)
-#define LPC17_WDT_WDFEED (LPC17_WDT_BASE+LPC17_WDT_WDFEED_OFFSET)
-#define LPC17_WDT_WDTV (LPC17_WDT_BASE+LPC17_WDT_WDTV_OFFSET)
-#define LPC17_WDT_WDCLKSEL (LPC17_WDT_BASE+LPC17_WDT_WDCLKSEL_OFFSET)
-
-/* Register bit definitions *********************************************************/
-
-/* Watchdog mode register */
-
-#define WDT_WDMOD_WDEN (1 << 0) /* Bit 0: Watchdog enable */
-#define WDT_WDMOD_WDRESET (1 << 1) /* Bit 1: Watchdog reset enable */
-#define WDT_WDMOD_WDTOF (1 << 2) /* Bit 2: Watchdog time-out */
-#define WDT_WDMOD_WDINT (1 << 3) /* Bit 3: Watchdog interrupt */
- /* Bits 14-31: Reserved */
-
-/* Watchdog timer constant register (Bits 0-31: Watchdog time-out interval) */
-
-/* Watchdog feed sequence register */
-
-#define WDT_WDFEED_MASK (0xff) /* Bits 0-7: Feed value should be 0xaa followed by 0x55 */
- /* Bits 14-31: Reserved */
-/* Watchdog timer value register (Bits 0-31: Counter timer value) */
-
-/* Watchdog clock source selection register */
-
-#define WDT_WDCLKSEL_WDSEL_SHIFT (0) /* Bits 0-1: Clock source for the Watchdog timer */
-#define WDT_WDCLKSEL_WDSEL_MASK (3 << WDT_WDCLKSEL_WDSEL_SHIFT)
-# define WDT_WDCLKSEL_WDSEL_INTRC (0 << WDT_WDCLKSEL_WDSEL_SHIFT) /* Internal RC osc */
-# define WDT_WDCLKSEL_WDSEL_APB (1 << WDT_WDCLKSEL_WDSEL_SHIFT) /* APB peripheral clock (watchdog pclk) */
-# define WDT_WDCLKSEL_WDSEL_RTC (2 << WDT_WDCLKSEL_WDSEL_SHIFT) /* RTC oscillator (rtc_clk) */
- /* Bits 2-30: Reserved */
-#define WDT_WDCLKSEL_WDLOCK (1 << 31) /* Bit 31: Lock WDT register bits if set */
-
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/configs/lincoln60/src/up_boot.c b/nuttx/configs/lincoln60/src/up_boot.c
index 42b01a3ea..6e67f777b 100644
--- a/nuttx/configs/lincoln60/src/up_boot.c
+++ b/nuttx/configs/lincoln60/src/up_boot.c
@@ -47,7 +47,6 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
#include "lincoln60_internal.h"
/************************************************************************************
diff --git a/nuttx/configs/lincoln60/src/up_buttons.c b/nuttx/configs/lincoln60/src/up_buttons.c
index 55781846d..76cb1f2d9 100644
--- a/nuttx/configs/lincoln60/src/up_buttons.c
+++ b/nuttx/configs/lincoln60/src/up_buttons.c
@@ -1,7 +1,7 @@
/****************************************************************************
* configs/lincoln60/src/up_buttons.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,7 +47,7 @@
#include <arch/board/board.h>
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "lincoln60_internal.h"
#ifdef CONFIG_ARCH_BUTTONS
diff --git a/nuttx/configs/lincoln60/src/up_leds.c b/nuttx/configs/lincoln60/src/up_leds.c
index fe00895b1..3b8692d93 100644
--- a/nuttx/configs/lincoln60/src/up_leds.c
+++ b/nuttx/configs/lincoln60/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/lincoln60/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -50,7 +50,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "lincoln60_internal.h"
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h b/nuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h
index 41ec1ce11..3e7dfa4e5 100644
--- a/nuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/lpcxpresso_internal.h
@@ -141,8 +141,8 @@
* SD Signal Pin Pin
* --- ----------- ----- --------
* CS PIO1_11* 55 P2.2 (See LPCXPRESSO_SD_CS)
- * DIN PIO0_9-MOSI 5 P0.9 MOSI1 (See GPIO_SSP1_MOSI in lpc17_internal.h)
- * DOUT PIO0_8-MISO 6 P0.8 MISO1 (See GPIO_SSP1_MISO in lpc17_internal.h)
+ * DIN PIO0_9-MOSI 5 P0.9 MOSI1 (See GPIO_SSP1_MOSI in chip/lpc17_ssp.h)
+ * DOUT PIO0_8-MISO 6 P0.8 MISO1 (See GPIO_SSP1_MISO in chip/lpc17_ssp.h)
* CLK PIO2_11-SCK 7 P0.9 SCK1 (See GPIO_SSP1_SCK in board.h)
* CD PIO2_10 52 P2.11 (See LPCXPRESSO_SD_CD)
*/
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_boot.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_boot.c
index f672c4517..9766569a9 100644
--- a/nuttx/configs/lpcxpresso-lpc1768/src/up_boot.c
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_boot.c
@@ -47,7 +47,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_ssp.h"
#include "lpcxpresso_internal.h"
/************************************************************************************
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c
index cebf3a143..85539b378 100644
--- a/nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/lpcxpresso-lpc1768/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -46,7 +46,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "lpcxpresso_internal.h"
#ifdef CONFIG_ARCH_LEDS
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c
index f3ecde909..c22b09ceb 100644
--- a/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_oled.c
@@ -2,7 +2,7 @@
* config/lpcxpresso-lpc1768/src/up_oled.c
* arch/arm/src/board/up_oled.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -48,7 +48,8 @@
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/ug-9664hswag01.h>
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
+#include "lpc17_ssp.h"
#include "lpcxpresso_internal.h"
/****************************************************************************
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c
index 7b5f02e31..3504d78c7 100644
--- a/nuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_ssp.c
@@ -2,7 +2,7 @@
* configs/lpcxpresso-lpc1768/src/up_ssp.c
* arch/arm/src/board/up_ssp.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,7 +49,8 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
+#include "lpc17_ssp.h"
#include "lpcxpresso_internal.h"
#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
@@ -155,11 +156,11 @@ void weak_function lpc17_sspinitialize(void)
void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
- ssp_dumpgpio("lpc17_spi0select() Entry");
+ ssp_dumpgpio("lpc17_ssp0select() Entry");
#warning "Assert CS here (false)"
- ssp_dumpgpio("lpc17_spi0select() Exit");
+ ssp_dumpgpio("lpc17_ssp0select() Exit");
}
uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
@@ -173,7 +174,7 @@ uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
- ssp_dumpgpio("lpc17_spi1select() Entry");
+ ssp_dumpgpio("lpc17_ssp1select() Entry");
if (devid == SPIDEV_MMCSD)
{
@@ -189,7 +190,7 @@ void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel
(void)lpc17_gpiowrite(LPCXPRESSO_OLED_CS, !selected);
}
#endif
- ssp_dumpgpio("lpc17_spi1select() Exit");
+ ssp_dumpgpio("lpc17_ssp1select() Exit");
}
uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
diff --git a/nuttx/configs/mbed/src/up_boot.c b/nuttx/configs/mbed/src/up_boot.c
index 42dd54bf5..489c0a58c 100644
--- a/nuttx/configs/mbed/src/up_boot.c
+++ b/nuttx/configs/mbed/src/up_boot.c
@@ -47,7 +47,6 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
#include "mbed_internal.h"
/************************************************************************************
@@ -80,3 +79,4 @@ void lpc17_boardinitialize(void)
up_ledinit();
#endif
}
+
diff --git a/nuttx/configs/mbed/src/up_leds.c b/nuttx/configs/mbed/src/up_leds.c
index bc8a87045..c8c78e3ad 100644
--- a/nuttx/configs/mbed/src/up_leds.c
+++ b/nuttx/configs/mbed/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/mbed/src/up_leds.c
* arch/arm/src/board/up_leds.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
@@ -50,7 +50,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "mbed_internal.h"
diff --git a/nuttx/configs/nucleus2g/src/up_boot.c b/nuttx/configs/nucleus2g/src/up_boot.c
index d4c44a455..4718e9f82 100644
--- a/nuttx/configs/nucleus2g/src/up_boot.c
+++ b/nuttx/configs/nucleus2g/src/up_boot.c
@@ -47,7 +47,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_ssp.h"
#include "nucleus2g_internal.h"
/************************************************************************************
diff --git a/nuttx/configs/nucleus2g/src/up_leds.c b/nuttx/configs/nucleus2g/src/up_leds.c
index 41f955af4..e1c39f515 100644
--- a/nuttx/configs/nucleus2g/src/up_leds.c
+++ b/nuttx/configs/nucleus2g/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/nucleus2g/src/up_leds.c
* arch/arm/src/board/up_leds.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
@@ -50,7 +50,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "nucleus2g_internal.h"
diff --git a/nuttx/configs/nucleus2g/src/up_outputs.c b/nuttx/configs/nucleus2g/src/up_outputs.c
index 749f331eb..beb979ae0 100644
--- a/nuttx/configs/nucleus2g/src/up_outputs.c
+++ b/nuttx/configs/nucleus2g/src/up_outputs.c
@@ -7,7 +7,7 @@
*
* This file is part of NuttX:
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -54,7 +54,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "nucleus2g_internal.h"
diff --git a/nuttx/configs/nucleus2g/src/up_ssp.c b/nuttx/configs/nucleus2g/src/up_ssp.c
index 13a768130..77c07f3eb 100644
--- a/nuttx/configs/nucleus2g/src/up_ssp.c
+++ b/nuttx/configs/nucleus2g/src/up_ssp.c
@@ -2,7 +2,7 @@
* configs/nucleus2g/src/up_ssp.c
* arch/arm/src/board/up_ssp.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
@@ -49,7 +49,8 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
+#include "lpc17_ssp.h"
#include "nucleus2g_internal.h"
#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
@@ -158,7 +159,7 @@ void weak_function lpc17_sspinitialize(void)
void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
- ssp_dumpgpio("lpc17_spiselect() Entry");
+ ssp_dumpgpio("lpc17_ssp0select() Entry");
if (devid == SPIDEV_MMCSD)
{
@@ -166,7 +167,7 @@ void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel
lpc17_gpiowrite(NUCLEUS2G_MMCSD_CS, !selected);
}
- ssp_dumpgpio("lpc17_spiselect() Exit");
+ ssp_dumpgpio("lpc17_ssp0select() Exit");
}
uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_boot.c b/nuttx/configs/olimex-lpc1766stk/src/up_boot.c
index 9d4c3ad3b..9f4200004 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_boot.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_boot.c
@@ -47,7 +47,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_ssp.h"
#include "lpc1766stk_internal.h"
/************************************************************************************
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_buttons.c b/nuttx/configs/olimex-lpc1766stk/src/up_buttons.c
index bcafc7337..6d47d2890 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_buttons.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_buttons.c
@@ -47,7 +47,7 @@
#include <arch/board/board.h>
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "lpc1766stk_internal.h"
#ifdef CONFIG_ARCH_BUTTONS
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_can.c b/nuttx/configs/olimex-lpc1766stk/src/up_can.c
index f947c827e..51d8423e3 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_can.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_can.c
@@ -49,7 +49,6 @@
#include "chip.h"
#include "up_arch.h"
-#include "lpc17_internal.h"
#include "lpc17_can.h"
#include "lpc1766stk_internal.h"
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c b/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c
index 93923b91a..4e4c94856 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_lcd.c
@@ -52,7 +52,7 @@
#include "up_arch.h"
#include "lpc17_syscon.h"
#include "lpc17_pwm.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "lpc1766stk_internal.h"
#if defined(CONFIG_NX_LCDDRIVER) && defined(CONFIG_LCD_NOKIA6100) && defined(CONFIG_LPC17_SSP0)
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_leds.c b/nuttx/configs/olimex-lpc1766stk/src/up_leds.c
index 75c6a8ce0..e590be39f 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_leds.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_leds.c
@@ -50,7 +50,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "lpc1766stk_internal.h"
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
index 036350ded..99e9c4d9c 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
@@ -2,7 +2,7 @@
* config/olimex-lpc1766stk/src/up_nsh.c
* arch/arm/src/board/up_nsh.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
@@ -49,7 +49,7 @@
#include <nuttx/mmcsd.h>
#include <nuttx/usb/usbhost.h>
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "lpc1766stk_internal.h"
/****************************************************************************
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_ssp.c b/nuttx/configs/olimex-lpc1766stk/src/up_ssp.c
index 272a17065..2c6c613c7 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_ssp.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_ssp.c
@@ -53,7 +53,8 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
+#include "lpc17_ssp.h"
#include "lpc1766stk_internal.h"
#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c b/nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c
index 08c5fb887..ce7c75771 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_usbmsc.c
@@ -48,7 +48,7 @@
#include <nuttx/spi.h>
#include <nuttx/mmcsd.h>
-#include "lpc17_internal.h"
+#include "lpc17_gpio.h"
#include "lpc1766stk_internal.h"
/****************************************************************************