summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-18 20:25:32 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-18 20:25:32 +0000
commit773fedfda3778f9dd224f035a46bd378435e82e4 (patch)
tree71da4b24ed3db7272a46d8e89d2c9fab29894f0c /nuttx
parent8606eb53ff4105795a9feb7c42a677b8b26042ef (diff)
downloadpx4-nuttx-773fedfda3778f9dd224f035a46bd378435e82e4.tar.gz
px4-nuttx-773fedfda3778f9dd224f035a46bd378435e82e4.tar.bz2
px4-nuttx-773fedfda3778f9dd224f035a46bd378435e82e4.zip
More LPC1788 register definitions from Rommel Marcelo
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5535 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc176x_syscon.h494
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h90
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h589
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h598
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpio.h115
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_syscon.h441
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c16
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h233
8 files changed, 2036 insertions, 540 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_syscon.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_syscon.h
new file mode 100644
index 000000000..ddacc05b5
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc176x_syscon.h
@@ -0,0 +1,494 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc176x_syscon.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_LPC176X_SYSCON_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC176X_SYSCON_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register offsets *****************************************************************/
+/* Flash accelerator module */
+
+#define LPC17_SYSCON_FLASHCFG_OFFSET 0x0000 /* Flash Accelerator Configuration Register */
+
+/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
+
+#define LPC17_SYSCON_MEMMAP_OFFSET 0x0040 /* Memory Mapping Control register */
+
+/* Clocking and power control - Phase locked loops */
+
+#define LPC17_SYSCON_PLL0CON_OFFSET 0x0080 /* PLL0 Control Register */
+#define LPC17_SYSCON_PLL0CFG_OFFSET 0x0084 /* PLL0 Configuration Register */
+#define LPC17_SYSCON_PLL0STAT_OFFSET 0x0088 /* PLL0 Status Register */
+#define LPC17_SYSCON_PLL0FEED_OFFSET 0x008c /* PLL0 Feed Register */
+
+#define LPC17_SYSCON_PLL1CON_OFFSET 0x00a0 /* PLL1 Control Register */
+#define LPC17_SYSCON_PLL1CFG_OFFSET 0x00a4 /* PLL1 Configuration Register */
+#define LPC17_SYSCON_PLL1STAT_OFFSET 0x00a8 /* PLL1 Status Register */
+#define LPC17_SYSCON_PLL1FEED_OFFSET 0x00ac /* PLL1 Feed Register */
+
+/* Clocking and power control - Peripheral power control registers */
+
+#define LPC17_SYSCON_PCON_OFFSET 0x00c0 /* Power Control Register */
+#define LPC17_SYSCON_PCONP_OFFSET 0x00c4 /* Power Control for Peripherals Register */
+
+/* Clocking and power control -- Clock dividers */
+
+#define LPC17_SYSCON_CCLKCFG_OFFSET 0x0104 /* CPU Clock Configuration Register */
+#define LPC17_SYSCON_USBCLKCFG_OFFSET 0x0108 /* USB Clock Configuration Register */
+
+/* 0x400f c110 - 0x400f c114: CAN Wake and Sleep Registers */
+
+/* Clocking and power control -- Clock source selection */
+
+#define LPC17_SYSCON_CLKSRCSEL_OFFSET 0x010c /* Clock Source Select Register */
+
+/* System control registers -- External Interrupts */
+
+#define LPC17_SYSCON_EXTINT_OFFSET 0x0140 /* External Interrupt Flag Register */
+
+#define LPC17_SYSCON_EXTMODE_OFFSET 0x0148 /* External Interrupt Mode register */
+#define LPC17_SYSCON_EXTPOLAR_OFFSET 0x014c /* External Interrupt Polarity Register */
+
+/* System control registers -- Reset */
+
+#define LPC17_SYSCON_RSID_OFFSET 0x0180 /* Reset Source Identification Register */
+
+/* System control registers -- Syscon Miscellaneous Registers */
+
+#define LPC17_SYSCON_SCS_OFFSET 0x01a0 /* System Control and Status */
+
+/* More clocking and power control -- Clock dividers */
+
+#define LPC17_SYSCON_PCLKSEL0_OFFSET 0x01a8 /* Peripheral Clock Selection register 0 */
+#define LPC17_SYSCON_PCLKSEL1_OFFSET 0x01ac /* Peripheral Clock Selection register 1 */
+
+/* Device Interrupt Registers (Might be a error in the User Manual, might be at 0x5000c1c0) */
+
+#define LPC17_SYSCON_USBINTST_OFFSET 0x01c0 /* USB Interrupt Status */
+
+/* DMA Request Select Register */
+
+#define LPC17_SYSCON_DMAREQSEL_OFFSET 0x01c4 /* Selects between UART and timer DMA requests */
+
+/* More clocking and power control -- Utility */
+
+#define LPC17_SYSCON_CLKOUTCFG_OFFSET 0x01c8 /* Clock Output Configuration Register */
+
+/* Register addresses ***************************************************************/
+/* Flash accelerator module */
+
+#define LPC17_SYSCON_FLASHCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_FLASHCFG_OFFSET)
+
+/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
+
+#define LPC17_SYSCON_MEMMAP (LPC17_SYSCON_BASE+LPC17_SYSCON_MEMMAP_OFFSET)
+
+/* Clocking and power control - Phase locked loops */
+
+#define LPC17_SYSCON_PLL0CON (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0CON_OFFSET)
+#define LPC17_SYSCON_PLL0CFG (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0CFG_OFFSET)
+#define LPC17_SYSCON_PLL0STAT (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0STAT_OFFSET)
+#define LPC17_SYSCON_PLL0FEED (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0FEED_OFFSET)
+
+#define LPC17_SYSCON_PLL1CON (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1CON_OFFSET)
+#define LPC17_SYSCON_PLL1CFG (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1CFG_OFFSET)
+#define LPC17_SYSCON_PLL1STAT (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1STAT_OFFSET)
+#define LPC17_SYSCON_PLL1FEED (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1FEED_OFFSET)
+
+/* Clocking and power control - Peripheral power control registers */
+
+#define LPC17_SYSCON_PCON (LPC17_SYSCON_BASE+LPC17_SYSCON_PCON_OFFSET)
+#define LPC17_SYSCON_PCONP (LPC17_SYSCON_BASE+LPC17_SYSCON_PCONP_OFFSET)
+
+/* Clocking and power control -- Clock dividers */
+
+#define LPC17_SYSCON_CCLKCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_CCLKCFG_OFFSET)
+#define LPC17_SYSCON_USBCLKCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_USBCLKCFG_OFFSET)
+
+/* 0x400f c110 - 0x400f c114: CAN Wake and Sleep Registers */
+
+/* Clocking and power control -- Clock source selection */
+
+#define LPC17_SYSCON_CLKSRCSEL (LPC17_SYSCON_BASE+LPC17_SYSCON_CLKSRCSEL_OFFSET)
+
+/* System control registers -- External Interrupts */
+
+#define LPC17_SYSCON_EXTINT (LPC17_SYSCON_BASE+LPC17_SYSCON_EXTINT_OFFSET)
+
+#define LPC17_SYSCON_EXTMODE (LPC17_SYSCON_BASE+LPC17_SYSCON_EXTMODE_OFFSET)
+#define LPC17_SYSCON_EXTPOLAR (LPC17_SYSCON_BASE+LPC17_SYSCON_EXTPOLAR_OFFSET)
+
+/* System control registers -- Reset */
+
+#define LPC17_SYSCON_RSID (LPC17_SYSCON_BASE+LPC17_SYSCON_RSID_OFFSET)
+
+/* System control registers -- Syscon Miscellaneous Registers */
+
+#define LPC17_SYSCON_SCS (LPC17_SYSCON_BASE+LPC17_SYSCON_SCS_OFFSET)
+
+/* More clocking and power control -- Clock dividers */
+
+#define LPC17_SYSCON_PCLKSEL0 (LPC17_SYSCON_BASE+LPC17_SYSCON_PCLKSEL0_OFFSET)
+#define LPC17_SYSCON_PCLKSEL1 (LPC17_SYSCON_BASE+LPC17_SYSCON_PCLKSEL1_OFFSET)
+
+/* Device Interrupt Registers (Might be a error in the User Manual, might be at 0x5000c1c0) */
+
+#define LPC17_SYSCON_USBINTST (LPC17_SYSCON_BASE+LPC17_SYSCON_USBINTST_OFFSET)
+
+/* DMA Request Select Register */
+
+#define LPC17_SYSCON_DMAREQSEL (LPC17_SYSCON_BASE+LPC17_SYSCON_DMAREQSEL_OFFSET)
+
+/* More clocking and power control -- Utility */
+
+#define LPC17_SYSCON_CLKOUTCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_CLKOUTCFG_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* Flash accelerator module */
+ /* Bits 0-11: Reserved */
+#define SYSCON_FLASHCFG_TIM_SHIFT (12) /* Bits 12-15: FLASHTIM Flash access time */
+#define SYSCON_FLASHCFG_TIM_MASK (15 << SYSCON_FLASHCFG_TIM_SHIFT)
+# define SYSCON_FLASHCFG_TIM_1 (0 << SYSCON_FLASHCFG_TIM_SHIFT) /* 1 CPU clock <= 20 MHz CPU clock */
+# define SYSCON_FLASHCFG_TIM_2 (1 << SYSCON_FLASHCFG_TIM_SHIFT) /* 2 CPU clock <= 40 MHz CPU clock */
+# define SYSCON_FLASHCFG_TIM_3 (2 << SYSCON_FLASHCFG_TIM_SHIFT) /* 3 CPU clock <= 60 MHz CPU clock */
+# define SYSCON_FLASHCFG_TIM_4 (3 << SYSCON_FLASHCFG_TIM_SHIFT) /* 4 CPU clock <= 80 MHz CPU clock */
+# define SYSCON_FLASHCFG_TIM_5 (4 << SYSCON_FLASHCFG_TIM_SHIFT) /* 5 CPU clock <= 100 MHz CPU clock
+ * (Up to 120 Mhz for LPC1759/69 only */
+# define SYSCON_FLASHCFG_TIM_6 (5 << SYSCON_FLASHCFG_TIM_SHIFT) /* "safe" setting for any conditions */
+ /* Bits 16-31: Reserved */
+
+/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
+
+#define SYSCON_MEMMAP_MAP (1 << 0) /* Bit 0:
+ * 0:Boot mode. A portion of the Boot ROM is mapped to address 0.
+ * 1:User mode. The on-chip Flash memory is mapped to address 0 */
+ /* Bits 1-31: Reserved */
+
+/* Clocking and power control -- Clock source selection */
+
+#define SYSCON_CLKSRCSEL_SHIFT (0) /* Bits 0-1: Clock selection */
+#define SYSCON_CLKSRCSEL_MASK (3 << SYSCON_CLKSRCSEL_SHIFT)
+# define SYSCON_CLKSRCSEL_INTRC (0 << SYSCON_CLKSRCSEL_SHIFT) /* PLL0 source = internal RC oscillator */
+# define SYSCON_CLKSRCSEL_MAIN (1 << SYSCON_CLKSRCSEL_SHIFT) /* PLL0 source = main oscillator */
+# define SYSCON_CLKSRCSEL_RTC (2 << SYSCON_CLKSRCSEL_SHIFT) /* PLL0 source = RTC oscillator */
+ /* Bits 2-31: Reserved */
+
+/* Clocking and power control - Phase locked loops */
+/* PLL0/1 Control register */
+
+#define SYSCON_PLLCON_PLLE (1 << 0) /* Bit 0: PLL0/1 Enable */
+#define SYSCON_PLLCON_PLLC (1 << 1) /* Bit 1: PLL0/1 Connect */
+ /* Bits 2-31: Reserved */
+/* PLL0 Configuration register */
+
+#define SYSCON_PLL0CFG_MSEL_SHIFT (0) /* Bit 0-14: PLL0 Multiplier value */
+#define SYSCON_PLL0CFG_MSEL_MASK (0x7fff << SYSCON_PLL0CFG_MSEL_SHIFT)
+ /* Bit 15: Reserved */
+#define SYSCON_PLL0CFG_NSEL_SHIFT (16) /* Bit 16-23: PLL0 Pre-Divider value */
+#define SYSCON_PLL0CFG_NSEL_MASK (0xff << SYSCON_PLL0CFG_NSEL_SHIFT)
+ /* Bits 24-31: Reserved */
+/* PLL1 Configuration register */
+
+#define SYSCON_PLL1CFG_MSEL_SHIFT (0) /* Bit 0-4: PLL1 Multiplier value */
+#define SYSCON_PLL1CFG_MSEL_MASK (0x1f < SYSCON_PLL1CFG_MSEL_SHIFT)
+#define SYSCON_PLL1CFG_NSEL_SHIFT (5) /* Bit 5-6: PLL1 Pre-Divider value */
+#define SYSCON_PLL1CFG_NSEL_MASK (3 << SYSCON_PLL1CFG_NSEL_SHIFT)
+ /* Bits 7-31: Reserved */
+/* PLL0 Status register */
+
+#define SYSCON_PLL0STAT_MSEL_SHIFT (0) /* Bit 0-14: PLL0 Multiplier value readback */
+#define SYSCON_PLL0STAT_MSEL_MASK (0x7fff << SYSCON_PLL0STAT_MSEL_SHIFT)
+ /* Bit 15: Reserved */
+#define SYSCON_PLL0STAT_NSEL_SHIFT (16) /* Bit 16-23: PLL0 Pre-Divider value readback */
+#define SYSCON_PLL0STAT_NSEL_MASK (0xff << SYSCON_PLL0STAT_NSEL_SHIFT)
+#define SYSCON_PLL0STAT_PLLE (1 << 24) /* Bit 24: PLL0 enable readback */
+#define SYSCON_PLL0STAT_PLLC (1 << 25) /* Bit 25: PLL0 connect readback */
+#define SYSCON_PLL0STAT_PLOCK (1 << 26) /* Bit 26: PLL0 lock status */
+ /* Bits 27-31: Reserved */
+/* PLL1 Status register */
+
+#define SYSCON_PLL1STAT_MSEL_SHIFT (0) /* Bit 0-4: PLL1 Multiplier value readback */
+#define SYSCON_PLL1STAT_MSEL_MASK (0x1f << SYSCON_PLL1STAT_MSEL_SHIFT)
+#define SYSCON_PLL1STAT_NSEL_SHIFT (5) /* Bit 5-6: PLL1 Pre-Divider value readback */
+#define SYSCON_PLL1STAT_NSEL_MASK (3 << SYSCON_PLL1STAT_NSEL_SHIFT)
+ /* Bit 7: Reserved */
+#define SYSCON_PLL1STAT_PLLE (1 << 8) /* Bit 8: PLL1 enable readback */
+#define SYSCON_PLL1STAT_PLLC (1 << 9) /* Bit 9: PLL1 connect readback */
+#define SYSCON_PLL1STAT_PLOCK (1 << 10) /* Bit 10: PLL1 lock status */
+ /* Bits 11-31: Reserved */
+/* PLL0/1 Feed register */
+
+#define SYSCON_PLLFEED_SHIFT (0) /* Bit 0-7: PLL0/1 feed sequence */
+#define SYSCON_PLLFEED_MASK (0xff << SYSCON_PLLFEED_SHIFT)
+ /* Bits 8-31: Reserved */
+/* Clocking and power control -- Clock dividers */
+/* CPU Clock Configuration register */
+
+#define SYSCON_CCLKCFG_SHIFT (0) /* 0-7: Divide value for CPU clock (CCLK) */
+#define SYSCON_CCLKCFG_MASK (0xff << SYSCON_CCLKCFG_SHIFT)
+# define SYSCON_CCLKCFG_DIV(n) ((n-1) << SYSCON_CCLKCFG_SHIFT) /* n=2,3,..255 */
+ /* Bits 8-31: Reserved */
+/* USB Clock Configuration register */
+
+#define SYSCON_USBCLKCFG_SHIFT (0) /* Bits 0-3: PLL0 divide value USB clock */
+#define SYSCON_USBCLKCFG_MASK (15 << SYSCON_USBCLKCFG_SHIFT)
+# define SYSCON_USBCLKCFG_DIV6 (5 << SYSCON_USBCLKCFG_SHIFT) /* PLL0/6 for PLL0=288 MHz */
+# define SYSCON_USBCLKCFG_DIV8 (7 << SYSCON_USBCLKCFG_SHIFT) /* PLL0/8 for PLL0=384 MHz */
+# define SYSCON_USBCLKCFG_DIV10 (9 << SYSCON_USBCLKCFG_SHIFT) /* PLL0/10 for PLL0=480 MHz */
+ /* Bits 8-31: Reserved */
+/* Peripheral Clock Selection registers 0 and 1 */
+
+#define SYSCON_PCLKSEL_CCLK4 (0) /* PCLK_peripheral = CCLK/4 */
+#define SYSCON_PCLKSEL_CCLK (1) /* PCLK_peripheral = CCLK */
+#define SYSCON_PCLKSEL_CCLK2 (2) /* PCLK_peripheral = CCLK/2 */
+#define SYSCON_PCLKSEL_CCLK8 (3) /* PCLK_peripheral = CCLK/8 (except CAN1, CAN2, and CAN) */
+#define SYSCON_PCLKSEL_CCLK6 (3) /* PCLK_peripheral = CCLK/6 (CAN1, CAN2, and CAN) */
+#define SYSCON_PCLKSEL_MASK (3)
+
+#define SYSCON_PCLKSEL0_WDT_SHIFT (0) /* Bits 0-1: Peripheral clock WDT */
+#define SYSCON_PCLKSEL0_WDT_MASK (3 << SYSCON_PCLKSEL0_WDT_SHIFT)
+#define SYSCON_PCLKSEL0_TMR0_SHIFT (2) /* Bits 2-3: Peripheral clock TIMER0 */
+#define SYSCON_PCLKSEL0_TMR0_MASK (3 << SYSCON_PCLKSEL0_TMR0_SHIFT)
+#define SYSCON_PCLKSEL0_TMR1_SHIFT (4) /* Bits 4-5: Peripheral clock TIMER1 */
+#define SYSCON_PCLKSEL0_TMR1_MASK (3 << SYSCON_PCLKSEL0_TMR1_SHIFT)
+#define SYSCON_PCLKSEL0_UART0_SHIFT (6) /* Bits 6-7: Peripheral clock UART0 */
+#define SYSCON_PCLKSEL0_UART0_MASK (3 << SYSCON_PCLKSEL0_UART0_SHIFT)
+#define SYSCON_PCLKSEL0_UART1_SHIFT (8) /* Bits 8-9: Peripheral clock UART1 */
+#define SYSCON_PCLKSEL0_UART1_MASK (3 << SYSCON_PCLKSEL0_UART1_SHIFT)
+ /* Bits 10-11: Reserved */
+#define SYSCON_PCLKSEL0_PWM1_SHIFT (12) /* Bits 12-13: Peripheral clock PWM1 */
+#define SYSCON_PCLKSEL0_PWM1_MASK (3 << SYSCON_PCLKSEL0_PWM1_SHIFT)
+#define SYSCON_PCLKSEL0_I2C0_SHIFT (14) /* Bits 14-15: Peripheral clock I2C0 */
+#define SYSCON_PCLKSEL0_I2C0_MASK (3 << SYSCON_PCLKSEL0_I2C0_SHIFT)
+#define SYSCON_PCLKSEL0_SPI_SHIFT (16) /* Bits 16-17: Peripheral clock SPI */
+#define SYSCON_PCLKSEL0_SPI_MASK (3 << SYSCON_PCLKSEL0_SPI_SHIFT)
+ /* Bits 18-19: Reserved */
+#define SYSCON_PCLKSEL0_SSP1_SHIFT (20) /* Bits 20-21: Peripheral clock SSP1 */
+#define SYSCON_PCLKSEL0_SSP1_MASK (3 << SYSCON_PCLKSEL0_SSP1_SHIFT)
+#define SYSCON_PCLKSEL0_DAC_SHIFT (22) /* Bits 22-23: Peripheral clock DAC */
+#define SYSCON_PCLKSEL0_DAC_MASK (3 << SYSCON_PCLKSEL0_DAC_SHIFT)
+#define SYSCON_PCLKSEL0_ADC_SHIFT (24) /* Bits 24-25: Peripheral clock ADC */
+#define SYSCON_PCLKSEL0_ADC_MASK (3 << SYSCON_PCLKSEL0_ADC_SHIFT)
+#define SYSCON_PCLKSEL0_CAN1_SHIFT (26) /* Bits 26-27: Peripheral clock CAN1 */
+#define SYSCON_PCLKSEL0_CAN1_MASK (3 << SYSCON_PCLKSEL0_CAN1_SHIFT)
+#define SYSCON_PCLKSEL0_CAN2_SHIFT (28) /* Bits 28-29: Peripheral clock CAN2 */
+#define SYSCON_PCLKSEL0_CAN2_MASK (3 << SYSCON_PCLKSEL0_CAN2_SHIFT)
+#define SYSCON_PCLKSEL0_ACF_SHIFT (30) /* Bits 30-31: Peripheral clock CAN AF */
+#define SYSCON_PCLKSEL0_ACF_MASK (3 << SYSCON_PCLKSEL0_ACF_SHIFT)
+
+#define SYSCON_PCLKSEL1_QEI_SHIFT (0) /* Bits 0-1: Peripheral clock Quadrature Encoder */
+#define SYSCON_PCLKSEL1_QEI_MASK (3 << SYSCON_PCLKSEL1_QEI_SHIFT)
+#define SYSCON_PCLKSEL1_GPIOINT_SHIFT (2) /* Bits 2-3: Peripheral clock GPIO interrupts */
+#define SYSCON_PCLKSEL1_GPIOINT_MASK (3 << SYSCON_PCLKSEL1_GPIOINT_SHIFT)
+#define SYSCON_PCLKSEL1_PCB_SHIFT (4) /* Bits 4-5: Peripheral clock the Pin Connect block */
+#define SYSCON_PCLKSEL1_PCB_MASK (3 << SYSCON_PCLKSEL1_PCB_SHIFT)
+#define SYSCON_PCLKSEL1_I2C1_SHIFT (6) /* Bits 6-7: Peripheral clock I2C1 */
+#define SYSCON_PCLKSEL1_I2C1_MASK (3 << SYSCON_PCLKSEL1_I2C1_SHIFT)
+ /* Bits 8-9: Reserved */
+#define SYSCON_PCLKSEL1_SSP0_SHIFT (10) /* Bits 10-11: Peripheral clock SSP0 */
+#define SYSCON_PCLKSEL1_SSP0_MASK (3 << SYSCON_PCLKSEL1_SSP0_SHIFT)
+#define SYSCON_PCLKSEL1_TMR2_SHIFT (12) /* Bits 12-13: Peripheral clock TIMER2 */
+#define SYSCON_PCLKSEL1_TMR2_MASK (3 << SYSCON_PCLKSEL1_TMR2_SHIFT)
+#define SYSCON_PCLKSEL1_TMR3_SHIFT (14) /* Bits 14-15: Peripheral clock TIMER3 */
+#define SYSCON_PCLKSEL1_TMR3_MASK (3 << SYSCON_PCLKSEL1_TMR3_SHIFT)
+#define SYSCON_PCLKSEL1_UART2_SHIFT (16) /* Bits 16-17: Peripheral clock UART2 */
+#define SYSCON_PCLKSEL1_UART2_MASK (3 << SYSCON_PCLKSEL1_UART2_SHIFT)
+#define SYSCON_PCLKSEL1_UART3_SHIFT (18) /* Bits 18-19: Peripheral clock UART3 */
+#define SYSCON_PCLKSEL1_UART3_MASK (3 << SYSCON_PCLKSEL1_UART3_SHIFT)
+#define SYSCON_PCLKSEL1_I2C2_SHIFT (20) /* Bits 20-21: Peripheral clock I2C2 */
+#define SYSCON_PCLKSEL1_I2C2_MASK (3 << SYSCON_PCLKSEL1_I2C2_SHIFT)
+#define SYSCON_PCLKSEL1_I2S_SHIFT (22) /* Bits 22-23: Peripheral clock I2S */
+#define SYSCON_PCLKSEL1_I2S_MASK (3 << SYSCON_PCLKSEL1_I2S_SHIFT)
+ /* Bits 24-25: Reserved */
+#define SYSCON_PCLKSEL1_RIT_SHIFT (26) /* Bits 26-27: Peripheral clock Repetitive Interrupt Timer */
+#define SYSCON_PCLKSEL1_RIT_MASK (3 << SYSCON_PCLKSEL1_RIT_SHIFT)
+#define SYSCON_PCLKSEL1_SYSCON_SHIFT (28) /* Bits 28-29: Peripheral clock the System Control block */
+#define SYSCON_PCLKSEL1_SYSCON_MASK (3 << SYSCON_PCLKSEL1_SYSCON_SHIFT)
+#define SYSCON_PCLKSEL1_MC_SHIFT (30) /* Bits 30-31: Peripheral clock the Motor Control PWM */
+#define SYSCON_PCLKSEL1_MC_MASK (3 << SYSCON_PCLKSEL1_MC_SHIFT)
+
+/* Clocking and power control - Peripheral power control registers */
+/* Power Control Register */
+
+#define SYSCON_PCON_PM0 (1 << 0) /* Bit 0: Power mode control bit 0 */
+#define SYSCON_PCON_PM1 (1 << 1) /* Bit 1: Power mode control bit 1 */
+#define SYSCON_PCON_BODRPM (1 << 2) /* Bit 2: Brown-Out Reduced Power Mode */
+#define SYSCON_PCON_BOGD (1 << 3) /* Bit 3: Brown-Out Global Disable */
+#define SYSCON_PCON_BORD (1 << 4) /* Bit 4: Brown-Out Reset Disable */
+ /* Bits 5-7: Reserved */
+#define SYSCON_PCON_SMFLAG (1 << 8) /* Bit 8: Sleep Mode entry flag */
+#define SYSCON_PCON_DSFLAG (1 << 9) /* Bit 9: Deep Sleep entry flag */
+#define SYSCON_PCON_PDFLAG (1 << 10) /* Bit 10: Power-down entry flag */
+#define SYSCON_PCON_DPDFLAG (1 << 11) /* Bit 11: Deep Power-down entry flag */
+ /* Bits 12-31: Reserved */
+/* Power Control for Peripherals Register */
+
+ /* Bit 0: Reserved */
+#define SYSCON_PCONP_PCTIM0 (1 << 1) /* Bit 1: Timer/Counter 0 power/clock control */
+#define SYSCON_PCONP_PCTIM1 (1 << 2) /* Bit 2: Timer/Counter 1 power/clock control */
+#define SYSCON_PCONP_PCUART0 (1 << 3) /* Bit 3: UART0 power/clock control */
+#define SYSCON_PCONP_PCUART1 (1 << 4) /* Bit 4: UART1 power/clock control */
+ /* Bit 5: Reserved */
+#define SYSCON_PCONP_PCPWM1 (1 << 6) /* Bit 6: PWM1 power/clock control */
+#define SYSCON_PCONP_PCI2C0 (1 << 7) /* Bit 7: I2C0 power/clock control */
+#define SYSCON_PCONP_PCSPI (1 << 8) /* Bit 8: SPI power/clock control */
+#define SYSCON_PCONP_PCRTC (1 << 9) /* Bit 9: RTC power/clock control */
+#define SYSCON_PCONP_PCSSP1 (1 << 10) /* Bit 10: SSP 1 power/clock control */
+ /* Bit 11: Reserved */
+#define SYSCON_PCONP_PCADC (1 << 12) /* Bit 12: A/D converter (ADC) power/clock control */
+#define SYSCON_PCONP_PCCAN1 (1 << 13) /* Bit 13: CAN Controller 1 power/clock control */
+#define SYSCON_PCONP_PCCAN2 (1 << 14) /* Bit 14: CAN Controller 2 power/clock control */
+#define SYSCON_PCONP_PCGPIO (1 << 15) /* Bit 15: GPIOs power/clock enable */
+#define SYSCON_PCONP_PCRIT (1 << 16) /* Bit 16: Repetitive Interrupt Timer power/clock control */
+#define SYSCON_PCONP_PCMCPWM (1 << 17) /* Bit 17: Motor Control PWM */
+#define SYSCON_PCONP_PCQEI (1 << 18) /* Bit 18: Quadrature Encoder power/clock control */
+#define SYSCON_PCONP_PCI2C1 (1 << 19) /* Bit 19: I2C1 power/clock control */
+ /* Bit 20: Reserved */
+#define SYSCON_PCONP_PCSSP0 (1 << 21) /* Bit 21: SSP0 power/clock control */
+#define SYSCON_PCONP_PCTIM2 (1 << 22) /* Bit 22: Timer 2 power/clock control */
+#define SYSCON_PCONP_PCTIM3 (1 << 23) /* Bit 23: Timer 3 power/clock control */
+#define SYSCON_PCONP_PCUART2 (1 << 24) /* Bit 24: UART 2 power/clock control */
+#define SYSCON_PCONP_PCUART3 (1 << 25) /* Bit 25: UART 3 power/clock control */
+#define SYSCON_PCONP_PCI2C2 (1 << 26) /* Bit 26: I2C 2 power/clock control */
+#define SYSCON_PCONP_PCI2S (1 << 27) /* Bit 27: I2S power/clock control */
+ /* Bit 28: Reserved */
+#define SYSCON_PCONP_PCGPDMA (1 << 29) /* Bit 29: GPDMA function power/clock control */
+#define SYSCON_PCONP_PCENET (1 << 30) /* Bit 30: Ethernet block power/clock control */
+#define SYSCON_PCONP_PCUSB (1 << 31) /* Bit 31: USB power/clock control */
+
+/* More clocking and power control -- Utility */
+
+#define SYSCON_CLKOUTCFG_SEL_SHIFT (0) /* Bits 0-3: Selects clock source for CLKOUT */
+#define SYSCON_CLKOUTCFG_SEL_MASK (15 << SYSCON_CLKOUTCFG_SEL_SHIFT)
+# define SYSCON_CLKOUTCFG_SEL_CPU (0 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=CPU clock */
+# define SYSCON_CLKOUTCFG_SEL_MAIN (1 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=main osc */
+# define SYSCON_CLKOUTCFG_SEL_INTRC (2 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=internal RC osc */
+# define SYSCON_CLKOUTCFG_SEL_USB (3 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=USB clock */
+# define SYSCON_CLKOUTCFG_SEL_RTC (4 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=RTC osc */
+#define SYSCON_CLKOUTCFG_DIV_SHIFT (4) /* Bits 4-7: CLKOUT divisor */
+#define SYSCON_CLKOUTCFG_DIV_MASK (15 << SYSCON_CLKOUTCFG_DIV_SHIFT)
+# define SYSCON_CLKOUTCFG_DIV(n) ((n-1) << SYSCON_CLKOUTCFG_DIV_SHIFT) /* n=1..16 */
+#define SYSCON_CLKOUTCFG_EN (1 << 8) /* Bit 8: CLKOUT enable control */
+#define SYSCON_CLKOUTCFG_ACT (1 << 9) /* Bit 9: CLKOUT activity indication */
+ /* Bits 10-31: Reserved */
+/* System control registers -- External Interrupts */
+/* External Interrupt Flag register */
+
+#define SYSCON_EXTINT_EINT0 (1 << 0) /* Bit 0: EINT0 */
+#define SYSCON_EXTINT_EINT1 (1 << 1) /* Bit 1: EINT1 */
+#define SYSCON_EXTINT_EINT2 (1 << 2) /* Bit 2: EINT2 */
+#define SYSCON_EXTINT_EINT3 (1 << 3) /* Bit 3: EINT3 */
+ /* Bits 4-31: Reserved */
+/* External Interrupt Mode register */
+
+#define SYSCON_EXTMODE_EINT0 (1 << 0) /* Bit 0: 1=EINT0 edge sensitive */
+#define SYSCON_EXTMODE_EINT1 (1 << 1) /* Bit 1: 1=EINT1 edge sensitive */
+#define SYSCON_EXTMODE_EINT2 (1 << 2) /* Bit 2: 1=EINT2 edge sensitive */
+#define SYSCON_EXTMODE_EINT3 (1 << 3) /* Bit 3: 1=EINT3 edge sensitive */
+ /* Bits 4-31: Reserved */
+/* External Interrupt Polarity register */
+
+#define SYSCON_EXTPOLAR_EINT0 (1 << 0) /* Bit 0: 1=EINT0 high active/rising edge */
+#define SYSCON_EXTPOLAR_EINT1 (1 << 1) /* Bit 1: 1=EINT1 high active/rising edge */
+#define SYSCON_EXTPOLAR_EINT2 (1 << 2) /* Bit 2: 1=EINT2 high active/rising edge */
+#define SYSCON_EXTPOLAR_EINT3 (1 << 3) /* Bit 3: 1=EINT3 high active/rising edge */
+ /* Bits 4-31: Reserved */
+/* System control registers -- Reset */
+/* Reset Source Identification Register */
+
+#define SYSCON_RSID_POR (1 << 0) /* Bit 0: Power on reset */
+#define SYSCON_RSID_EXTR (1 << 1) /* Bit 1: external RESET signal */
+#define SYSCON_RSID_WDTR (1 << 2) /* Bit 2: Watchdog Timer time out w/WDTRESET */
+#define SYSCON_RSID_BODR (1 << 3) /* Bit 3: Brown out detection */
+ /* Bits 4-31: Reserved */
+/* System control registers -- Syscon Miscellaneous Registers */
+
+ /* Bits 0-3: Reserved */
+#define SYSCON_SCS_OSCRANGE (1 << 4) /* Bit 4: Main oscillator range select */
+#define SYSCON_SCS_OSCEN (1 << 5) /* Bit 5: Main oscillator enable */
+#define SYSCON_SCS_OSCSTAT (1 << 6) /* Bit 6: Main oscillator status */
+ /* Bits 7-31: Reserved */
+/* Device Interrupt Registers */
+/* USB Interrupt Status register */
+
+#define SYSCON_USBINTST_REQLP (1 << 0) /* Bit 0: Low priority interrupt line status */
+#define SYSCON_USBINTST_REQHP (1 << 1) /* Bit 1: High priority interrupt line status */
+#define SYSCON_USBINTST_REQDMA (1 << 2) /* Bit 2: DMA interrupt line status */
+#define SYSCON_USBINTST_HOSTINT (1 << 3) /* Bit 3: USB host interrupt line status */
+#define SYSCON_USBINTST_ATXINT (1 << 4) /* Bit 4: External ATX interrupt line status */
+#define SYSCON_USBINTST_OTGINT (1 << 5) /* Bit 5: OTG interrupt line status */
+#define SYSCON_USBINTST_I2CINT (1 << 6) /* Bit 6: I2C module interrupt line status */
+ /* Bit 7: Reserved */
+#define SYSCON_USBINTST_NEEDCLK (1 << 8) /* Bit 8: USB need clock indicator */
+ /* Bits 9-30: Reserved */
+#define SYSCON_USBINTST_ENINTS (1 << 31) /* Bit 31: Enable all USB interrupts */
+
+/* DMA Request Select Register */
+
+#define SYSCON_DMAREQSEL_INP8 (1 << 0) /* Bit 0: Input 8 0=UART0 TX 1=Timer 0 match 0 */
+#define SYSCON_DMAREQSEL_INP9 (1 << 1) /* Bit 1: Input 8 0=UART0 RX 1=Timer 0 match 1 */
+#define SYSCON_DMAREQSEL_INP10 (1 << 2) /* Bit 2: Input 8 0=UART1 TX 1=Timer 1 match 0 */
+#define SYSCON_DMAREQSEL_INP11 (1 << 3) /* Bit 3: Input 8 0=UART1 RX 1=Timer 1 match 1 */
+#define SYSCON_DMAREQSEL_INP12 (1 << 4) /* Bit 4: Input 8 0=UART2 TX 1=Timer 2 match 0 */
+#define SYSCON_DMAREQSEL_INP13 (1 << 5) /* Bit 5: Input 8 0=UART2 RX 1=Timer 2 match 1 */
+#define SYSCON_DMAREQSEL_INP14 (1 << 6) /* Bit 6: Input 8 0=UART3 TX 1=Timer 3 match 0 */
+#define SYSCON_DMAREQSEL_INP15 (1 << 7) /* Bit 7: Input 8 0=UART3 RX 1=Timer 3 match 1 */
+ /* Bits 8-31: Reserved */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC176X_SYSCON_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h
index 21e8e6c33..295e1a0ee 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h
@@ -48,6 +48,96 @@
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
+/* Memory Map ***********************************************************************/
+
+#define LPC17_FLASH_BASE 0x00000000 /* -0x1fffffff: On-chip non-volatile memory */
+#define LPC17_SRAM_BASE 0x10000000 /* -0x10007fff: On-chip SRAM (devices <=32Kb) */
+#define LPC17_ROM_BASE 0x1fff0000 /* -0x1fffffff: 8Kb Boot ROM with flash services */
+#define LPC17_AHBSRAM_BASE 0x20000000 /* -0x3fffffff: On-chip Peripheral SRAM (devices >32Kb) */
+# define LPC17_SRAM_BANK0 0x20000000 /* -0x20003fff: On-chip Peripheral SRAM Bank0 (devices >=32Kb) */
+# define LPC17_SRAM_BANK1 0x20004000 /* -0x20007fff: On-chip Peripheral SRAM Bank1 (devices 64Kb) */
+#define LPC17_AHB_BASE 0x20080000 /* -0x2008ffff: DMA Controller, Ethernet, and USB */
+#define LPC17_SPIFI_BASE 0x28000000
+#define LPC17_APB_BASE 0x40000000 /* -0x5fffffff: APB Peripherals */
+# define LPC17_APB0_BASE 0x40000000 /* -0x4007ffff: APB0 Peripherals */
+# define LPC17_APB1_BASE 0x40080000 /* -0x400fffff: APB1 Peripherals */
+
+/* Off chip Memory via External Memory Interface */
+
+#define LPC17_EXTRAM_BASE 0x80000000 /* */
+# define LPC17_EXTSRAM_CS0 0x80000000 /* Chip select 0 /up to 64MB/ */
+# define LPC17_EXTSRAM_CS1 0x90000000 /* Chip select 1 /up to 64MB/ */
+# define LPC17_EXTSRAM_CS2 0x98000000 /* Chip select 2 /up to 64MB/ */
+# define LPC17_EXTSRAM_CS3 0x9c000000 /* Chip select 3 /up to 64MB/ */
+
+# define LPC17_EXTDRAM_CS0 0x9c000000 /* Chip select 0 /up to 256MB/ */
+# define LPC17_EXTDRAM_CS1 0x9c000000 /* Chip select 1 /up to 256MB/ */
+# define LPC17_EXTDRAM_CS2 0x9c000000 /* Chip select 2 /up to 256MB/ */
+# define LPC17_EXTDRAM_CS3 0x9c000000 /* Chip select 3 /up to 256MB/ */
+
+#define LPC17_CORTEXM3_BASE 0xe0000000 /* -0xe00fffff: (see armv7-m/nvic.h) */
+#define LPC17_SCS_BASE 0xe000e000
+#define LPC17_DEBUGMCU_BASE 0xe0042000
+
+/* AHB SRAM Bank sizes **************************************************************/
+
+#define LPC17_BANK0_SIZE (16*1024) /* Size of AHB SRAM Bank0 (if present) */
+#define LPC17_BANK1_SIZE (16*1024) /* Size of AHB SRAM Bank1 (if present) */
+
+/* APB0 Peripherals *****************************************************************/
+
+#define LPC17_WDT_BASE 0x40000000 /* -0x40003fff: Watchdog timer */
+#define LPC17_TMR0_BASE 0x40004000 /* -0x40007fff: Timer 0 */
+#define LPC17_TMR1_BASE 0x40008000 /* -0x4000bfff: Timer 1 */
+#define LPC17_UART0_BASE 0x4000c000 /* -0x4000ffff: UART 0 */
+#define LPC17_UART1_BASE 0x40010000 /* -0x40013fff: UART 1 */
+#define LPC17_PWM0_BASE 0x40014000 /* -0x40017fff: PWM 0 */
+#define LPC17_PWM1_BASE 0x40018000 /* -0x4001bfff: PWM 1 */
+#define LPC17_I2C0_BASE 0x4001c000 /* -0x4001ffff: I2C 0 */
+ /* -0x40023fff: Reserved */
+#define LPC17_RTC_BASE 0x40024000 /* -0x40027fff: RTC + backup registers */
+#define LPC17_GPIOINT_BASE 0x40028000 /* -0x4002bfff: GPIO interrupts */
+#define LPC17_PINCONN_BASE 0x4002c000 /* -0x4002ffff: Pin connect block */
+#define LPC17_SSP1_BASE 0x40030000 /* -0x40033fff: SSP 1 */
+#define LPC17_ADC_BASE 0x40034000 /* -0x40037fff: ADC */
+#define LPC17_CANAFRAM_BASE 0x40038000 /* -0x4003bfff: CAN acceptance filter (AF) RAM */
+#define LPC17_CANAF_BASE 0x4003c000 /* -0x4003ffff: CAN acceptance filter (AF) registers */
+#define LPC17_CAN_BASE 0x40040000 /* -0x40043fff: CAN common registers */
+#define LPC17_CAN1_BASE 0x40044000 /* -0x40047fff: CAN controller l */
+#define LPC17_CAN2_BASE 0x40048000 /* -0x4004bfff: CAN controller 2 */
+ /* -0x4005bfff: Reserved */
+#define LPC17_I2C1_BASE 0x4005c000 /* -0x4005ffff: I2C 1 */
+ /* -0x4007ffff: Reserved */
+
+/* APB1 Peripherals *****************************************************************/
+
+ /* -0x40087fff: Reserved */
+#define LPC17_SSP0_BASE 0x40088000 /* -0x4008bfff: SSP 0 */
+#define LPC17_DAC_BASE 0x4008c000 /* -0x4008ffff: DAC */
+#define LPC17_TMR2_BASE 0x40090000 /* -0x40093fff: Timer 2 */
+#define LPC17_TMR3_BASE 0x40094000 /* -0x40097fff: Timer 3 */
+#define LPC17_UART2_BASE 0x40098000 /* -0x4009bfff: UART 2 */
+#define LPC17_UART3_BASE 0x4009c000 /* -0x4009ffff: UART 3 */
+#define LPC17_I2C2_BASE 0x400a0000 /* -0x400a3fff: I2C 2 */
+ /* -0x400a7fff: Reserved */
+#define LPC17_I2S_BASE 0x400a8000 /* -0x400abfff: I2S */
+#define LPC17_SSP2_BASE 0x400ac000 /* -0x400affff: SSP2 */
+ /* -0x400b3fff: Reserved */
+ /* -0x400b7fff: Reserved */
+#define LPC17_MCPWM_BASE 0x400b8000 /* -0x400bbfff: Motor control PWM */
+#define LPC17_QEI_BASE 0x400bc000 /* -0x400bffff: Quadrature encoder interface */
+#define LPC17_MCI_BASE 0x400c0000 /* -0x400fbfff: SD interface */
+#define LPC17_SYSCON_BASE 0x400fc000 /* -0x400fffff: System control */
+
+/* AHB Peripherals ******************************************************************/
+
+#define LPC17_GPDMA_BASE 0x20080000 /* GPDMA controller */
+#define LPC17_ETH_BASE 0x20084000 /* Ethernet controller */
+#define LPC17_LCD_BASE 0x20088000 /* LCD controller */
+#define LPC17_USB_BASE 0x2008c000 /* USB controller */
+#define LPC17_CRC_BASE 0x20090000 /* CRC engine */
+#define LPC17_GPIO_BASE 0x20098000 /* GPIO */
+#define LPC17_EMC_BASE 0x2009c000 /* External Memory Controller */
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
index 53c2b26a9..37a16c1e0 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
@@ -48,7 +48,7 @@
************************************************************************************/
/* 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
+ * are identified with a numerical suffix like _1, _2, or _3. Your board.h file
* should select the correct alternative for your board by including definitions
* such as:
*
@@ -57,6 +57,593 @@
* (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_UART0_TXD_1 (GPIO_ALT4 | 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_RXD_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN1)
+
+#define GPIO_UART0_TXD (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN2)
+#define GPIO_UART3_TXD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN2)
+
+#define GPIO_UART0_RXD (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN3)
+#define GPIO_UART3_RXD (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_LCD_VD0_1 (GPIO_ALT4 | 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_LCD_VD1_1 (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_UART1_RTS_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
+#define GPIO_LCD_VD8 (GPIO_ALT5 | 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_RTC_EV0_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
+#define GPIO_LCD_VD9 (GPIO_ALT5 | 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_RTC_EV1_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
+#define GPIO_LCD_VD16 (GPIO_ALT5 | 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_RTC_EV2_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
+#define GPIO_LCD_VD17 (GPIO_ALT5 | 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_USB_PPWR2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN12)
+#define GPIO_SSP1_MISO (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN12)
+#define GPIO_AD0p6 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN12)
+
+#define GPIO_USB_LED2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN13)
+#define GPIO_SSP1_MOSI (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN13)
+#define GPIO_AD0p7 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN13)
+
+#define GPIO_USB_HSTEN2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN14)
+#define GPIO_SSP1_SSEL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN14)
+#define GPIO_USB_CONNECT2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN14)
+
+#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_SPIFI_IO2 (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_SPIFI_IO3 (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_SPIFI_IO1 (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_SPIFI_IO0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
+
+#define GPIO_UART1_DSR_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN19)
+#define GPIO_SD_CLK (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN19)
+#define GPIO_I2C1_SDA_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN19)
+
+#define GPIO_UART1_DTR_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN20)
+#define GPIO_SD_CMD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN20)
+#define GPIO_I2C1_SCL_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN20)
+
+#define GPIO_UART1_RI_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
+#define GPIO_SD_PWR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
+#define GPIO_UART4_OE (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
+#define GPIO_CAN1_RD_2 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
+#define GPIO_UART4_SCLK (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN21)
+
+#define GPIO_UART1_RTS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
+#define GPIO_SD_DAT0 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
+#define GPIO_UART4_TXD (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
+#define GPIO_CAN1_TD_2 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
+#define GPIO_SPIFI_SCLK (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN22)
+
+#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_USB1DP (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN29)
+#define GPIO_EINT0 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN29)
+
+#define GPIO_USB1DM (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN30)
+#define GPIO_EINT1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN30)
+
+#define GPIO_USB2_DP (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN31)
+
+#define GPIO_ENET_TXD0 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN0)
+#define GPIO_CAP3p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN0)
+#define GPIO_SSP2_SCK (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN0)
+
+#define GPIO_ENET_TXD1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN1)
+#define GPIO_MAT3p3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN1)
+#define GPIO_SSP2_MOSI (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN1)
+
+#define GPIO_ENET_TXD2 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN2)
+#define GPIO_SD_CLK (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN2)
+#define GPIO_PWM0p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN2)
+
+#define GPIO_ENET_TXD3 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN3)
+#define GPIO_SD_CMD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN3)
+#define GPIO_PWM0p2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN3)
+
+#define GPIO_ENET_TXEN (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN4)
+#define GPIO_MAT3p2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN4)
+#define GPIO_SSP2_MISO (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN4)
+
+#define GPIO_ENET_TX_ER (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN5)
+#define GPIO_SD_PWR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN5)
+#define GPIO_PWM0p3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN5)
+
+#define GPIO_ENET_TX_CLK (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN6)
+#define GPIO_SD_DAT0 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN6)
+#define GPIO_PWM0p4 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN6)
+
+#define GPIO_ENET_COL (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN7)
+#define GPIO_SD_DAT1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN7)
+#define GPIO_PWM0p5 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN7)
+
+#define GPIO_ENET_CRSDV (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN8)
+#define GPIO_MAT3p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN8)
+#define GPIO_SSP2_SSEL (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN8)
+
+#define GPIO_ENET_RXD0 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN9)
+#define GPIO_MAT3p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN9)
+
+#define GPIO_ENET_RXD1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN10)
+#define GPIO_CAP3p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN10)
+
+#define GPIO_ENET_RXD2 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN11)
+#define GPIO_SD_DAT2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN11)
+#define GPIO_PWM0p6 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN11)
+
+#define GPIO_ENET_RXD3 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN12)
+#define GPIO_SD_DAT3 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN12)
+#define GPIO_PWM0CAPp0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN12)
+
+#define GPIO_ENET_RX_DV (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN13)
+
+#define GPIO_ENET_RXER (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN14)
+#define GPIO_CAP2p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN14)
+
+#define GPIO_ENET_REFCLK (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN15)
+#define GPIO_I2C2_SDA (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN15)
+
+#define GPIO_ENET_MDC_1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN16)
+#define GPIO_I2S_TXMCLK (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN16)
+
+#define GPIO_ENET_MDIO_1 (GPIO_ALT1 | GPIO_FLOAT | GPIO_PORT1 | GPIO_PIN17)
+#define GPIO_I2S_RXMCLK (GPIO_ALT2 | 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_SSP1_MISO (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN18)
+
+#define GPIO_USB1_TXE (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
+#define GPIO_USB1_PPWR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
+#define GPIO_CAP1p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
+#define GPIO_MCPWM_MC0A (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
+#define GPIO_SSP1_SCK (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
+#define GPIO_UART2_OE (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN19)
+
+#define GPIO_USB1_TXDP (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+#define GPIO_PWM1p2_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+#define GPIO_QEI_PHA (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+#define GPIO_MCPWM_MCFB0 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+#define GPIO_SSP0_SCK (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+#define GPIO_LCD_VD6 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+#define GPIO_LCD_VD10 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN20)
+
+#define GPIO_USB1_TXDM (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_ABORT (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN21)
+#define GPIO_LCD_VD7 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN21)
+#define GPIO_LCD_VD11 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN21)
+
+#define GPIO_USB1_RCV (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
+#define GPIO_USB1_PWRD (GPIO_ALT2 | GPIO_PULLDN | GPIO_PORT1 | GPIO_PIN22)
+#define GPIO_MAT1p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
+#define GPIO_MCPWM_MCOB (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
+#define GPIO_SSP1_MOSI (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
+#define GPIO_LCD_VD8 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
+#define GPIO_LCD_VD12 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN22)
+
+#define GPIO_USB1_RXDP (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+#define GPIO_PWM1p4 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+#define GPIO_QEI_PHB (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+#define GPIO_MCPWM_MCFB1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+#define GPPIO_SSP0_MOSI (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+#define GPIO_LCD_VD9 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+#define GPIO_LCD_VD13 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN23)
+
+#define GPIO_USB1_RXDM (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+#define GPIO_PWM1p5_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+#define GPIO_QEI_IDX (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+#define GPIO_MCPWM_MCFB2 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+#define GPIO_SSP0_MOSI_2 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+#define GPIO_LCD_VD10_VD14 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+#define GPIO_LCD_VD10_VD14 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN24)
+
+#define GPIO_USB1_LS (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
+#define GPIO_USB1_HSTEN (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
+#define GPIO_MAT1p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
+#define GPIO_MCPWM_MC1A (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
+#define GPIO_CLKOUT_ (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
+#define GPIO_LCD_VD11 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
+#define GPIO_LCD_VD15 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN25)
+
+#define GPIO_USB1_SSPND (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_MCPWM_MC1B (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
+#define GPIO_SSP1_SSEL (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
+#define GPIO_LCD_VD12 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
+#define GPIO_LCD_VD20 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26)
+
+#define GPIO_USB1_INT (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
+#define GPIO_USB1_OVRCR (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
+#define GPIO_CAP0p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
+#define GPIO_CLKOUT_2 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
+#define GPIO_LCD_VD13 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
+#define GPIO_LCD_VD21 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN27)
+
+#define GPIO_USB1_SCL (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_MC2A (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
+#define GPIO_SSP0_SSEL (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
+#define GPIO_LCD_VD14 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
+#define GPIO_LCD_VD22 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN28)
+
+#define GPIO_USB1_SDA (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_MCPWM_MC2B (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
+#define GPIO_UART4_TXD (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
+#define GPIO_LCD_VD15 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
+#define GPIO_LCD_VD23 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN29)
+
+#define GPIO_USB2_PWRD (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN30)
+#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_I2C0_SDA (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN30)
+#define GPIO_UART3_OE (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN30)
+
+#define GPIO_USB2_OVRCR (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN31)
+#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_I2C0_SCL (GPIO_ALT4 | 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_LCD_PWR (GPIO_ALT7 | 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_LCD_LE (GPIO_ALT7 | 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_MAT2p3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN2)
+#define GPIO_TRACEDATA3 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN2)
+#define GPIO_LCD_DCLK (GPIO_ALT7 | 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_MAT2p2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN3)
+#define GPIO_TRACEDATA2 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN3)
+#define GPIO_LCD_FP (GPIO_ALT7 | 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_MAT2p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN4)
+#define GPIO_TRACEDATA1 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN4)
+#define GPIO_LCD_ENABM (GPIO_ALT7 | 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_MAT2p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN5)
+#define GPIO_TRACEDATA0 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN5)
+#define GPIO_LCD_LP (GPIO_ALT7 | 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_CAP2p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN6)
+#define GPIO_UART2_OE (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN6)
+#define GPIO_TRACECLK (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN6)
+#define GPIO_LCD_VD0_2 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN6)
+#define GPIO_LCD_VD4 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN6)
+
+#define GPIO_CAN2_RD_2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
+#define GPIO_UART1_RTS_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
+#define GPIO_SPIFI_CS (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
+#define GPIO_LCD_VD1_2 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
+#define GPIO_LCD_VD5 (GPIO_ALT7 | 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_UART1_CTS (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN8)
+#define GPIO_ENET_MDC_2 (GPIO_ALT4 | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN8)
+#define GPIO_LCD_VD2 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN8)
+#define GPIO_LCD_VD6 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN8)
+
+#define GPIO_USB1_CONNECT (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
+#define GPIO_UART2_RXD_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
+#define GPIO_UART4_RXD_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
+#define GPIO_ENET_MDIO_2 (GPIO_ALT4 | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN9)
+#define GPIO_LCD_VD3 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
+#define GPIO_LCD_VD7 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN9)
+
+#define GPIO_EINT0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN10)
+#define GPIO_NMI (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN10)
+
+#define GPIO_EINT1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
+#define GPIO_SD_DAT1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
+#define GPIO_I2S_TXCLK_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
+#define GPIO_LCD_CLKIN (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN11)
+
+#define GPIO_EINT2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define GPIO_SD_DAT2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define GPIO_I2S_TXWS_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define GPIO_LCD_VD4 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define GPIO_LCD_VD3 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define GPIO_LCD_VD8 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define GPIO_LCD_VD18 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+
+#define GPIO_EINT3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+#define GPIO_SD_DAT3 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+#define GPIO_I2S_TXSDA_2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+#define GPIO_LCD_VD5 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+#define GPIO_LCD_VD9 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+#define GPIO_LCD_VD19 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+
+#define GPIO_EMC_CS2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN14)
+#define GPIO_I2C1_SDA (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN14)
+#define GPIO_CAP2p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN14)
+
+#define GPIO_EMC_CS3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN15)
+#define GPIO_I2C1_SCL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN15)
+#define GPIO_CAP2p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN15)
+
+#define GPIO_EMC_CAS (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN16)
+#define GPIO_EMC_RAS (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN17)
+#define GPIO_EMC_CLK0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN18)
+
+#define GPIO_EMC_CLK1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN19)
+#define GPIO_EMC_DYCS0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN20)
+#define GPIO_EMC_DYCS1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN21)
+
+#define GPIO_EMC_DYCS2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN22)
+#define GPIO_SSP0_SCK (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN22)
+#define GPIO_CAP3p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN22)
+
+#define GPIO_EMC_DYCS3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN23)
+#define GPIO_SSP0_SSEL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN23)
+#define GPIO_CAP3p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN23)
+
+#define GPIO_EMC_CKE0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN24)
+#define GPIO_EMC_CKE1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN25)
+
+#define GPIO_EMC_CKE2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN26)
+#define GPIO_SSP0_MISO (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN26)
+#define GPIO_MAT3p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN26)
+
+#define GPIO_EMC_CKE3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN27)
+#define GPIO_SSP0_MOSI (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN27)
+#define GPIO_MAT3p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN27)
+
+#define GPIO_EMC_DQM0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN28)
+#define GPIO_EMC_DQM1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN29)
+
+#define GPIO_EMC_DQM2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN30)
+#define GPIO_I2C2_SDA (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN30)
+#define GPIO_MAT3p2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN30)
+
+#define GPIO_EMC_DQM3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN30)
+#define GPIO_I2C2_SCL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN30)
+#define GPIO_MAT3p3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN30)
+
+#define GPIO_EMC_D0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN0)
+#define GPIO_EMC_D1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN1)
+#define GPIO_EMC_D2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN2)
+#define GPIO_EMC_D3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN3)
+#define GPIO_EMC_D4 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN4)
+#define GPIO_EMC_D5 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN5)
+#define GPIO_EMC_D6 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN6)
+#define GPIO_EMC_D7 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN7)
+#define GPIO_EMC_D8 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN8)
+#define GPIO_EMC_D9 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN9)
+#define GPIO_EMC_D10 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN10)
+#define GPIO_EMC_D11 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN11)
+#define GPIO_EMC_12 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN12)
+#define GPIO_EMC_D13 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN13)
+#define GPIO_EMC_D14 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN14)
+#define GPIO_EMC_D15 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN15)
+
+#define GPIO_EMC_D16 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN16)
+#define GPIO_PWM0p1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN16)
+#define GPIO_UART1_TXD (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN16)
+
+#define GPIO_EMC_D17 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN17)
+#define GPIO_PWM0p2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN17)
+#define GPIO_UART1_RXD (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN17)
+
+#define GPIO_EMC_D18 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN18)
+#define GPIO_PWM0p3 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN18)
+#define GPIO_UART1_CTS (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN18)
+
+#define GPIO_EMC_D19 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN19)
+#define GPIO_PWM0p4 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN19)
+#define GPIO_UART1_DCD (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN19)
+
+#define GPIO_EMC_D20 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN20)
+#define GPIO_PWM0p5 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN20)
+#define GPIO_UART1_DSR (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN20)
+
+#define GPIO_EMC_D21 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN21)
+#define GPIO_PWM0p6 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN21)
+#define GPIO_UART1_DTR (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN21)
+
+#define GPIO_EMC_D22 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN22)
+#define GPIO_PWM0CAPp0 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN22)
+#define GPIO_UART1_RI (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN22)
+
+#define GPIO_EMC_D23 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN23)
+#define GPIO_PWM1CAPp0 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN23)
+#define GPIO_CAP0p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN23)
+
+#define GPIO_EMC_D24 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN24)
+#define GPIO_PWM1p1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN24)
+#define GPIO_CAP0p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN24)
+
+#define GPIO_EMC_D25 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN25)
+#define GPIO_PWM1p2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN25)
+#define GPIO_MAT0p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN25)
+
+#define GPIO_EMC_D26 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
+#define GPIO_PWM1p3 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
+#define GPIO_MAT0p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
+#define GPIO_STCLK (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN26)
+
+#define GPIO_EMC_D27 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN27)
+#define GPIO_PWM1p4 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN27)
+#define GPIO_CAP1p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN27)
+
+#define GPIO_EMC_D28 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN28)
+#define GPIO_PWM1p5 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN28)
+#define GPIO_CAP1p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN28)
+
+#define GPIO_EMC_D29 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN29)
+#define GPIO_PWM1p6 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN29)
+#define GPIO_MAT1p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN29)
+
+#define GPIO_EMC_D30 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN30)
+#define GPIO_UART1_RTS (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN30)
+#define GPIO_MAT1p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN30)
+
+#define GPIO_EMC_D31 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN31)
+#define GPIO_MAT1p2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT3 | GPIO_PIN31)
+
+#define GPIO_EMC_A0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN0)
+#define GPIO_EMC_A1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN1)
+#define GPIO_EMC_A2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN2)
+#define GPIO_EMC_A3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN3)
+#define GPIO_EMC_A4 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN4)
+#define GPIO_EMC_A5 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN5)
+#define GPIO_EMC_A6 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN6)
+#define GPIO_EMC_A7 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN7)
+#define GPIO_EMC_A8 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN8)
+#define GPIO_EMC_A9 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN9)
+#define GPIO_EMC_A10 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN10)
+#define GPIO_EMC_A11 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN11)
+#define GPIO_EMC_A12 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN12)
+#define GPIO_EMC_A13 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN13)
+#define GPIO_EMC_A14 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN14)
+#define GPIO_EMC_A15 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN15)
+#define GPIO_EMC_A16 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN16)
+#define GPIO_EMC_A17 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN17)
+#define GPIO_EMC_A18 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN18)
+#define GPIO_EMC_A19 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN19)
+
+#define GPIO_EMC_A20 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN20)
+#define GPIO_I2C2_SDA (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN20)
+#define GPIO_SSP1_SCK (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN20)
+
+#define GPIO_EMC_A21 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN21)
+#define GPIO_I2C2_SCL (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN21)
+#define GPIO_SSP1_SSEL (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN21)
+
+#define GPIO_EMC_A22 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN22)
+#define GPIO_UART2_TXD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN22)
+#define GPIO_SSP1_MISO (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN22)
+
+#define GPIO_EMC_A23 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN23)
+#define GPIO_UART2_RXD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN23)
+#define GPIO_SSP1_MOSI (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN23)
+
+#define GPIO_EMC_OE (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN24)
+#define GPIO_EMC_WE (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN25)
+#define GPIO_EMC_BLS0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN26)
+#define GPIO_EMC_BLS1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN27)
+
+#define GPIO_EMC_BLS2 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
+#define GPIO_UART3_TXD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
+#define GPIO_MAT2p0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
+#define GPIO_LCD_VD6 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
+#define GPIO_LCD_VD10 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
+#define GPIO_LCD_VD2 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN28)
+
+#define GPIO_EMC_BLS3 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+#define GPIO_UART3_RXD (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+#define GPIO_MAT2p1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+#define GPIO_I2C2_SCL (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+#define GPIO_LCD_VD7 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+#define GPIO_LCD_VD11 (GPIO_ALT6 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+#define GPIO_LCD_VD2 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN29)
+
+#define GPIO_EMC_CS0 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN30)
+#define GPIO_EMC_CS1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN31)
+
+#define GPIO_EMC_A24 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN0)
+#define GPIO_MAT2p2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN0)
+
+#define GPIO_EMC_A25 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN1)
+#define GPIO_MAT2p3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN1)
+
+#define GPIO_MAT3p2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN2)
+#define GPIO_I2C0_SDA (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN2)
+
+#define GPIO_UART4_RXD (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN3)
+#define GPIO_I2C0_SCL0 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN3)
+
+#define GPIO_UART4_OE (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN4)
+#define GPIO_MAT3p3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN4)
+#define GPIO_UART4_TXD (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT5 | GPIO_PIN4)
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h
new file mode 100644
index 000000000..5aafce7a6
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h
@@ -0,0 +1,598 @@
+/****************************************************************************************************
+ * arch/arm/src/lpc17xx/chip/lpc178x_syscon.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_SYSCON_H
+#define __ARCH_ARM_SRC_LPC17XX_CHIP_LPC178X_SYSCON_H
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
+
+/****************************************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************************************/
+
+/* Register offsets *********************************************************************************/
+/* Flash accelerator module */
+
+#define LPC17_SYSCON_FLASHCFG_OFFSET 0x0000 /* Flash Accelerator Configuration Register */
+
+/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
+
+#define LPC17_SYSCON_MEMMAP_OFFSET 0x0040 /* Memory Mapping Control register */
+
+/* Clocking and power control - Phase locked loops */
+
+#define LPC17_SYSCON_PLL0CON_OFFSET 0x0080 /* PLL0 Control Register */
+#define LPC17_SYSCON_PLL0CFG_OFFSET 0x0084 /* PLL0 Configuration Register */
+#define LPC17_SYSCON_PLL0STAT_OFFSET 0x0088 /* PLL0 Status Register */
+#define LPC17_SYSCON_PLL0FEED_OFFSET 0x008c /* PLL0 Feed Register */
+
+#define LPC17_SYSCON_PLL1CON_OFFSET 0x00a0 /* PLL1 Control Register */
+#define LPC17_SYSCON_PLL1CFG_OFFSET 0x00a4 /* PLL1 Configuration Register */
+#define LPC17_SYSCON_PLL1STAT_OFFSET 0x00a8 /* PLL1 Status Register */
+#define LPC17_SYSCON_PLL1FEED_OFFSET 0x00ac /* PLL1 Feed Register */
+
+/* Clocking and power control - Peripheral power control registers */
+
+#define LPC17_SYSCON_PCON_OFFSET 0x00c0 /* Power Control Register */
+#define LPC17_SYSCON_PCONP_OFFSET 0x00c4 /* Power Control for Peripherals Register */
+
+/* Clocking and power control -- Clock dividers */
+
+#define LPC17_SYSCON_EMCCLKCFG_OFFSET 0x0100 /* EMC Clock Configuration Register */
+#define LPC17_SYSCON_CCLKCFG_OFFSET 0x0104 /* CPU Clock Configuration Register */
+#define LPC17_SYSCON_USBCLKCFG_OFFSET 0x0108 /* USB Clock Configuration Register */
+
+/* 0x400f c110 - 0x400f c114: CAN Wake and Sleep Registers */
+
+/* Clocking and power control -- Clock source selection */
+
+#define LPC17_SYSCON_CLKSRCSEL_OFFSET 0x010c /* Clock Source Select Register */
+#define LPC17_SYSCON_CANSLEEPCLR_OFFSET 0x0110 /* CAN Channel Sleep State Register */
+#define LPC17_SYSCON_CANWAKEFLAGS_OFFSET 0x0114 /* CAN Channel Wake-Up State Register */
+
+/* System control registers -- External Interrupts */
+
+#define LPC17_SYSCON_EXTINT_OFFSET 0x0140 /* External Interrupt Flag Register */
+#define LPC17_SYSCON_EXTMODE_OFFSET 0x0148 /* External Interrupt Mode register */
+#define LPC17_SYSCON_EXTPOLAR_OFFSET 0x014c /* External Interrupt Polarity Register */
+
+/* System control registers -- Reset */
+
+#define LPC17_SYSCON_RSID_OFFSET 0x0180 /* Reset Source Identification Register */
+
+/* System control registers -- Syscon Miscellaneous Registers */
+
+#define LPC17_SYSCON_MATRIXARB_OFFSET 0x0188 /* Matrix Arbitration Register */
+#define LPC17_SYSCON_SCS_OFFSET 0x01a0 /* System Control and Status */
+#define LPC17_SYSCON_PCLKSEL_OFFSET 0x01a8 /* Peripheral Clock Selection Register */
+#define LPC17_SYSCON_PBOOST_OFFSET 0x01b0 /* Power Boost Register */
+#define LPC17_SYSCON_SPIFICLKSEL_OFFSET 0x01b4 /* SPIFI Clock Selection Register */
+#define LPC17_SYSCON_LCDCFG_OFFSET 0x01b8 /* LCD Clock Configuration Register */
+
+/* Device Interrupt Registers (Might be a error in the User Manual, might be at 0x5000c1c0) */
+
+#define LPC17_SYSCON_USBINTST_OFFSET 0x01c0 /* USB Interrupt Status */
+
+/* DMA Request Select Register */
+
+#define LPC17_SYSCON_DMAREQSEL_OFFSET 0x01c4 /* Selects between UART and timer DMA requests */
+
+/* More clocking and power control -- Utility */
+
+#define LPC17_SYSCON_CLKOUTCFG_OFFSET 0x01c8 /* Clock Output Configuration Register */
+
+/* Peripheral Reset Control */
+
+#define LPC17_SYSCON_RSTCON0_OFFSET 0x01cc /* Individual Peripheral Reset Control Bits */
+#define LPC17_SYSCON_RSTCON1_OFFSET 0x01d0 /* Individual Peripheral Reset Control Bits */
+
+/* EMC Clock Control and Calibration */
+
+#define LPC17_SYSCON_EMCDLYCTL_OFFSET 0x01dc /* Programmable Delays for SDRAM Operation */
+#define LPC17_SYSCON_EMCCAL_OFFSET 0x01e0 /* Calibration Counter for EMCDLYCTL */
+
+
+/* Register addresses *******************************************************************************/
+/* Flash accelerator module */
+
+#define LPC17_SYSCON_FLASHCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_FLASHCFG_OFFSET)
+
+/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
+
+#define LPC17_SYSCON_MEMMAP (LPC17_SYSCON_BASE+LPC17_SYSCON_MEMMAP_OFFSET)
+
+/* Clocking and power control - Phase locked loops */
+
+#define LPC17_SYSCON_PLL0CON (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0CON_OFFSET)
+#define LPC17_SYSCON_PLL0CFG (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0CFG_OFFSET)
+#define LPC17_SYSCON_PLL0STAT (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0STAT_OFFSET)
+#define LPC17_SYSCON_PLL0FEED (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0FEED_OFFSET)
+
+#define LPC17_SYSCON_PLL1CON (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1CON_OFFSET)
+#define LPC17_SYSCON_PLL1CFG (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1CFG_OFFSET)
+#define LPC17_SYSCON_PLL1STAT (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1STAT_OFFSET)
+#define LPC17_SYSCON_PLL1FEED (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1FEED_OFFSET)
+
+/* Clocking and power control - Peripheral power control registers */
+
+#define LPC17_SYSCON_PCON (LPC17_SYSCON_BASE+LPC17_SYSCON_PCON_OFFSET)
+#define LPC17_SYSCON_PCONP (LPC17_SYSCON_BASE+LPC17_SYSCON_PCONP_OFFSET)
+
+/* Clocking and power control -- Clock dividers */
+
+#define LPC17_SYSCON_EMCCLKCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_EMCCLKCFG_OFFSET)
+#define LPC17_SYSCON_CCLKCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_CCLKCFG_OFFSET)
+#define LPC17_SYSCON_USBCLKCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_USBCLKCFG_OFFSET)
+
+/* 0x400f c110 - 0x400f c114: CAN Wake and Sleep Registers */
+
+/* Clocking and power control -- Clock source selection */
+
+#define LPC17_SYSCON_CLKSRCSEL (LPC17_SYSCON_BASE+LPC17_SYSCON_CLKSRCSEL_OFFSET)
+#define LPC17_SYSCON_CANSLEEPCLR (LPC17_SYSCON_BASE+LPC17_SYSCON_CANSLEEPCLR_OFFSET)
+#define LPC17_SYSCON_CANWAKEFLAGS (LPC17_SYSCON_BASE+LPC17_SYSCON_CANWAKEFLAGS_OFFSET)
+
+/* System control registers -- External Interrupts */
+
+#define LPC17_SYSCON_EXTINT (LPC17_SYSCON_BASE+LPC17_SYSCON_EXTINT_OFFSET)
+
+#define LPC17_SYSCON_EXTMODE (LPC17_SYSCON_BASE+LPC17_SYSCON_EXTMODE_OFFSET)
+#define LPC17_SYSCON_EXTPOLAR (LPC17_SYSCON_BASE+LPC17_SYSCON_EXTPOLAR_OFFSET)
+
+/* System control registers -- Reset */
+
+#define LPC17_SYSCON_RSID (LPC17_SYSCON_BASE+LPC17_SYSCON_RSID_OFFSET)
+
+/* System control registers -- Syscon Miscellaneous Registers */
+
+#define LPC17_SYSCON_MATRIXARB (LPC17_SYSCON_BASE+LPC17_SYSCON_MATRIXARB_OFFSET)
+#define LPC17_SYSCON_SCS (LPC17_SYSCON_BASE+LPC17_SYSCON_SCS_OFFSET)
+#define LPC17_SYSCON_PCLKSEL (LPC17_SYSCON_BASE+LPC17_SYSCON_PCLKSEL_OFFSET)
+#define LPC17_SYSCON_PBOOST (LPC17_SYSCON_BASE+LPC17_SYSCON_PBOOST_OFFSET)
+#define LPC17_SYSCON_SPIFICLKSEL (LPC17_SYSCON_BASE+LPC17_SYSCON_SPIFICLKSEL_OFFSET)
+#define LPC17_SYSCON_LCDCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_LCDCFG_OFFSET)
+
+/* Device Interrupt Registers (Might be a error in the User Manual, might be at 0x5000c1c0) */
+
+#define LPC17_SYSCON_USBINTST (LPC17_SYSCON_BASE+LPC17_SYSCON_USBINTST_OFFSET)
+
+/* DMA Request Select Register */
+
+#define LPC17_SYSCON_DMAREQSEL (LPC17_SYSCON_BASE+LPC17_SYSCON_DMAREQSEL_OFFSET)
+
+/* More clocking and power control -- Utility */
+
+#define LPC17_SYSCON_CLKOUTCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_CLKOUTCFG_OFFSET)
+
+
+/* Peripheral Reset Control */
+
+#define LPC17_SYSCON_RSTCON0 (LPC17_SYSCON_BASE+LPC17_SYSCON_RSTCON0_OFFSET)
+#define LPC17_SYSCON_RSTCON1 (LPC17_SYSCON_BASE+LPC17_SYSCON_RSTCON1_OFFSET)
+
+/* EMC Clock Control and Calibration */
+
+#define LPC17_SYSCON_EMCDLYCTL (LPC17_SYSCON_BASE+LPC17_SYSCON_EMCDLYCTL_OFFSET)
+#define LPC17_SYSCON_EMCCAL (LPC17_SYSCON_BASE+LPC17_SYSCON_EMCCAL_OFFSET)
+
+/* Register bit definitions *************************************************************************/
+/* Flash accelerator module */
+ /* Bits 0-11: Reserved */
+#define SYSCON_FLASHCFG_TIM_SHIFT (12) /* Bits 12-15: FLASHTIM Flash access time */
+#define SYSCON_FLASHCFG_TIM_MASK (15 << SYSCON_FLASHCFG_TIM_SHIFT)
+# define SYSCON_FLASHCFG_TIM_1 (0 << SYSCON_FLASHCFG_TIM_SHIFT) /* 1 CPU clock <= 20 MHz CPU clock */
+# define SYSCON_FLASHCFG_TIM_2 (1 << SYSCON_FLASHCFG_TIM_SHIFT) /* 2 CPU clock <= 40 MHz CPU clock */
+# define SYSCON_FLASHCFG_TIM_3 (2 << SYSCON_FLASHCFG_TIM_SHIFT) /* 3 CPU clock <= 60 MHz CPU clock */
+# define SYSCON_FLASHCFG_TIM_4 (3 << SYSCON_FLASHCFG_TIM_SHIFT) /* 4 CPU clock <= 80 MHz CPU clock */
+# define SYSCON_FLASHCFG_TIM_5 (4 << SYSCON_FLASHCFG_TIM_SHIFT) /* 5 CPU clock <= 100 MHz CPU clock
+ * (Up to 120 Mhz for LPC1788x) */
+# define SYSCON_FLASHCFG_TIM_6 (5 << SYSCON_FLASHCFG_TIM_SHIFT) /* "safe" setting for any conditions */
+ /* Bits 16-31: Reserved */
+/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
+
+#define SYSCON_MEMMAP_MAP (1 << 0) /* Bit 0:
+ * 0:Boot mode. A portion of the Boot ROM is mapped to address 0.
+ * 1:User mode. The on-chip Flash memory is mapped to address 0 */
+ /* Bits 1-31: Reserved */
+/* Clocking and power control -- Clock source selection */
+
+#define SYSCON_CLKSRCSEL_SHIFT (0) /* Bits 0: Clock selection */
+#define SYSCON_CLKSRCSEL_MASK (1 << SYSCON_CLKSRCSEL_SHIFT)
+# define SYSCON_CLKSRCSEL_INTRC (0 << SYSCON_CLKSRCSEL_SHIFT) /* PLL0 source = internal RC oscillator */
+# define SYSCON_CLKSRCSEL_MAIN (1 << SYSCON_CLKSRCSEL_SHIFT) /* PLL0 source = main oscillator */
+ /* Bits 1-31: Reserved */
+/* Clocking and power control - Phase locked loops */
+/* PLL0/1 Control register */
+
+#define SYSCON_PLLCON_PLLE (1 << 0) /* Bit 0: PLL Enable */
+ /* Bits 1-31: Reserved */
+/* PLL0/1 Configuration register */
+
+#define SYSCON_PLLCFG_MSEL_SHIFT (0) /* Bit 0-4: PLL Multiplier value */
+#define SYSCON_PLLCFG_MSEL_MASK (0x1f << SYSCON_PLL0CFG_MSEL_SHIFT)
+#define SYSCON_PLLCFG_PSEL_SHIFT (5) /* Bit 5-6: PLL Pre-Divider value */
+#define SYSCON_PLLCFG_PSEL_MASK (3 << SYSCON_PLL0CFG_PSEL_SHIFT)
+
+/* PLL0/1 Status register */
+
+#define SYSCON_PLLSTAT_MSEL_SHIFT (0) /* Bit 0-4: PLLMultiplier value readback */
+#define SYSCON_PLLSTAT_MSEL_MASK (0x1f << SYSCON_PLLSTAT_MSEL_SHIFT)
+#define SYSCON_PLLSTAT_PSEL_SHIFT (5) /* Bit 5-6: PLL Pre-Divider value readback */
+#define SYSCON_PLLSTAT_PSEL_MASK (3 << SYSCON_PLLSTAT_PSEL_SHIFT)
+ /* Bit 7: Reserved */
+#define SYSCON_PLLSTAT_PLLE (1 << 8) /* Bit 8: PLL enable readback */
+#define SYSCON_PLLSTAT_PLLC (1 << 9) /* Bit 9: PLL connect readback */
+#define SYSCON_PLLSTAT_PLOCK (1 << 10) /* Bit 10: PLL lock status */
+ /* Bits 11-31: Reserved */
+/* PLL0/1 Feed register */
+
+#define SYSCON_PLLFEED_SHIFT (0) /* Bit 0-7: PLL0/1 feed sequence */
+#define SYSCON_PLLFEED_MASK (0xff << SYSCON_PLLFEED_SHIFT)
+ /* Bits 8-31: Reserved */
+/* Clocking and power control -- Clock dividers */
+
+/* EMC Clock Selection Register */
+
+#define SYSCON_EMCDIV (1 << 0) /* Bit 0: EMC Clock rate relative to CPU */
+ /* 0: EMC uses same clock as CPU */
+ /* 1: EMC uses half the rate of CPU */
+ /* Bits 1-31: Reserved
+/* CPU Clock Configuration register */
+
+#define SYSCON_CCLKCFG_CCLKDIV_SHIFT (0) /* 0-4: Divide value for CPU clock (CCLK) */
+#define SYSCON_CCLKCFG_CCLKDIV_MASK (0x1f << SYSCON_CCLKCFG_CCLKDIV_SHIFT)
+# define SYSCON_CCLKCFG_CCLKDIV(n) ((n-1) << SYSCON_CCLKCFG_CCLKDIV_SHIFT) /* n = 2 - 31 */
+ /* Bits 5-7: Reserved */
+#define SYSCON_CCLKCFG_CCLKSEL (1 << 8) /* Bit 8: Select input clock to CPU clock divider */
+ /* 0: Sysclk used as input to CCLKDIV */
+ /* 1: Main PLL used as input to CCLKDIV */
+ /* Bits 9-31: Reserved */
+/* USB Clock Configuration register */
+
+#define SYSCON_USBCLKCFG_USBDIV_SHIFT (0) /* Bits 0-4: PLL0/1 divide value USB clock */
+#define SYSCON_USBCLKCFG_USBDIV_MASK (0x1f << SYSCON_USBCLKCFG_USBDIV_SHIFT)
+# define SYSCON_USBCLKCFG_USBDIV_DIV1 (1 << SYSCON_USBCLKCFG_USBDIV_SHIFT) /* PLL0/1 output must be 48MHz */
+# define SYSCON_USBCLKCFG_USBDIV_DIV2 (2 << SYSCON_USBCLKCFG_USBDIV_SHIFT) /* PLL0/1 output must be 96MHz */
+# define SYSCON_USBCLKCFG_USBDIV_DIV3 (3 << SYSCON_USBCLKCFG_USBDIV_SHIFT) /* PLL0/1 output must be 144MHz */
+ /* Bits 5-7: Reserved */
+#define SYSCON_USBCLKCFG_USBSEL_SHIFT (8) /* Bits 8-9: Input clock to USBDIV */
+#define SYSCON_USBCLKCFG_USBSEL_MASK (3 << SYSCON_USBCLKCFG_USBSEL_SHIFT)
+#define SYSCON_USBCLKCFG_USBSEL_MAINPLL (1 << SYSCON_USBCLKCFG_USBSEL_SHIFT) /* 01: PLL0 is used as input clock to USBDIV */
+#define SYSCON_USBCLKCFG_USBSEL_ALTPLL (2 << SYSCON_USBCLKCFG_USBSEL_SHIFT) /* 10: PLL1 is used as input clock to USBDIV */
+ /* 11: unused */
+ /* Bits 10-31: Reserved */
+/* CAN0/1 Sleep Clear Register */
+ /* Bit 0: Reserved */
+#define SYSCON_CANSLEEPCLR_SHIFT (1) /* Bits 1-2: CAN0/1 Sleep Status and Control */
+#define SYSCON_CANSLEEPCLR_MASK (3 << SYSCON_CANSLEEPCLR_SHIFT) /* */
+#define SYSCON_CANSLEEPCLR_CAN1 (1 << SYSCON_CANSLEEPCLR_SHIFT) /* CAN1 Sleep Status */
+#define SYSCON_CANSLEEPCLR_CAN2 (2 << SYSCON_CANSLEEPCLR_SHIFT) /* CAN2 Sleep Status */
+ /* Read 1: CAN channel in sleep mode */
+ /* Write 1: CAN channel clocks restored */
+ /* Bits 3-31: Reserved */
+/* CAN0/1 WakeUp Flags Register */
+ /* Bit 0: Reserved */
+#define SYSCON_CANWAKEFLAGS_SHIFT (1) /* Bits 1-2: CAN0/1 WakeUp Status */
+#define SYSCON_CANWAKEFLAGS_MASK (3 << SYSCON_CANWAKEFLAGS_SHIFT) /* */
+#define SYSCON_CANWAKEFLAGS_CAN1 (1 << SYSCON_CANWAKEFLAGS_SHIFT) /* CAN1 WakeUp Status */
+#define SYSCON_CANWAKEFLAGS_CAN2 (2 << SYSCON_CANWAKEFLAGS_SHIFT) /* CAN2 WakeUp Status */
+ /* Read 1: CAN channel falling edge occur on receive line */
+ /* Write 1: CAN channel clears wakeup flag bit */
+ /* Bits 3-31: Reserved */
+/* Peripheral Clock Selection register */
+/* PCLK is common to all peripheral */
+
+#define SYSCON_PCLKSEL_PCLKDIV_SHIFT (0) /* Bits 0-4: Clock divide value for all APB peripherals */
+#define SYSCON_PCLKSEL_PCLKDIV_MASK (0x1f << SYSCON_PCLKSEL_PCLKDIV_SHIFT)
+# define SYSCON_PCLKSEL_PCLKDIV(n) ((n-1) << SYSCON_PCLKSEL_PCLKDIV_SHIFT) /* n = 2 - 31 */
+ /* Bits 5-31: Reserved */
+/* Power Boost Control Register */
+
+#define SYSCON_PBOOST_BOOST_SHIFT (0) /* Bits 0-1: Boost control bits */
+#define SYSCON_PBOOST_BOOST_MASK (3 << SYSCON_PBOOST_BOOST_SHIFT)
+#define SYSCON_PBOOST_BOOST_OFF (0) /* Boost OFF, operation must be below 100MHz */
+#define SYSCON_PBOOST_BOOST_ON (3) /* Boost ON, operation upto 120MHz allowed */
+ /* Bits 2-31: Reserved */
+/* SPIFI Clock Selection Register */
+
+#define SYSCON_SPIFICLKSEL_SPIFIDIV_SHIFT (0) /* Bits 0-4: divide value for SPIFI clock */
+#define SYSCON_SPIFICLKSEL_SPIFIDIV_MASK (0x1f << SYSCON_SPIFICLKSEL_SPIFIDIV_SHIFT)
+# define SYSCON_SPIFICLKSEL_SPIFIDIV(n) ((n-1) << SYSCON_SPIFICLKSEL_SPIFIDIV_SHIFT) /* n = 2 - 31 */
+ /* Bits 5-7: Reserved */
+#define SYSCON_SPIFICLKSEL_SPIFISEL_SHIFT (8) /* Bits 8-9: Selects input clock for SPIFI clock divider */
+#define SYSCON_SPIFICLKSEL_SPIFISEL_MASK (3 << SYSCON_SPIFICLKSEL_SPIFISEL_SHIFT)
+#define SYSCON_SPIFICLKSEL_SPIFISEL_SYSCLK (0) /* Sysclk used as input to SPIFIDIV */
+#define SYSCON_SPIFICLKSEL_SPIFISEL_PLL0 (1 << SYSCON_SPIFICLKSEL_SPIFISEL_SHIFT) /* Main PLL used as input to SPIFIDIV */
+#define SYSCON_SPIFICLKSEL_SPIFISEL_PLL1 (2 << SYSCON_SPIFICLKSEL_SPIFISEL_SHIFT) /* Alt PLL used as input to SPIFIDIV */
+ /* Bits 10-31: Reserved */
+/* LCD Configuration Register */
+
+#define SYSCON_LCDCFG_CLKDIV_SHIFT (0) /* Bits 0-4: LCD Panel clock prescaler */
+#define SYSCON_LCDCFG_CLKDIV_MASK (0x1f << SYSCON_LCDCFG_CLKDIV_SHIFT)
+#define SYSCON_LCDCFG_CLKDIV(n) ((n+1) << SYSCON_LCDCFG_CLKDIV_SHIFT) /* n = 0 - 31 */
+ /* Bits 5-31: Reserved */
+/* Clocking and power control - Peripheral power control registers */
+/* Power Control Register */
+
+#define SYSCON_PCON_PM0 (1 << 0) /* Bit 0: Power mode control bit 0 */
+#define SYSCON_PCON_PM1 (1 << 1) /* Bit 1: Power mode control bit 1 */
+#define SYSCON_PCON_BODRPM (1 << 2) /* Bit 2: Brown-Out Reduced Power Mode */
+#define SYSCON_PCON_BOGD (1 << 3) /* Bit 3: Brown-Out Global Disable */
+#define SYSCON_PCON_BORD (1 << 4) /* Bit 4: Brown-Out Reset Disable */
+ /* Bits 5-7: Reserved */
+#define SYSCON_PCON_SMFLAG (1 << 8) /* Bit 8: Sleep Mode entry flag */
+#define SYSCON_PCON_DSFLAG (1 << 9) /* Bit 9: Deep Sleep entry flag */
+#define SYSCON_PCON_PDFLAG (1 << 10) /* Bit 10: Power-down entry flag */
+#define SYSCON_PCON_DPDFLAG (1 << 11) /* Bit 11: Deep Power-down entry flag */
+ /* Bits 12-31: Reserved */
+/* Power Control for Peripherals Register */
+
+#define SYSCON_PCONP_PCLCD (1 << 0) /* Bit 0: LCD power/clock control */
+#define SYSCON_PCONP_PCTIM0 (1 << 1) /* Bit 1: Timer/Counter 0 power/clock control */
+#define SYSCON_PCONP_PCTIM1 (1 << 2) /* Bit 2: Timer/Counter 1 power/clock control */
+#define SYSCON_PCONP_PCUART0 (1 << 3) /* Bit 3: UART0 power/clock control */
+#define SYSCON_PCONP_PCUART1 (1 << 4) /* Bit 4: UART1 power/clock control */
+#define SYSCON_PCONP_PCPWM0 (1 << 5) /* Bit 5: PWM0 power/clock control */
+#define SYSCON_PCONP_PCPWM1 (1 << 6) /* Bit 6: PWM1 power/clock control */
+#define SYSCON_PCONP_PCI2C0 (1 << 7) /* Bit 7: I2C0 power/clock control */
+#define SYSCON_PCONP_PCSPI (1 << 8) /* Bit 8: SPI power/clock control */
+#define SYSCON_PCONP_PCRTC (1 << 9) /* Bit 9: RTC power/clock control */
+#define SYSCON_PCONP_PCSSP1 (1 << 10) /* Bit 10: SSP 1 power/clock control */
+#define SYSCON_PCONP_PCEMC (1 << 11) /* Bit 11: External Memory */
+#define SYSCON_PCONP_PCADC (1 << 12) /* Bit 12: A/D converter (ADC) power/clock control */
+#define SYSCON_PCONP_PCCAN1 (1 << 13) /* Bit 13: CAN Controller 1 power/clock control */
+#define SYSCON_PCONP_PCCAN2 (1 << 14) /* Bit 14: CAN Controller 2 power/clock control */
+#define SYSCON_PCONP_PCGPIO (1 << 15) /* Bit 15: GPIOs power/clock enable */
+#define SYSCON_PCONP_PCRIT (1 << 16) /* Bit 16: Repetitive Interrupt Timer power/clock control */
+#define SYSCON_PCONP_PCMCPWM (1 << 17) /* Bit 17: Motor Control PWM */
+#define SYSCON_PCONP_PCQEI (1 << 18) /* Bit 18: Quadrature Encoder power/clock control */
+#define SYSCON_PCONP_PCI2C1 (1 << 19) /* Bit 19: I2C1 power/clock control */
+#define SYSCON_PCONP_PCSSP0 (1 << 20) /* Bit 20: SSP2 power/clock control */
+#define SYSCON_PCONP_PCSSP0 (1 << 21) /* Bit 21: SSP0 power/clock control */
+#define SYSCON_PCONP_PCTIM2 (1 << 22) /* Bit 22: Timer 2 power/clock control */
+#define SYSCON_PCONP_PCTIM3 (1 << 23) /* Bit 23: Timer 3 power/clock control */
+#define SYSCON_PCONP_PCUART2 (1 << 24) /* Bit 24: UART 2 power/clock control */
+#define SYSCON_PCONP_PCUART3 (1 << 25) /* Bit 25: UART 3 power/clock control */
+#define SYSCON_PCONP_PCI2C2 (1 << 26) /* Bit 26: I2C 2 power/clock control */
+#define SYSCON_PCONP_PCI2S (1 << 27) /* Bit 27: I2S power/clock control */
+#define SYSCON_PCONP_PCSDC (1 << 28) /* Bit 28: SD Card power/clock control */
+#define SYSCON_PCONP_PCGPDMA (1 << 29) /* Bit 29: GPDMA function power/clock control */
+#define SYSCON_PCONP_PCENET (1 << 30) /* Bit 30: Ethernet block power/clock control */
+#define SYSCON_PCONP_PCUSB (1 << 31) /* Bit 31: USB power/clock control */
+
+/* More clocking and power control -- Utility */
+
+#define SYSCON_CLKOUTCFG_SEL_SHIFT (0) /* Bits 0-3: Selects clock source for CLKOUT */
+#define SYSCON_CLKOUTCFG_SEL_MASK (15 << SYSCON_CLKOUTCFG_SEL_SHIFT)
+# define SYSCON_CLKOUTCFG_SEL_CPU (0 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=CPU clock */
+# define SYSCON_CLKOUTCFG_SEL_MAIN (1 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=main osc */
+# define SYSCON_CLKOUTCFG_SEL_INTRC (2 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=internal RC osc */
+# define SYSCON_CLKOUTCFG_SEL_USB (3 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=USB clock */
+# define SYSCON_CLKOUTCFG_SEL_RTC (4 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=RTC osc */
+# define SYSCON_CLKOUTCFG_SEL_SPIFI (5 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=SPIFI osc */
+#define SYSCON_CLKOUTCFG_DIV_SHIFT (4) /* Bits 4-7: CLKOUT divisor */
+#define SYSCON_CLKOUTCFG_DIV_MASK (15 << SYSCON_CLKOUTCFG_DIV_SHIFT)
+# define SYSCON_CLKOUTCFG_DIV(n) ((n-1) << SYSCON_CLKOUTCFG_DIV_SHIFT) /* n=1..16 */
+#define SYSCON_CLKOUTCFG_EN (1 << 8) /* Bit 8: CLKOUT enable control */
+#define SYSCON_CLKOUTCFG_ACT (1 << 9) /* Bit 9: CLKOUT activity indication */
+ /* Bits 10-31: Reserved */
+/* System control registers -- External Interrupts */
+/* External Interrupt Flag register */
+
+#define SYSCON_EXTINT_EINT0 (1 << 0) /* Bit 0: EINT0 */
+#define SYSCON_EXTINT_EINT1 (1 << 1) /* Bit 1: EINT1 */
+#define SYSCON_EXTINT_EINT2 (1 << 2) /* Bit 2: EINT2 */
+#define SYSCON_EXTINT_EINT3 (1 << 3) /* Bit 3: EINT3 */
+ /* Bits 4-31: Reserved */
+/* External Interrupt Mode register */
+
+#define SYSCON_EXTMODE_EINT0 (1 << 0) /* Bit 0: 1=EINT0 edge sensitive */
+#define SYSCON_EXTMODE_EINT1 (1 << 1) /* Bit 1: 1=EINT1 edge sensitive */
+#define SYSCON_EXTMODE_EINT2 (1 << 2) /* Bit 2: 1=EINT2 edge sensitive */
+#define SYSCON_EXTMODE_EINT3 (1 << 3) /* Bit 3: 1=EINT3 edge sensitive */
+ /* Bits 4-31: Reserved */
+/* External Interrupt Polarity register */
+
+#define SYSCON_EXTPOLAR_EINT0 (1 << 0) /* Bit 0: 1=EINT0 high active/rising edge */
+#define SYSCON_EXTPOLAR_EINT1 (1 << 1) /* Bit 1: 1=EINT1 high active/rising edge */
+#define SYSCON_EXTPOLAR_EINT2 (1 << 2) /* Bit 2: 1=EINT2 high active/rising edge */
+#define SYSCON_EXTPOLAR_EINT3 (1 << 3) /* Bit 3: 1=EINT3 high active/rising edge */
+ /* Bits 4-31: Reserved */
+/* System control registers -- Reset */
+/* Reset Source Identification Register */
+
+#define SYSCON_RSID_POR (1 << 0) /* Bit 0: Power on reset */
+#define SYSCON_RSID_EXTR (1 << 1) /* Bit 1: external RESET signal */
+#define SYSCON_RSID_WDTR (1 << 2) /* Bit 2: Watchdog Timer time out w/WDTRESET */
+#define SYSCON_RSID_BODR (1 << 3) /* Bit 3: Brown out detection */
+#define SYSCON_RSID_SYSRESET (1 << 4) /* Bit 4: System Reset */
+#define SYSCON_RSID_LOCKUP (1 << 5) /* Bit 5: Lockup Reset */
+ /* Bits 6-31: Reserved */
+/* System control registers -- Matrix Arbitration Priorities */
+/*TODO*/
+#define SYSCON_MATRIXARB_PRI_ICODE (3 << 0) /* Bit 0-1: I-Code bus priority (should be lower than D-Code */
+#define SYSCON_MATRIXARB_PRI_DCODE (3 << 2) /* Bit 2-3: D-Code bus priority */
+#define SYSCON_MATRIXARB_PRI_SYS (3 << 4) /* Bit 4-5: System bus priority */
+#define SYSCON_MATRIXARB_PRI_GPDMA (3 << 6) /* Bit 6-7: General Purpose DMA priority */
+#define SYSCON_MATRIXARB_PRI_ETH (3 << 8) /* Bit 8-9: Ethernet DMA priority */
+#define SYSCON_MATRIXARB_PRI_LCD (3 << 10) /* Bit 10-11: LCD DMA priority */
+#define SYSCON_MATRIXARB_PRI_USB (3 << 12) /* Bit 12-13: USB DMA priority */
+ /* Bits 14-15: Reserved */
+#define SYSCON_MATRIXARB_ROM_LAT (1 << 16) /* Bit 16: ROM Latency select (should always be zero) */
+ /* Bits 17-31: Reserved */
+/* System control registers -- Syscon Miscellaneous Registers */
+
+#define SYSCON_SCS_EMCSC (1 << 0) /* Bit 0: EMC shift control */
+#define SYSCON_SCS_EMCRD (1 << 1) /* Bit 1: EMC reset disable */
+#define SYSCON_SCS_EMCBC (1 << 2) /* Bit 2: EMC burst control */
+#define SYSCON_SCS_MCIPWRAL (1 << 3) /* Bit 3: MCI power active level */
+#define SYSCON_SCS_OSCRS (1 << 4) /* Bit 4: Main oscillator range select */
+#define SYSCON_SCS_OSCEN (1 << 5) /* Bit 5: Main oscillator enable */
+#define SYSCON_SCS_OSCSTAT (1 << 6) /* Bit 6: Main oscillator status */
+ /* Bits 7-31: Reserved */
+/* Device Interrupt Registers */
+/* USB Interrupt Status register */
+
+#define SYSCON_USBINTST_REQLP (1 << 0) /* Bit 0: Low priority interrupt line status */
+#define SYSCON_USBINTST_REQHP (1 << 1) /* Bit 1: High priority interrupt line status */
+#define SYSCON_USBINTST_REQDMA (1 << 2) /* Bit 2: DMA interrupt line status */
+#define SYSCON_USBINTST_HOSTINT (1 << 3) /* Bit 3: USB host interrupt line status */
+#define SYSCON_USBINTST_ATXINT (1 << 4) /* Bit 4: External ATX interrupt line status */
+#define SYSCON_USBINTST_OTGINT (1 << 5) /* Bit 5: OTG interrupt line status */
+#define SYSCON_USBINTST_I2CINT (1 << 6) /* Bit 6: I2C module interrupt line status */
+ /* Bit 7: Reserved */
+#define SYSCON_USBINTST_NEEDCLK (1 << 8) /* Bit 8: USB need clock indicator */
+ /* Bits 9-30: Reserved */
+#define SYSCON_USBINTST_ENINTS (1 << 31) /* Bit 31: Enable all USB interrupts */
+
+/* DMA Request Select Register */
+
+#define SYSCON_DMAREQSEL_INP0 (1 << 0) /* Bit 0: Input 0 0=unused 1=Timer 0 match 0 */
+#define SYSCON_DMAREQSEL_INP1 (1 << 1) /* Bit 1: Input 1 0=SD 1=Timer 0 match 1 */
+#define SYSCON_DMAREQSEL_INP2 (1 << 2) /* Bit 2: Input 2 0=SSP0 TX 1=Timer 1 match 0 */
+#define SYSCON_DMAREQSEL_INP3 (1 << 3) /* Bit 3: Input 3 0=SSP0 RX 1=Timer 1 match 1 */
+#define SYSCON_DMAREQSEL_INP4 (1 << 4) /* Bit 4: Input 4 0=SSP1 TX 1=Timer 2 match 0 */
+#define SYSCON_DMAREQSEL_INP5 (1 << 5) /* Bit 5: Input 5 0=SSP1 RX 1=Timer 2 match 1 */
+#define SYSCON_DMAREQSEL_INP6 (1 << 6) /* Bit 6: Input 6 0=SSP2 TX 1=I2S0 */
+#define SYSCON_DMAREQSEL_INP7 (1 << 7) /* Bit 7: Input 7 0=SSP2 RX 1=I2S1 */
+ /* Bits 8-9: Reserved */
+#define SYSCON_DMAREQSEL_INP10 (1 << 10) /* Bit 10: Input 10 0=UART0 TX 1=UART3 TX */
+#define SYSCON_DMAREQSEL_INP11 (1 << 11) /* Bit 11: Input 11 0=UART0 RX 1=UART3 RX */
+#define SYSCON_DMAREQSEL_INP12 (1 << 12) /* Bit 12: Input 12 0=UART1 TX 1=UART4 TX */
+#define SYSCON_DMAREQSEL_INP13 (1 << 13) /* Bit 13: Input 13 0=UART1 RX 1=UART4 RX */
+#define SYSCON_DMAREQSEL_INP14 (1 << 14) /* Bit 14: Input 14 0=UART2 TX 1=Timer 3 match 0 */
+#define SYSCON_DMAREQSEL_INP15 (1 << 15) /* Bit 15: Input 15 0=UART2 RX 1=Timer 3 match 1 */
+ /* Bits 16-31: Reserved */
+/* Reset Control Register 0 */
+
+#define SYSCON_RSTCON0_RSTLCD (1 << 0) /* LCD controller reset control bit */
+#define SYSCON_RSTCON0_RSTTIM0 (1 << 1) /* Timer/Counter 0 reset control bit */
+#define SYSCON_RSTCON0_RSTTIM1 (1 << 2) /* Timer/Counter 1 reset control bit */
+#define SYSCON_RSTCON0_RSTUART0 (1 << 3) /* UART0 reset control bit */
+#define SYSCON_RSTCON0_RSTUART1 (1 << 4) /* UART1 reset control bit */
+#define SYSCON_RSTCON0_RSTPWM0 (1 << 5) /* PWM0 reset control bit */
+#define SYSCON_RSTCON0_RSTPWM1 (1 << 6) /* PWM1 reset control bit */
+#define SYSCON_RSTCON0_RSTI2C0 (1 << 7) /* The I2C0 interface reset control bit */
+#define SYSCON_RSTCON0_RSTUART4 (1 << 8) /* UART4 reset control bit */
+#define SYSCON_RSTCON0_RSTRTC (1 << 9) /* RTC and Event Monitor/Recorder reset control bit. RTC reset is limited */
+#define SYSCON_RSTCON0_RSTSSP1 (1 << 10) /* The SSP 1 interface reset control bit */
+#define SYSCON_RSTCON0_RSTEMC (1 << 11) /* External Memory Controller reset control bit */
+#define SYSCON_RSTCON0_RSTADC (1 << 12) /* A/D converter (ADC) reset control bit */
+#define SYSCON_RSTCON0_RSTCAN1 (1 << 13) /* CAN Controller 1 reset control bit */
+ /* Note: The CAN acceptance filter may be reset by 0
+ * a separate bit in the RSTCON1 register. */
+#define SYSCON_RSTCON0_RSTCAN2 (1 << 14) /* CAN Controller 2 reset control bit */
+ /* Note: The CAN acceptance filter may be reset by 0
+ * a separate bit in the RSTCON1 register */
+#define SYSCON_RSTCON0_RSTGPIO (1 << 15) /* Reset control bit for GPIO, and GPIO interrupts */
+ /* Note: IOCON may be reset by a 0
+ * separate bit in the RSTCON1 register */
+#define SYSCON_RSTCON0_RSTSPIFI (1 << 16) /* SPI Flash Interface reset control bit (LPC1773 only) */
+#define SYSCON_RSTCON0_RSTMCPWM (1 << 17) /* Motor Control PWM reset control bit */
+#define SYSCON_RSTCON0_RSTQEI (1 << 18) /* Quadrature Encoder Interface reset control bit */
+#define SYSCON_RSTCON0_RSTI2C1 (1 << 19) /* The I2C1 interface reset control bit */
+#define SYSCON_RSTCON0_RSTSSP2 (1 << 20) /* The SSP2 interface reset control bit */
+#define SYSCON_RSTCON0_RSTSSP0 (1 << 21) /* The SSP0 interface reset control bit */
+#define SYSCON_RSTCON0_RSTTIM2 (1 << 22) /* Timer 2 reset control bit */
+#define SYSCON_RSTCON0_RSTTIM3 (1 << 23) /* Timer 3 reset control bit */
+#define SYSCON_RSTCON0_RSTUART2 (1 << 24) /* UART 2 reset control bit */
+#define SYSCON_RSTCON0_RSTUART3 (1 << 25) /* UART 3 reset control bit */
+#define SYSCON_RSTCON0_RSTI2C2 (1 << 26) /* I2C2 interface reset control bit.*/
+#define SYSCON_RSTCON0_RSTI2S (1 << 27) /* I2S interface reset control bit */
+#define SYSCON_RSTCON0_RSTSDC (1 << 28) /* SD Card interface reset control bit */
+#define SYSCON_RSTCON0_RSTGPDMA (1 << 29) /* GPDMA function reset control bit */
+
+#define SYSCON_RSTCON0_RSTENET (1 << 30) /* Ethernet block reset control bit */
+#define SYSCON_RSTCON0_RSTUSB (1 << 31) /* USB interface reset control bit */
+
+/* Reset Control Register 1 */
+
+#define SYSCON_RSTCON1_RSTIOCON (1 << 0) /* Reset control bit for the IOCON registers */
+#define SYSCON_RSTCON1_RSTDAC (1 << 1) /* D/A converter (DAC) reset control bit */
+#define SYSCON_RSTCON1_RSTCANACC (1 << 2) /* CAN acceptance filter reset control bit */
+ /* Bits 3-31: Reserved */
+/* Delay Control Register - EMC */
+ /* Delay values multiplied by 250 picoseconds */
+#define SYSCON_EMCDLYCTL_CMDDLY_SHIFT (0) /* Bits 0-4: Delay value for EMC outputs in command delayed mode */
+#define SYSCON_EMCDLYCTL_CMDDLY_MASK (0x1f << SYSCON_EMCDLYCTL_CMDDLY_SHIFT)
+# define SYSCON_EMCDLYCTL_CMDDLY(n) ((n+1) << SYSCON_EMCDLYCTL_CMDDLY_SHIFT) /* n = 2 - 31 */
+ /* Bits 5-7: Reserved */
+#define SYSCON_EMCDLYCTL_FBCLKDLY_SHIFT (8) /* Bits 8-12: Delay value for the feedback clock that controls input data sampling */
+#define SYSCON_EMCDLYCTL_FBCLKDLY_MASK (0x1f << SYSCON_EMCDLYCTL_FBCLKDLY_SHIFT)
+#define SYSCON_EMCDLYCTL_FBCLKDLY(n) ((n+1)<< SYSCON_EMCDLYCTL_FBCLKDLY_SHIFT) /* n = 2 - 31 */
+ /* Bits 13-15: Reserved */
+#define SYSCON_EMCDLYCTL_CLKOUT0DLY_SHIFT (16) /* Bits 16-20: Delay value for the CLKOUT0 output */
+#define SYSCON_EMCDLYCTL_CLKOUT0DLY_MASK (0x1f << SYSCON_EMCDLYCTL_CLKOUT0DLY_SHIFT)
+# define SYSCON_EMCDLYCTL_CLKOUT0DLY(n) ((n+1) << SYSCON_EMCDLYCTL_CLKOUT0DLY_SHIFT) /* n = 2 - 31 */
+ /* Bits 21-23: Reserved */
+#define SYSCON_EMCDLYCTL_CLKOUT1DLY_SHIFT (24) /* Bits 24-28: Delay value for the CLKOUT1 output */
+#define SYSCON_EMCDLYCTL_CLKOUT1DLY_MASK (0x1f << SYSCON_EMCDLYCTL_CLKOUT1DLY_SHIFT)
+# define SYSCON_EMCDLYCTL_CLKOUT1DLY(n) ((n+1) << SYSCON_EMCDLYCTL_CLKOUT1DLY_SHIFT) /* n = 2 - 31 */
+ /* Bits 29-31: Reserved */
+/* Calibration Register - EMC */
+
+#define SYSCON_EMCCAL_CALVALUE_SHIFT (0) /* Bits 0-7: Ring oscillator count during 32 clocks of Internal RC */
+#define SYSCON_EMCCAL_CALVALUE_MASK (0xff << SYSCON_EMCCAL_CALVALUE_SHIFT)
+//~ #define SYSCON_EMCCAL_CALVALUE
+ /* Bits 8-13: Reserved */
+#define SYSCON_EMCCAL_START_SHIFT (14) /* Bit 14: Start control bit for EMC calibration counter */
+#define SYSCON_EMCCAL_START_MASK (1 << SYSCON_EMCCAL_START_SHIFT)
+# define SYSCON_EMCCAL_START (1) /* Automatically cleared when measurement is done */
+#define SYSCON_EMCCAL_DONE_SHIFT (15) /* Bit 15: Measurement completetion flag bit */
+#define SYSCON_EMCCAL_DONE_MASK (1 << SYSCON_EMCCAL_DONE_SHIFT)
+ /* Automatically cleared when START bit is set */
+//~ # define SYSCON_EMCCAL_DONE
+ /* Bits 16-31: Reserved */
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public Data
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC17XX_CHIP_LPC178X_SYSCON_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpio.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpio.h
index 20b4ae380..aa5c0f57b 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpio.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_gpio.h
@@ -57,6 +57,9 @@
#define LPC17_FIO2_OFFSET 0x0040
#define LPC17_FIO3_OFFSET 0x0060
#define LPC17_FIO4_OFFSET 0x0080
+#ifdef LPC178x
+# define LPC17_FIO5_OFFSET 0x00a0
+#endif
#define LPC17_FIO_DIR_OFFSET 0x0000 /* Fast GPIO Port Direction control */
#define LPC17_FIO_MASK_OFFSET 0x0010 /* Fast Mask register for ports */
@@ -86,6 +89,9 @@
#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)
+#ifdef LPC178x
+# define LPC17_FIO5_BASE (LPC17_GPIO_BASE+LPC17_FIO5_OFFSET)
+#endif
#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)
@@ -123,6 +129,14 @@
#define LPC17_FIO4_SET (LPC17_FIO4_BASE+LPC17_FIO_SET_OFFSET)
#define LPC17_FIO4_CLR (LPC17_FIO4_BASE+LPC17_FIO_CLR_OFFSET)
+#ifdef LPC178x
+# define LPC17_FIO5_DIR (LPC17_FIO5_BASE+LPC17_FIO_DIR_OFFSET)
+# define LPC17_FIO5_MASK (LPC17_FIO5_BASE+LPC17_FIO_MASK_OFFSET)
+# define LPC17_FIO5_PIN (LPC17_FIO5_BASE+LPC17_FIO_PIN_OFFSET)
+# define LPC17_FIO5_SET (LPC17_FIO5_BASE+LPC17_FIO_SET_OFFSET)
+# define LPC17_FIO5_CLR (LPC17_FIO5_BASE+LPC17_FIO_CLR_OFFSET)
+#endif
+
/* GPIO interrupt block register addresses ******************************************/
#define LPC17_GPIOINTn_BASE(n) (LPC17_GPIOINT_BASE+LPC17_GPIOINT_OFFSET(n))
@@ -137,7 +151,7 @@
#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) */
+/* Pins P0.0-31 */
#define LPC17_GPIOINT0_INTSTATR (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTSTATR_OFFSET)
#define LPC17_GPIOINT0_INTSTATF (LPC17_GPIOINT0_BASE+LPC17_GPIOINT_INTSTATF_OFFSET)
@@ -145,7 +159,7 @@
#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) */
+/* Pins P2.0-31 */
#define LPC17_GPIOINT2_INTSTATR (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTSTATR_OFFSET)
#define LPC17_GPIOINT2_INTSTATF (LPC17_GPIOINT2_BASE+LPC17_GPIOINT_INTSTATF_OFFSET)
@@ -189,105 +203,8 @@
* 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_syscon.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_syscon.h
index 15be1e672..ebe39cb72 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_syscon.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_syscon.h
@@ -42,443 +42,20 @@
#include <nuttx/config.h>
-#include "chip.h"
-#include "chip/lpc17_memorymap.h"
+#include <arch/lpc17xx/chip.h>
+
+#if defined(LPC176x)
+# include "chip/lpc176x_syscon.h"
+#elif defined(LPC178x)
+# include "chip/lpc178x_syscon.h"
+#else
+# error "Unrecognized LPC17xx family"
+#endif
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-/* Flash accelerator module */
-
-#define LPC17_SYSCON_FLASHCFG_OFFSET 0x0000 /* Flash Accelerator Configuration Register */
-
-/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
-
-#define LPC17_SYSCON_MEMMAP_OFFSET 0x0040 /* Memory Mapping Control register */
-
-/* Clocking and power control - Phase locked loops */
-
-#define LPC17_SYSCON_PLL0CON_OFFSET 0x0080 /* PLL0 Control Register */
-#define LPC17_SYSCON_PLL0CFG_OFFSET 0x0084 /* PLL0 Configuration Register */
-#define LPC17_SYSCON_PLL0STAT_OFFSET 0x0088 /* PLL0 Status Register */
-#define LPC17_SYSCON_PLL0FEED_OFFSET 0x008c /* PLL0 Feed Register */
-
-#define LPC17_SYSCON_PLL1CON_OFFSET 0x00a0 /* PLL1 Control Register */
-#define LPC17_SYSCON_PLL1CFG_OFFSET 0x00a4 /* PLL1 Configuration Register */
-#define LPC17_SYSCON_PLL1STAT_OFFSET 0x00a8 /* PLL1 Status Register */
-#define LPC17_SYSCON_PLL1FEED_OFFSET 0x00ac /* PLL1 Feed Register */
-
-/* Clocking and power control - Peripheral power control registers */
-
-#define LPC17_SYSCON_PCON_OFFSET 0x00c0 /* Power Control Register */
-#define LPC17_SYSCON_PCONP_OFFSET 0x00c4 /* Power Control for Peripherals Register */
-
-/* Clocking and power control -- Clock dividers */
-
-#define LPC17_SYSCON_CCLKCFG_OFFSET 0x0104 /* CPU Clock Configuration Register */
-#define LPC17_SYSCON_USBCLKCFG_OFFSET 0x0108 /* USB Clock Configuration Register */
-
-/* 0x400f c110 - 0x400f c114: CAN Wake and Sleep Registers */
-
-/* Clocking and power control -- Clock source selection */
-
-#define LPC17_SYSCON_CLKSRCSEL_OFFSET 0x010c /* Clock Source Select Register */
-
-/* System control registers -- External Interrupts */
-
-#define LPC17_SYSCON_EXTINT_OFFSET 0x0140 /* External Interrupt Flag Register */
-
-#define LPC17_SYSCON_EXTMODE_OFFSET 0x0148 /* External Interrupt Mode register */
-#define LPC17_SYSCON_EXTPOLAR_OFFSET 0x014c /* External Interrupt Polarity Register */
-
-/* System control registers -- Reset */
-
-#define LPC17_SYSCON_RSID_OFFSET 0x0180 /* Reset Source Identification Register */
-
-/* System control registers -- Syscon Miscellaneous Registers */
-
-#define LPC17_SYSCON_SCS_OFFSET 0x01a0 /* System Control and Status */
-
-/* More clocking and power control -- Clock dividers */
-
-#define LPC17_SYSCON_PCLKSEL0_OFFSET 0x01a8 /* Peripheral Clock Selection register 0 */
-#define LPC17_SYSCON_PCLKSEL1_OFFSET 0x01ac /* Peripheral Clock Selection register 1 */
-
-/* Device Interrupt Registers (Might be a error in the User Manual, might be at 0x5000c1c0) */
-
-#define LPC17_SYSCON_USBINTST_OFFSET 0x01c0 /* USB Interrupt Status */
-
-/* DMA Request Select Register */
-
-#define LPC17_SYSCON_DMAREQSEL_OFFSET 0x01c4 /* Selects between UART and timer DMA requests */
-
-/* More clocking and power control -- Utility */
-
-#define LPC17_SYSCON_CLKOUTCFG_OFFSET 0x01c8 /* Clock Output Configuration Register */
-
-/* Register addresses ***************************************************************/
-/* Flash accelerator module */
-
-#define LPC17_SYSCON_FLASHCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_FLASHCFG_OFFSET)
-
-/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
-
-#define LPC17_SYSCON_MEMMAP (LPC17_SYSCON_BASE+LPC17_SYSCON_MEMMAP_OFFSET)
-
-/* Clocking and power control - Phase locked loops */
-
-#define LPC17_SYSCON_PLL0CON (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0CON_OFFSET)
-#define LPC17_SYSCON_PLL0CFG (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0CFG_OFFSET)
-#define LPC17_SYSCON_PLL0STAT (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0STAT_OFFSET)
-#define LPC17_SYSCON_PLL0FEED (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL0FEED_OFFSET)
-
-#define LPC17_SYSCON_PLL1CON (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1CON_OFFSET)
-#define LPC17_SYSCON_PLL1CFG (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1CFG_OFFSET)
-#define LPC17_SYSCON_PLL1STAT (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1STAT_OFFSET)
-#define LPC17_SYSCON_PLL1FEED (LPC17_SYSCON_BASE+LPC17_SYSCON_PLL1FEED_OFFSET)
-
-/* Clocking and power control - Peripheral power control registers */
-
-#define LPC17_SYSCON_PCON (LPC17_SYSCON_BASE+LPC17_SYSCON_PCON_OFFSET)
-#define LPC17_SYSCON_PCONP (LPC17_SYSCON_BASE+LPC17_SYSCON_PCONP_OFFSET)
-
-/* Clocking and power control -- Clock dividers */
-
-#define LPC17_SYSCON_CCLKCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_CCLKCFG_OFFSET)
-#define LPC17_SYSCON_USBCLKCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_USBCLKCFG_OFFSET)
-
-/* 0x400f c110 - 0x400f c114: CAN Wake and Sleep Registers */
-
-/* Clocking and power control -- Clock source selection */
-
-#define LPC17_SYSCON_CLKSRCSEL (LPC17_SYSCON_BASE+LPC17_SYSCON_CLKSRCSEL_OFFSET)
-
-/* System control registers -- External Interrupts */
-
-#define LPC17_SYSCON_EXTINT (LPC17_SYSCON_BASE+LPC17_SYSCON_EXTINT_OFFSET)
-
-#define LPC17_SYSCON_EXTMODE (LPC17_SYSCON_BASE+LPC17_SYSCON_EXTMODE_OFFSET)
-#define LPC17_SYSCON_EXTPOLAR (LPC17_SYSCON_BASE+LPC17_SYSCON_EXTPOLAR_OFFSET)
-
-/* System control registers -- Reset */
-
-#define LPC17_SYSCON_RSID (LPC17_SYSCON_BASE+LPC17_SYSCON_RSID_OFFSET)
-
-/* System control registers -- Syscon Miscellaneous Registers */
-
-#define LPC17_SYSCON_SCS (LPC17_SYSCON_BASE+LPC17_SYSCON_SCS_OFFSET)
-
-/* More clocking and power control -- Clock dividers */
-
-#define LPC17_SYSCON_PCLKSEL0 (LPC17_SYSCON_BASE+LPC17_SYSCON_PCLKSEL0_OFFSET)
-#define LPC17_SYSCON_PCLKSEL1 (LPC17_SYSCON_BASE+LPC17_SYSCON_PCLKSEL1_OFFSET)
-
-/* Device Interrupt Registers (Might be a error in the User Manual, might be at 0x5000c1c0) */
-
-#define LPC17_SYSCON_USBINTST (LPC17_SYSCON_BASE+LPC17_SYSCON_USBINTST_OFFSET)
-
-/* DMA Request Select Register */
-
-#define LPC17_SYSCON_DMAREQSEL (LPC17_SYSCON_BASE+LPC17_SYSCON_DMAREQSEL_OFFSET)
-
-/* More clocking and power control -- Utility */
-
-#define LPC17_SYSCON_CLKOUTCFG (LPC17_SYSCON_BASE+LPC17_SYSCON_CLKOUTCFG_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* Flash accelerator module */
- /* Bits 0-11: Reserved */
-#define SYSCON_FLASHCFG_TIM_SHIFT (12) /* Bits 12-15: FLASHTIM Flash access time */
-#define SYSCON_FLASHCFG_TIM_MASK (15 << SYSCON_FLASHCFG_TIM_SHIFT)
-# define SYSCON_FLASHCFG_TIM_1 (0 << SYSCON_FLASHCFG_TIM_SHIFT) /* 1 CPU clock <= 20 MHz CPU clock */
-# define SYSCON_FLASHCFG_TIM_2 (1 << SYSCON_FLASHCFG_TIM_SHIFT) /* 2 CPU clock <= 40 MHz CPU clock */
-# define SYSCON_FLASHCFG_TIM_3 (2 << SYSCON_FLASHCFG_TIM_SHIFT) /* 3 CPU clock <= 60 MHz CPU clock */
-# define SYSCON_FLASHCFG_TIM_4 (3 << SYSCON_FLASHCFG_TIM_SHIFT) /* 4 CPU clock <= 80 MHz CPU clock */
-# define SYSCON_FLASHCFG_TIM_5 (4 << SYSCON_FLASHCFG_TIM_SHIFT) /* 5 CPU clock <= 100 MHz CPU clock
- * (Up to 120 Mhz for LPC1759/69 only */
-# define SYSCON_FLASHCFG_TIM_6 (5 << SYSCON_FLASHCFG_TIM_SHIFT) /* "safe" setting for any conditions */
- /* Bits 16-31: Reserved */
-
-/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
-
-#define SYSCON_MEMMAP_MAP (1 << 0) /* Bit 0:
- * 0:Boot mode. A portion of the Boot ROM is mapped to address 0.
- * 1:User mode. The on-chip Flash memory is mapped to address 0 */
- /* Bits 1-31: Reserved */
-
-/* Clocking and power control -- Clock source selection */
-
-#define SYSCON_CLKSRCSEL_SHIFT (0) /* Bits 0-1: Clock selection */
-#define SYSCON_CLKSRCSEL_MASK (3 << SYSCON_CLKSRCSEL_SHIFT)
-# define SYSCON_CLKSRCSEL_INTRC (0 << SYSCON_CLKSRCSEL_SHIFT) /* PLL0 source = internal RC oscillator */
-# define SYSCON_CLKSRCSEL_MAIN (1 << SYSCON_CLKSRCSEL_SHIFT) /* PLL0 source = main oscillator */
-# define SYSCON_CLKSRCSEL_RTC (2 << SYSCON_CLKSRCSEL_SHIFT) /* PLL0 source = RTC oscillator */
- /* Bits 2-31: Reserved */
-
-/* Clocking and power control - Phase locked loops */
-/* PLL0/1 Control register */
-
-#define SYSCON_PLLCON_PLLE (1 << 0) /* Bit 0: PLL0/1 Enable */
-#define SYSCON_PLLCON_PLLC (1 << 1) /* Bit 1: PLL0/1 Connect */
- /* Bits 2-31: Reserved */
-/* PLL0 Configuration register */
-
-#define SYSCON_PLL0CFG_MSEL_SHIFT (0) /* Bit 0-14: PLL0 Multiplier value */
-#define SYSCON_PLL0CFG_MSEL_MASK (0x7fff << SYSCON_PLL0CFG_MSEL_SHIFT)
- /* Bit 15: Reserved */
-#define SYSCON_PLL0CFG_NSEL_SHIFT (16) /* Bit 16-23: PLL0 Pre-Divider value */
-#define SYSCON_PLL0CFG_NSEL_MASK (0xff << SYSCON_PLL0CFG_NSEL_SHIFT)
- /* Bits 24-31: Reserved */
-/* PLL1 Configuration register */
-
-#define SYSCON_PLL1CFG_MSEL_SHIFT (0) /* Bit 0-4: PLL1 Multiplier value */
-#define SYSCON_PLL1CFG_MSEL_MASK (0x1f < SYSCON_PLL1CFG_MSEL_SHIFT)
-#define SYSCON_PLL1CFG_NSEL_SHIFT (5) /* Bit 5-6: PLL1 Pre-Divider value */
-#define SYSCON_PLL1CFG_NSEL_MASK (3 << SYSCON_PLL1CFG_NSEL_SHIFT)
- /* Bits 7-31: Reserved */
-/* PLL0 Status register */
-
-#define SYSCON_PLL0STAT_MSEL_SHIFT (0) /* Bit 0-14: PLL0 Multiplier value readback */
-#define SYSCON_PLL0STAT_MSEL_MASK (0x7fff << SYSCON_PLL0STAT_MSEL_SHIFT)
- /* Bit 15: Reserved */
-#define SYSCON_PLL0STAT_NSEL_SHIFT (16) /* Bit 16-23: PLL0 Pre-Divider value readback */
-#define SYSCON_PLL0STAT_NSEL_MASK (0xff << SYSCON_PLL0STAT_NSEL_SHIFT)
-#define SYSCON_PLL0STAT_PLLE (1 << 24) /* Bit 24: PLL0 enable readback */
-#define SYSCON_PLL0STAT_PLLC (1 << 25) /* Bit 25: PLL0 connect readback */
-#define SYSCON_PLL0STAT_PLOCK (1 << 26) /* Bit 26: PLL0 lock status */
- /* Bits 27-31: Reserved */
-/* PLL1 Status register */
-
-#define SYSCON_PLL1STAT_MSEL_SHIFT (0) /* Bit 0-4: PLL1 Multiplier value readback */
-#define SYSCON_PLL1STAT_MSEL_MASK (0x1f << SYSCON_PLL1STAT_MSEL_SHIFT)
-#define SYSCON_PLL1STAT_NSEL_SHIFT (5) /* Bit 5-6: PLL1 Pre-Divider value readback */
-#define SYSCON_PLL1STAT_NSEL_MASK (3 << SYSCON_PLL1STAT_NSEL_SHIFT)
- /* Bit 7: Reserved */
-#define SYSCON_PLL1STAT_PLLE (1 << 8) /* Bit 8: PLL1 enable readback */
-#define SYSCON_PLL1STAT_PLLC (1 << 9) /* Bit 9: PLL1 connect readback */
-#define SYSCON_PLL1STAT_PLOCK (1 << 10) /* Bit 10: PLL1 lock status */
- /* Bits 11-31: Reserved */
-/* PLL0/1 Feed register */
-
-#define SYSCON_PLLFEED_SHIFT (0) /* Bit 0-7: PLL0/1 feed sequence */
-#define SYSCON_PLLFEED_MASK (0xff << SYSCON_PLLFEED_SHIFT)
- /* Bits 8-31: Reserved */
-/* Clocking and power control -- Clock dividers */
-/* CPU Clock Configuration register */
-
-#define SYSCON_CCLKCFG_SHIFT (0) /* 0-7: Divide value for CPU clock (CCLK) */
-#define SYSCON_CCLKCFG_MASK (0xff << SYSCON_CCLKCFG_SHIFT)
-# define SYSCON_CCLKCFG_DIV(n) ((n-1) << SYSCON_CCLKCFG_SHIFT) /* n=2,3,..255 */
- /* Bits 8-31: Reserved */
-/* USB Clock Configuration register */
-
-#define SYSCON_USBCLKCFG_SHIFT (0) /* Bits 0-3: PLL0 divide value USB clock */
-#define SYSCON_USBCLKCFG_MASK (15 << SYSCON_USBCLKCFG_SHIFT)
-# define SYSCON_USBCLKCFG_DIV6 (5 << SYSCON_USBCLKCFG_SHIFT) /* PLL0/6 for PLL0=288 MHz */
-# define SYSCON_USBCLKCFG_DIV8 (7 << SYSCON_USBCLKCFG_SHIFT) /* PLL0/8 for PLL0=384 MHz */
-# define SYSCON_USBCLKCFG_DIV10 (9 << SYSCON_USBCLKCFG_SHIFT) /* PLL0/10 for PLL0=480 MHz */
- /* Bits 8-31: Reserved */
-/* Peripheral Clock Selection registers 0 and 1 */
-
-#define SYSCON_PCLKSEL_CCLK4 (0) /* PCLK_peripheral = CCLK/4 */
-#define SYSCON_PCLKSEL_CCLK (1) /* PCLK_peripheral = CCLK */
-#define SYSCON_PCLKSEL_CCLK2 (2) /* PCLK_peripheral = CCLK/2 */
-#define SYSCON_PCLKSEL_CCLK8 (3) /* PCLK_peripheral = CCLK/8 (except CAN1, CAN2, and CAN) */
-#define SYSCON_PCLKSEL_CCLK6 (3) /* PCLK_peripheral = CCLK/6 (CAN1, CAN2, and CAN) */
-#define SYSCON_PCLKSEL_MASK (3)
-
-#define SYSCON_PCLKSEL0_WDT_SHIFT (0) /* Bits 0-1: Peripheral clock WDT */
-#define SYSCON_PCLKSEL0_WDT_MASK (3 << SYSCON_PCLKSEL0_WDT_SHIFT)
-#define SYSCON_PCLKSEL0_TMR0_SHIFT (2) /* Bits 2-3: Peripheral clock TIMER0 */
-#define SYSCON_PCLKSEL0_TMR0_MASK (3 << SYSCON_PCLKSEL0_TMR0_SHIFT)
-#define SYSCON_PCLKSEL0_TMR1_SHIFT (4) /* Bits 4-5: Peripheral clock TIMER1 */
-#define SYSCON_PCLKSEL0_TMR1_MASK (3 << SYSCON_PCLKSEL0_TMR1_SHIFT)
-#define SYSCON_PCLKSEL0_UART0_SHIFT (6) /* Bits 6-7: Peripheral clock UART0 */
-#define SYSCON_PCLKSEL0_UART0_MASK (3 << SYSCON_PCLKSEL0_UART0_SHIFT)
-#define SYSCON_PCLKSEL0_UART1_SHIFT (8) /* Bits 8-9: Peripheral clock UART1 */
-#define SYSCON_PCLKSEL0_UART1_MASK (3 << SYSCON_PCLKSEL0_UART1_SHIFT)
- /* Bits 10-11: Reserved */
-#define SYSCON_PCLKSEL0_PWM1_SHIFT (12) /* Bits 12-13: Peripheral clock PWM1 */
-#define SYSCON_PCLKSEL0_PWM1_MASK (3 << SYSCON_PCLKSEL0_PWM1_SHIFT)
-#define SYSCON_PCLKSEL0_I2C0_SHIFT (14) /* Bits 14-15: Peripheral clock I2C0 */
-#define SYSCON_PCLKSEL0_I2C0_MASK (3 << SYSCON_PCLKSEL0_I2C0_SHIFT)
-#define SYSCON_PCLKSEL0_SPI_SHIFT (16) /* Bits 16-17: Peripheral clock SPI */
-#define SYSCON_PCLKSEL0_SPI_MASK (3 << SYSCON_PCLKSEL0_SPI_SHIFT)
- /* Bits 18-19: Reserved */
-#define SYSCON_PCLKSEL0_SSP1_SHIFT (20) /* Bits 20-21: Peripheral clock SSP1 */
-#define SYSCON_PCLKSEL0_SSP1_MASK (3 << SYSCON_PCLKSEL0_SSP1_SHIFT)
-#define SYSCON_PCLKSEL0_DAC_SHIFT (22) /* Bits 22-23: Peripheral clock DAC */
-#define SYSCON_PCLKSEL0_DAC_MASK (3 << SYSCON_PCLKSEL0_DAC_SHIFT)
-#define SYSCON_PCLKSEL0_ADC_SHIFT (24) /* Bits 24-25: Peripheral clock ADC */
-#define SYSCON_PCLKSEL0_ADC_MASK (3 << SYSCON_PCLKSEL0_ADC_SHIFT)
-#define SYSCON_PCLKSEL0_CAN1_SHIFT (26) /* Bits 26-27: Peripheral clock CAN1 */
-#define SYSCON_PCLKSEL0_CAN1_MASK (3 << SYSCON_PCLKSEL0_CAN1_SHIFT)
-#define SYSCON_PCLKSEL0_CAN2_SHIFT (28) /* Bits 28-29: Peripheral clock CAN2 */
-#define SYSCON_PCLKSEL0_CAN2_MASK (3 << SYSCON_PCLKSEL0_CAN2_SHIFT)
-#define SYSCON_PCLKSEL0_ACF_SHIFT (30) /* Bits 30-31: Peripheral clock CAN AF */
-#define SYSCON_PCLKSEL0_ACF_MASK (3 << SYSCON_PCLKSEL0_ACF_SHIFT)
-
-#define SYSCON_PCLKSEL1_QEI_SHIFT (0) /* Bits 0-1: Peripheral clock Quadrature Encoder */
-#define SYSCON_PCLKSEL1_QEI_MASK (3 << SYSCON_PCLKSEL1_QEI_SHIFT)
-#define SYSCON_PCLKSEL1_GPIOINT_SHIFT (2) /* Bits 2-3: Peripheral clock GPIO interrupts */
-#define SYSCON_PCLKSEL1_GPIOINT_MASK (3 << SYSCON_PCLKSEL1_GPIOINT_SHIFT)
-#define SYSCON_PCLKSEL1_PCB_SHIFT (4) /* Bits 4-5: Peripheral clock the Pin Connect block */
-#define SYSCON_PCLKSEL1_PCB_MASK (3 << SYSCON_PCLKSEL1_PCB_SHIFT)
-#define SYSCON_PCLKSEL1_I2C1_SHIFT (6) /* Bits 6-7: Peripheral clock I2C1 */
-#define SYSCON_PCLKSEL1_I2C1_MASK (3 << SYSCON_PCLKSEL1_I2C1_SHIFT)
- /* Bits 8-9: Reserved */
-#define SYSCON_PCLKSEL1_SSP0_SHIFT (10) /* Bits 10-11: Peripheral clock SSP0 */
-#define SYSCON_PCLKSEL1_SSP0_MASK (3 << SYSCON_PCLKSEL1_SSP0_SHIFT)
-#define SYSCON_PCLKSEL1_TMR2_SHIFT (12) /* Bits 12-13: Peripheral clock TIMER2 */
-#define SYSCON_PCLKSEL1_TMR2_MASK (3 << SYSCON_PCLKSEL1_TMR2_SHIFT)
-#define SYSCON_PCLKSEL1_TMR3_SHIFT (14) /* Bits 14-15: Peripheral clock TIMER3 */
-#define SYSCON_PCLKSEL1_TMR3_MASK (3 << SYSCON_PCLKSEL1_TMR3_SHIFT)
-#define SYSCON_PCLKSEL1_UART2_SHIFT (16) /* Bits 16-17: Peripheral clock UART2 */
-#define SYSCON_PCLKSEL1_UART2_MASK (3 << SYSCON_PCLKSEL1_UART2_SHIFT)
-#define SYSCON_PCLKSEL1_UART3_SHIFT (18) /* Bits 18-19: Peripheral clock UART3 */
-#define SYSCON_PCLKSEL1_UART3_MASK (3 << SYSCON_PCLKSEL1_UART3_SHIFT)
-#define SYSCON_PCLKSEL1_I2C2_SHIFT (20) /* Bits 20-21: Peripheral clock I2C2 */
-#define SYSCON_PCLKSEL1_I2C2_MASK (3 << SYSCON_PCLKSEL1_I2C2_SHIFT)
-#define SYSCON_PCLKSEL1_I2S_SHIFT (22) /* Bits 22-23: Peripheral clock I2S */
-#define SYSCON_PCLKSEL1_I2S_MASK (3 << SYSCON_PCLKSEL1_I2S_SHIFT)
- /* Bits 24-25: Reserved */
-#define SYSCON_PCLKSEL1_RIT_SHIFT (26) /* Bits 26-27: Peripheral clock Repetitive Interrupt Timer */
-#define SYSCON_PCLKSEL1_RIT_MASK (3 << SYSCON_PCLKSEL1_RIT_SHIFT)
-#define SYSCON_PCLKSEL1_SYSCON_SHIFT (28) /* Bits 28-29: Peripheral clock the System Control block */
-#define SYSCON_PCLKSEL1_SYSCON_MASK (3 << SYSCON_PCLKSEL1_SYSCON_SHIFT)
-#define SYSCON_PCLKSEL1_MC_SHIFT (30) /* Bits 30-31: Peripheral clock the Motor Control PWM */
-#define SYSCON_PCLKSEL1_MC_MASK (3 << SYSCON_PCLKSEL1_MC_SHIFT)
-
-/* Clocking and power control - Peripheral power control registers */
-/* Power Control Register */
-
-#define SYSCON_PCON_PM0 (1 << 0) /* Bit 0: Power mode control bit 0 */
-#define SYSCON_PCON_PM1 (1 << 1) /* Bit 1: Power mode control bit 1 */
-#define SYSCON_PCON_BODRPM (1 << 2) /* Bit 2: Brown-Out Reduced Power Mode */
-#define SYSCON_PCON_BOGD (1 << 3) /* Bit 3: Brown-Out Global Disable */
-#define SYSCON_PCON_BORD (1 << 4) /* Bit 4: Brown-Out Reset Disable */
- /* Bits 5-7: Reserved */
-#define SYSCON_PCON_SMFLAG (1 << 8) /* Bit 8: Sleep Mode entry flag */
-#define SYSCON_PCON_DSFLAG (1 << 9) /* Bit 9: Deep Sleep entry flag */
-#define SYSCON_PCON_PDFLAG (1 << 10) /* Bit 10: Power-down entry flag */
-#define SYSCON_PCON_DPDFLAG (1 << 11) /* Bit 11: Deep Power-down entry flag */
- /* Bits 12-31: Reserved */
-/* Power Control for Peripherals Register */
-
- /* Bit 0: Reserved */
-#define SYSCON_PCONP_PCTIM0 (1 << 1) /* Bit 1: Timer/Counter 0 power/clock control */
-#define SYSCON_PCONP_PCTIM1 (1 << 2) /* Bit 2: Timer/Counter 1 power/clock control */
-#define SYSCON_PCONP_PCUART0 (1 << 3) /* Bit 3: UART0 power/clock control */
-#define SYSCON_PCONP_PCUART1 (1 << 4) /* Bit 4: UART1 power/clock control */
- /* Bit 5: Reserved */
-#define SYSCON_PCONP_PCPWM1 (1 << 6) /* Bit 6: PWM1 power/clock control */
-#define SYSCON_PCONP_PCI2C0 (1 << 7) /* Bit 7: I2C0 power/clock control */
-#define SYSCON_PCONP_PCSPI (1 << 8) /* Bit 8: SPI power/clock control */
-#define SYSCON_PCONP_PCRTC (1 << 9) /* Bit 9: RTC power/clock control */
-#define SYSCON_PCONP_PCSSP1 (1 << 10) /* Bit 10: SSP 1 power/clock control */
- /* Bit 11: Reserved */
-#define SYSCON_PCONP_PCADC (1 << 12) /* Bit 12: A/D converter (ADC) power/clock control */
-#define SYSCON_PCONP_PCCAN1 (1 << 13) /* Bit 13: CAN Controller 1 power/clock control */
-#define SYSCON_PCONP_PCCAN2 (1 << 14) /* Bit 14: CAN Controller 2 power/clock control */
-#define SYSCON_PCONP_PCGPIO (1 << 15) /* Bit 15: GPIOs power/clock enable */
-#define SYSCON_PCONP_PCRIT (1 << 16) /* Bit 16: Repetitive Interrupt Timer power/clock control */
-#define SYSCON_PCONP_PCMCPWM (1 << 17) /* Bit 17: Motor Control PWM */
-#define SYSCON_PCONP_PCQEI (1 << 18) /* Bit 18: Quadrature Encoder power/clock control */
-#define SYSCON_PCONP_PCI2C1 (1 << 19) /* Bit 19: I2C1 power/clock control */
- /* Bit 20: Reserved */
-#define SYSCON_PCONP_PCSSP0 (1 << 21) /* Bit 21: SSP0 power/clock control */
-#define SYSCON_PCONP_PCTIM2 (1 << 22) /* Bit 22: Timer 2 power/clock control */
-#define SYSCON_PCONP_PCTIM3 (1 << 23) /* Bit 23: Timer 3 power/clock control */
-#define SYSCON_PCONP_PCUART2 (1 << 24) /* Bit 24: UART 2 power/clock control */
-#define SYSCON_PCONP_PCUART3 (1 << 25) /* Bit 25: UART 3 power/clock control */
-#define SYSCON_PCONP_PCI2C2 (1 << 26) /* Bit 26: I2C 2 power/clock control */
-#define SYSCON_PCONP_PCI2S (1 << 27) /* Bit 27: I2S power/clock control */
- /* Bit 28: Reserved */
-#define SYSCON_PCONP_PCGPDMA (1 << 29) /* Bit 29: GPDMA function power/clock control */
-#define SYSCON_PCONP_PCENET (1 << 30) /* Bit 30: Ethernet block power/clock control */
-#define SYSCON_PCONP_PCUSB (1 << 31) /* Bit 31: USB power/clock control */
-
-/* More clocking and power control -- Utility */
-
-#define SYSCON_CLKOUTCFG_SEL_SHIFT (0) /* Bits 0-3: Selects clock source for CLKOUT */
-#define SYSCON_CLKOUTCFG_SEL_MASK (15 << SYSCON_CLKOUTCFG_SEL_SHIFT)
-# define SYSCON_CLKOUTCFG_SEL_CPU (0 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=CPU clock */
-# define SYSCON_CLKOUTCFG_SEL_MAIN (1 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=main osc */
-# define SYSCON_CLKOUTCFG_SEL_INTRC (2 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=internal RC osc */
-# define SYSCON_CLKOUTCFG_SEL_USB (3 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=USB clock */
-# define SYSCON_CLKOUTCFG_SEL_RTC (4 << SYSCON_CLKOUTCFG_SEL_SHIFT) /* CLKOUT source=RTC osc */
-#define SYSCON_CLKOUTCFG_DIV_SHIFT (4) /* Bits 4-7: CLKOUT divisor */
-#define SYSCON_CLKOUTCFG_DIV_MASK (15 << SYSCON_CLKOUTCFG_DIV_SHIFT)
-# define SYSCON_CLKOUTCFG_DIV(n) ((n-1) << SYSCON_CLKOUTCFG_DIV_SHIFT) /* n=1..16 */
-#define SYSCON_CLKOUTCFG_EN (1 << 8) /* Bit 8: CLKOUT enable control */
-#define SYSCON_CLKOUTCFG_ACT (1 << 9) /* Bit 9: CLKOUT activity indication */
- /* Bits 10-31: Reserved */
-/* System control registers -- External Interrupts */
-/* External Interrupt Flag register */
-
-#define SYSCON_EXTINT_EINT0 (1 << 0) /* Bit 0: EINT0 */
-#define SYSCON_EXTINT_EINT1 (1 << 1) /* Bit 1: EINT1 */
-#define SYSCON_EXTINT_EINT2 (1 << 2) /* Bit 2: EINT2 */
-#define SYSCON_EXTINT_EINT3 (1 << 3) /* Bit 3: EINT3 */
- /* Bits 4-31: Reserved */
-/* External Interrupt Mode register */
-
-#define SYSCON_EXTMODE_EINT0 (1 << 0) /* Bit 0: 1=EINT0 edge sensitive */
-#define SYSCON_EXTMODE_EINT1 (1 << 1) /* Bit 1: 1=EINT1 edge sensitive */
-#define SYSCON_EXTMODE_EINT2 (1 << 2) /* Bit 2: 1=EINT2 edge sensitive */
-#define SYSCON_EXTMODE_EINT3 (1 << 3) /* Bit 3: 1=EINT3 edge sensitive */
- /* Bits 4-31: Reserved */
-/* External Interrupt Polarity register */
-
-#define SYSCON_EXTPOLAR_EINT0 (1 << 0) /* Bit 0: 1=EINT0 high active/rising edge */
-#define SYSCON_EXTPOLAR_EINT1 (1 << 1) /* Bit 1: 1=EINT1 high active/rising edge */
-#define SYSCON_EXTPOLAR_EINT2 (1 << 2) /* Bit 2: 1=EINT2 high active/rising edge */
-#define SYSCON_EXTPOLAR_EINT3 (1 << 3) /* Bit 3: 1=EINT3 high active/rising edge */
- /* Bits 4-31: Reserved */
-/* System control registers -- Reset */
-/* Reset Source Identification Register */
-
-#define SYSCON_RSID_POR (1 << 0) /* Bit 0: Power on reset */
-#define SYSCON_RSID_EXTR (1 << 1) /* Bit 1: external RESET signal */
-#define SYSCON_RSID_WDTR (1 << 2) /* Bit 2: Watchdog Timer time out w/WDTRESET */
-#define SYSCON_RSID_BODR (1 << 3) /* Bit 3: Brown out detection */
- /* Bits 4-31: Reserved */
-/* System control registers -- Syscon Miscellaneous Registers */
-
- /* Bits 0-3: Reserved */
-#define SYSCON_SCS_OSCRANGE (1 << 4) /* Bit 4: Main oscillator range select */
-#define SYSCON_SCS_OSCEN (1 << 5) /* Bit 5: Main oscillator enable */
-#define SYSCON_SCS_OSCSTAT (1 << 6) /* Bit 6: Main oscillator status */
- /* Bits 7-31: Reserved */
-/* Device Interrupt Registers */
-/* USB Interrupt Status register */
-
-#define SYSCON_USBINTST_REQLP (1 << 0) /* Bit 0: Low priority interrupt line status */
-#define SYSCON_USBINTST_REQHP (1 << 1) /* Bit 1: High priority interrupt line status */
-#define SYSCON_USBINTST_REQDMA (1 << 2) /* Bit 2: DMA interrupt line status */
-#define SYSCON_USBINTST_HOSTINT (1 << 3) /* Bit 3: USB host interrupt line status */
-#define SYSCON_USBINTST_ATXINT (1 << 4) /* Bit 4: External ATX interrupt line status */
-#define SYSCON_USBINTST_OTGINT (1 << 5) /* Bit 5: OTG interrupt line status */
-#define SYSCON_USBINTST_I2CINT (1 << 6) /* Bit 6: I2C module interrupt line status */
- /* Bit 7: Reserved */
-#define SYSCON_USBINTST_NEEDCLK (1 << 8) /* Bit 8: USB need clock indicator */
- /* Bits 9-30: Reserved */
-#define SYSCON_USBINTST_ENINTS (1 << 31) /* Bit 31: Enable all USB interrupts */
-
-/* DMA Request Select Register */
-
-#define SYSCON_DMAREQSEL_INP8 (1 << 0) /* Bit 0: Input 8 0=UART0 TX 1=Timer 0 match 0 */
-#define SYSCON_DMAREQSEL_INP9 (1 << 1) /* Bit 1: Input 8 0=UART0 RX 1=Timer 0 match 1 */
-#define SYSCON_DMAREQSEL_INP10 (1 << 2) /* Bit 2: Input 8 0=UART1 TX 1=Timer 1 match 0 */
-#define SYSCON_DMAREQSEL_INP11 (1 << 3) /* Bit 3: Input 8 0=UART1 RX 1=Timer 1 match 1 */
-#define SYSCON_DMAREQSEL_INP12 (1 << 4) /* Bit 4: Input 8 0=UART2 TX 1=Timer 2 match 0 */
-#define SYSCON_DMAREQSEL_INP13 (1 << 5) /* Bit 5: Input 8 0=UART2 RX 1=Timer 2 match 1 */
-#define SYSCON_DMAREQSEL_INP14 (1 << 6) /* Bit 6: Input 8 0=UART3 TX 1=Timer 3 match 0 */
-#define SYSCON_DMAREQSEL_INP15 (1 << 7) /* Bit 7: Input 8 0=UART3 RX 1=Timer 3 match 1 */
- /* Bits 8-31: Reserved */
-
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
index 9db9b136b..73939a389 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
@@ -212,7 +212,7 @@ static int lpc17_pinsel(unsigned int port, unsigned int pin, unsigned int value)
*
****************************************************************************/
-static int lpc17_pullup(uint16_t cfgset, unsigned int port, unsigned int pin)
+static int lpc17_pullup(lpc17_pinset_t cfgset, unsigned int port, unsigned int pin)
{
const uint32_t *table;
uint32_t regaddr;
@@ -355,7 +355,7 @@ static void lpc17_clropendrain(unsigned int port, unsigned int pin)
*
****************************************************************************/
-static inline int lpc17_configinput(uint16_t cfgset, unsigned int port, unsigned int pin)
+static inline int lpc17_configinput(lpc17_pinset_t cfgset, unsigned int port, unsigned int pin)
{
uint32_t regval;
uint32_t fiobase;
@@ -419,7 +419,7 @@ static inline int lpc17_configinput(uint16_t cfgset, unsigned int port, unsigned
*
****************************************************************************/
-static inline int lpc17_configinterrupt(uint16_t cfgset, unsigned int port,
+static inline int lpc17_configinterrupt(lpc17_pinset_t cfgset, unsigned int port,
unsigned int pin)
{
/* First, configure the port as a generic input so that we have a known
@@ -445,7 +445,7 @@ static inline int lpc17_configinterrupt(uint16_t cfgset, unsigned int port,
*
****************************************************************************/
-static inline int lpc17_configoutput(uint16_t cfgset, unsigned int port,
+static inline int lpc17_configoutput(lpc17_pinset_t cfgset, unsigned int port,
unsigned int pin)
{
uint32_t fiobase;
@@ -494,7 +494,7 @@ static inline int lpc17_configoutput(uint16_t cfgset, unsigned int port,
*
****************************************************************************/
-static int lpc17_configalternate(uint16_t cfgset, unsigned int port,
+static int lpc17_configalternate(lpc17_pinset_t cfgset, unsigned int port,
unsigned int pin, uint32_t alt)
{
/* First, configure the port as an input so that we have a known
@@ -536,7 +536,7 @@ static int lpc17_configalternate(uint16_t cfgset, unsigned int port,
*
****************************************************************************/
-int lpc17_configgpio(uint16_t cfgset)
+int lpc17_configgpio(lpc17_pinset_t cfgset)
{
unsigned int port;
unsigned int pin;
@@ -597,7 +597,7 @@ int lpc17_configgpio(uint16_t cfgset)
*
****************************************************************************/
-void lpc17_gpiowrite(uint16_t pinset, bool value)
+void lpc17_gpiowrite(lpc17_pinset_t pinset, bool value)
{
uint32_t fiobase;
uint32_t offset;
@@ -637,7 +637,7 @@ void lpc17_gpiowrite(uint16_t pinset, bool value)
*
****************************************************************************/
-bool lpc17_gpioread(uint16_t pinset)
+bool lpc17_gpioread(lpc17_pinset_t pinset)
{
uint32_t fiobase;
unsigned int port;
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h
index dad14bc9e..f3a003255 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h
@@ -46,6 +46,8 @@
# include <stdint.h>
#endif
+#include <arch/lpc17xx/chip.h>
+
#include "chip/lpc17_gpio.h"
#include "chip/lpc17_pinconn.h"
#include "chip/lpc17_pinconfig.h"
@@ -55,6 +57,8 @@
************************************************************************************/
/* Bit-encoded input to lpc17_configgpio() ******************************************/
+#if defined(LPC176x)
+
/* Encoding: FFFx MMOV PPPN NNNN
*
* Pin Function: FFF
@@ -165,10 +169,153 @@
#define GPIO_PIN30 (30 << GPIO_PIN_SHIFT)
#define GPIO_PIN31 (31 << GPIO_PIN_SHIFT)
+#elif defined(LPC178x)
+
+/* Encoding: TT FFFF MMOV PPPN NNNN
+ Encoding: TTTT TTTT FFFF MMOV PPPN NNNN
+ */
+/* Encoding: FFFF MMOV PPPN NNNN
+ *
+ * Pin Function: FFFF
+ * 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: FFFF
+ * Only meaningful when the GPIO function is GPIO_PIN
+ */
+
+#define GPIO_FUNC_SHIFT (12) /* Bits 12-15: GPIO mode */
+#define GPIO_FUNC_MASK (15 << GPIO_FUNC_SHIFT)
+# define GPIO_INPUT (0 << GPIO_FUNC_SHIFT) /* 0000 GPIO input pin */
+# define GPIO_INTFE (1 << GPIO_FUNC_SHIFT) /* 0001 GPIO interrupt falling edge */
+# define GPIO_INTRE (2 << GPIO_FUNC_SHIFT) /* 0010 GPIO interrupt rising edge */
+# define GPIO_INTBOTH (3 << GPIO_FUNC_SHIFT) /* 0011 GPIO interrupt both edges */
+# define GPIO_OUTPUT (4 << GPIO_FUNC_SHIFT) /* 0100 GPIO outpout pin */
+# define GPIO_ALT1 (5 << GPIO_FUNC_SHIFT) /* 0101 Alternate function 1 */
+# define GPIO_ALT2 (6 << GPIO_FUNC_SHIFT) /* 0110 Alternate function 2 */
+# define GPIO_ALT3 (7 << GPIO_FUNC_SHIFT) /* 0111 Alternate function 3 */
+
+# define GPIO_ALT4 (8 << GPIO_FUNC_SHIFT) /* 1000 Alternate function 4 */
+# define GPIO_ALT5 (9 << GPIO_FUNC_SHIFT) /* 1001 Alternate function 5 */
+# define GPIO_ALT6 (10 << GPIO_FUNC_SHIFT) /* 1010 Alternate function 6 */
+# define GPIO_ALT7 (11 << GPIO_FUNC_SHIFT) /* 1011 Alternate function 7 */
+
+/* Options for each IOCON Types */
+//~ #define GPIO_TYPE_SHIFT (16)
+//~ #define GPIO_TYPE_MASK (3 << GPIO_TYPE_SHIFT)
+//~ # define GPIO_HYSTERIS (<< 0 << )
+//~ # define GPIO_INVERTED (<< 1 << )
+//~ # define GPIO_SLEW (<< 2 << )
+//~ # define GPIO_ADMODE (<< 3 << )
+//~ # define GPIO_FILTER (<< 4 << )
+//~ # define GPIO_DACEN (<< 5 << )
+//~ # define GPIO_I2CHS (<< 6 << )
+//~ # define GPIO_HIDRIVE (<< 7 << )
+
+#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-5) */
+
+#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_PORT5 (5 << GPIO_PORT_SHIFT)
+
+#define GPIO_NPORTS 6
+
+/* 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)
+
+#else
+# error "Unrecognized LPC17xx family"
+#endif
+
/************************************************************************************
* Public Types
************************************************************************************/
+#ifdef LPC176x
+typedef uint16_t lpc17_pinset_t;
+#else
+typedef uint32_t lpc17_pinset_t;
+#endif
+
/************************************************************************************
* Public Data
************************************************************************************/
@@ -204,6 +351,92 @@ EXTERN const uint32_t g_odmode[GPIO_NPORTS];
* 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(lpc17_pinset_t cfgset);
+
+/************************************************************************************
+ * Name: lpc17_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ************************************************************************************/
+
+void lpc17_gpiowrite(lpc17_pinset_t pinset, bool value);
+
+/************************************************************************************
+ * Name: lpc17_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ************************************************************************************/
+
+bool lpc17_gpioread(lpc17_pinset_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(lpc17_pinset_t pinset, const char *msg);
+#else
+# define lpc17_dumpgpio(p,m)
+#endif
+
#ifdef __cplusplus
}
#endif