summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/include/lpc43xx/irq.h402
-rw-r--r--nuttx/arch/arm/src/lpc43xx/Make.defs61
-rw-r--r--nuttx/arch/arm/src/lpc43xx/chip.h52
-rw-r--r--nuttx/arch/arm/src/lpc43xx/chip/lpc43_gpio.h47
-rw-r--r--nuttx/arch/arm/src/lpc43xx/chip/lpc43_scu.h6
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_config.h13
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_gpio.h25
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.h39
8 files changed, 371 insertions, 274 deletions
diff --git a/nuttx/arch/arm/include/lpc43xx/irq.h b/nuttx/arch/arm/include/lpc43xx/irq.h
index c25cfcf5c..08fce71d1 100644
--- a/nuttx/arch/arm/include/lpc43xx/irq.h
+++ b/nuttx/arch/arm/include/lpc43xx/irq.h
@@ -1,4 +1,4 @@
-/****************************************************************************
+/********************************************************************************************
* arch/arm/include/lpc43xxx/irq.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
@@ -31,7 +31,7 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ****************************************************************************/
+ ********************************************************************************************/
/* This file should never be included directed but, rather,
* only indirectly through nuttx/irq.h
@@ -40,138 +40,98 @@
#ifndef __ARCH_ARM_INCLUDE_LPC43XX_IRQ_H
#define __ARCH_ARM_INCLUDE_LPC43XX_IRQ_H
-/****************************************************************************
+/********************************************************************************************
* Included Files
- ****************************************************************************/
+ ********************************************************************************************/
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
-/****************************************************************************
+/********************************************************************************************
* Pre-processor Definitions
- ****************************************************************************/
+ ********************************************************************************************/
-/* IRQ numbers. The IRQ number corresponds vector number and hence map
- * directly to bits in the NVIC. This does, however, waste several words of
- * memory in the IRQ to handle mapping tables.
+/* IRQ numbers. The IRQ number corresponds vector number and hence map directly to bits in
+ * the NVIC. This does, however, waste several words of memory in the IRQ to handle mapping
+ * tables.
*/
/* Processor Exceptions (vectors 0-15) */
-#define LPC43_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG) */
- /* Vector 0: Reset stack pointer value */
- /* Vector 1: Reset (not handler as an IRQ) */
-#define LPC43_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
-#define LPC43_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
-#define LPC43_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */
-#define LPC43_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */
-#define LPC43_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */
-#define LPC43_IRQ_SIGNVALUE (7) /* Vector 7: Sign value */
-#define LPC43_IRQ_SVCALL (11) /* Vector 11: SVC call */
-#define LPC43_IRQ_DBGMONITOR (12) /* Vector 12: Debug Monitor */
- /* Vector 13: Reserved */
-#define LPC43_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */
-#define LPC43_IRQ_SYSTICK (15) /* Vector 15: System tick */
-#define LPC43_IRQ_EXTINT (16) /* Vector 16: Vector number of the first external interrupt */
+#define LPC43_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG) */
+ /* Vector 0: Reset stack pointer value */
+ /* Vector 1: Reset (not handler as an IRQ) */
+#define LPC43_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
+#define LPC43_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
+#define LPC43_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */
+#define LPC43_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */
+#define LPC43_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */
+#define LPC43_IRQ_SIGNVALUE (7) /* Vector 7: Sign value */
+#define LPC43_IRQ_SVCALL (11) /* Vector 11: SVC call */
+#define LPC43_IRQ_DBGMONITOR (12) /* Vector 12: Debug Monitor */
+ /* Vector 13: Reserved */
+#define LPC43_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */
+#define LPC43_IRQ_SYSTICK (15) /* Vector 15: System tick */
+#define LPC43_IRQ_EXTINT (16) /* Vector 16: Vector number of the first external interrupt */
/* Cortex-M4 External interrupts (vectors >= 16) */
-#define LPC43M4_IRQ_DAC (LPC43_IRQ_EXTINT+0) /* D/A */
-#define LPC43M4_IRQ_M0CORE (LPC43_IRQ_EXTINT+1) /* M0 Core */
-#define LPC43M4_IRQ_DMA (LPC43_IRQ_EXTINT+2) /* DMA */
-#define LPC43M4_IRQ_FLASHEEPROM (LPC43_IRQ_EXTINT+4) /* EEPROM interrupts (BankA or BankB) */
-#define LPC43M4_IRQ_ETHERNET (LPC43_IRQ_EXTINT+5) /* Ethernet interrupt */
-#define LPC43M4_IRQ_SDIO (LPC43_IRQ_EXTINT+6) /* SD/MMC interrupt */
-#define LPC43M4_IRQ_LCD (LPC43_IRQ_EXTINT+7) /* LCD */
-#define LPC43M4_IRQ_USB0 (LPC43_IRQ_EXTINT+8) /* USB0 OTG interrupt */
-#define LPC43M4_IRQ_USB1 (LPC43_IRQ_EXTINT+9) /* USB1 interrupt */
-#define LPC43M4_IRQ_SCT (LPC43_IRQ_EXTINT+10) /* SCT combined interrupt */
-#define LPC43M4_IRQ_RITIMER (LPC43_IRQ_EXTINT+11) /* RITIMER interrupt */
-#define LPC43M4_IRQ_TIMER0 (LPC43_IRQ_EXTINT+12) /* TIMER0 interrupt */
-#define LPC43M4_IRQ_TIMER1 (LPC43_IRQ_EXTINT+13) /* TIMER1 interrupt */
-#define LPC43M4_IRQ_TIMER2 (LPC43_IRQ_EXTINT+14) /* TIMER2 interrupt */
-#define LPC43M4_IRQ_TIMER3 (LPC43_IRQ_EXTINT+15) /* TIMER3 interrupt */
-#define LPC43M4_IRQ_MCPWM (LPC43_IRQ_EXTINT+16) /* Motor control PWM interrupt */
-#define LPC43M4_IRQ_ADC0 (LPC43_IRQ_EXTINT+17) /* ADC0 interrupt */
-#define LPC43M4_IRQ_I2C0 (LPC43_IRQ_EXTINT+18) /* I2C0 interrupt */
-#define LPC43M4_IRQ_I2C1 (LPC43_IRQ_EXTINT+19) /* I2C1 interrupt */
-#define LPC43M4_IRQ_SPI (LPC43_IRQ_EXTINT+20) /* SPI interrupt */
-#define LPC43M4_IRQ_ADC1 (LPC43_IRQ_EXTINT+21) /* ADC1 interrupt */
-#define LPC43M4_IRQ_SSP0 (LPC43_IRQ_EXTINT+22) /* SSP0 interrupt */
-#define LPC43M4_IRQ_SSP1 (LPC43_IRQ_EXTINT+23) /* SSP1 interrupt */
-#define LPC43M4_IRQ_USART0 (LPC43_IRQ_EXTINT+24) /* USART0 interrupt */
-#define LPC43M4_IRQ_UART1 (LPC43_IRQ_EXTINT+25) /* UART1/Modem interrupt */
-#define LPC43M4_IRQ_USART2 (LPC43_IRQ_EXTINT+26) /* USART2 interrupt */
-#define LPC43M4_IRQ_USART3 (LPC43_IRQ_EXTINT+27) /* USART3/IrDA interrupt */
-#define LPC43M4_IRQ_I2S0 (LPC43_IRQ_EXTINT+28) /* I2S0 interrupt */
-#define LPC43M4_IRQ_I2S1 (LPC43_IRQ_EXTINT+29) /* I2S1 interrupt */
-#define LPC43M4_IRQ_SPIFI (LPC43_IRQ_EXTINT+30) /* SPIFI interrupt */
-#define LPC43M4_IRQ_SGPIO (LPC43_IRQ_EXTINT+31) /* SGPIO interrupt */
-#define LPC43M4_IRQ_PININT0 (LPC43_IRQ_EXTINT+32) /* GPIO pin interrupt 0 */
-#define LPC43M4_IRQ_PININT1 (LPC43_IRQ_EXTINT+33) /* GPIO pin interrupt 1 */
-#define LPC43M4_IRQ_PININT2 (LPC43_IRQ_EXTINT+34) /* GPIO pin interrupt 2 */
-#define LPC43M4_IRQ_PININT3 (LPC43_IRQ_EXTINT+35) /* GPIO pin interrupt 3 */
-#define LPC43M4_IRQ_PININT4 (LPC43_IRQ_EXTINT+36) /* GPIO pin interrupt 4 */
-#define LPC43M4_IRQ_PININT5 (LPC43_IRQ_EXTINT+37) /* GPIO pin interrupt 5 */
-#define LPC43M4_IRQ_PININT6 (LPC43_IRQ_EXTINT+38) /* GPIO pin interrupt 6 */
-#define LPC43M4_IRQ_PININT7 (LPC43_IRQ_EXTINT+39) /* GPIO pin interrupt 7 */
-#define LPC43M4_IRQ_GINT0 (LPC43_IRQ_EXTINT+40) /* GPIO global interrupt 0 */
-#define LPC43M4_IRQ_GINT1 (LPC43_IRQ_EXTINT+41) /* GPIO global interrupt 1 */
-#define LPC43M4_IRQ_EVENTROUTER (LPC43_IRQ_EXTINT+42) /* Event router interrupt */
-#define LPC43M4_IRQ_CAN1 (LPC43_IRQ_EXTINT+43) /* C_CAN1 interrupt */
-#define LPC43M4_IRQ_ATIMER (LPC43_IRQ_EXTINT+46) /* ATIMER Alarm timer interrupt */
-#define LPC43M4_IRQ_RTC (LPC43_IRQ_EXTINT+47) /* RTC interrupt */
-#define LPC43M4_IRQ_WWDT (LPC43_IRQ_EXTINT+49) /* WWDT interrupt */
-#define LPC43M4_IRQ_CAN0 (LPC43_IRQ_EXTINT+51) /* C_CAN0 interrupt */
-#define LPC43M4_IRQ_QEI (LPC43_IRQ_EXTINT+52) /* QEI interrupt */
-
-/* Cortex-M0 External interrupts (vectors >= 16) */
-
-#define LPC43M0_IRQ_RTC (LPC43_IRQ_EXTINT+0) /* RT interrupt */
-#define LPC43M0_IRQ_M4CORE (LPC43_IRQ_EXTINT+1) /* Interrupt from the M4 core */
-#define LPC43M0_IRQ_DMA (LPC43_IRQ_EXTINT+2) /* DMA interrupt */
-#define LPC43M0_IRQ_FLASHEEPROM (LPC43_IRQ_EXTINT+4) /* EEPROM (Bank A or B) | A Timer */
-#define LPC43M0_IRQ_ATIMER (LPC43_IRQ_EXTINT+4) /* EEPROM (Bank A or B) | A Timer */
-#define LPC43M0_IRQ_ETHERNET (LPC43_IRQ_EXTINT+5) /* Ethernet interrupt */
-#define LPC43M0_IRQ_SDIO (LPC43_IRQ_EXTINT+6) /* SDIO interrupt */
-#define LPC43M0_IRQ_LCD (LPC43_IRQ_EXTINT+7) /* LCD interrupt */
-#define LPC43M0_IRQ_USB0 (LPC43_IRQ_EXTINT+8) /* USB0 OTG interrupt */
-#define LPC43M0_IRQ_USB1 (LPC43_IRQ_EXTINT+9) /* USB1 interrupt */
-#define LPC43M0_IRQ_SCT (LPC43_IRQ_EXTINT+10) /* SCT combined interrupt */
-#define LPC43M0_IRQ_RITIMER (LPC43_IRQ_EXTINT+11) /* RI Timer | WWDT interrupt */
-#define LPC43M0_IRQ_WWDT (LPC43_IRQ_EXTINT+11) /* RI Timer | WWDT interrupt */
-#define LPC43M0_IRQ_TIMER0 (LPC43_IRQ_EXTINT+12) /* TIMER0 interrupt */
-#define LPC43M0_IRQ_GINT1 (LPC43_IRQ_EXTINT+13) /* GINT1 GPIO global interrupt 1 */
-#define LPC43M0_IRQ_PININT4 (LPC43_IRQ_EXTINT+14) /* GPIO pin interrupt 4 */
-#define LPC43M0_IRQ_TIMER3 (LPC43_IRQ_EXTINT+15) /* TIMER interrupt */
-#define LPC43M0_IRQ_MCPWM (LPC43_IRQ_EXTINT+16) /* Motor control PWM interrupt */
-#define LPC43M0_IRQ_ADC0 (LPC43_IRQ_EXTINT+17) /* ADC0 interrupt */
-#define LPC43M0_IRQ_I2C0 (LPC43_IRQ_EXTINT+18) /* I2C0 | I2C1 interrupt */
-#define LPC43M0_IRQ_I2C1 (LPC43_IRQ_EXTINT+18) /* I2C0 | I2C1 interrupt */
-#define LPC43M0_IRQ_SGPIO (LPC43_IRQ_EXTINT+19) /* SGPIO interrupt */
-#define LPC43M0_IRQ_SPI (LPC43_IRQ_EXTINT+20) /* SPI | DAC interrupt */
-#define LPC43M0_IRQ_DAC (LPC43_IRQ_EXTINT+20) /* SPI | DAC interrupt */
-#define LPC43M0_IRQ_ADC1 (LPC43_IRQ_EXTINT+21) /* ADC1 interrupt */
-#define LPC43M0_IRQ_SSP0 (LPC43_IRQ_EXTINT+22) /* SSP0 | SSP1 interrupt */
-#define LPC43M0_IRQ_SSP1 (LPC43_IRQ_EXTINT+22) /* SSP0 | SSP1 interrupt */
-#define LPC43M0_IRQ_EVENTROUTER (LPC43_IRQ_EXTINT+23) /* Event router interrupt */
-#define LPC43M0_IRQ_USART0 (LPC43_IRQ_EXTINT+24) /* USART0 interrupt */
-#define LPC43M0_IRQ_UART1 (LPC43_IRQ_EXTINT+25) /* UART1 Modem/UART1 interrupt */
-#define LPC43M0_IRQ_USART2 (LPC43_IRQ_EXTINT+26) /* USART2 | C_CAN1 interrupt */
-#define LPC43M0_IRQ_CAN1 (LPC43_IRQ_EXTINT+26) /* USART2 | C_CAN1 interrupt */
-#define LPC43M0_IRQ_USART3 (LPC43_IRQ_EXTINT+27) /* USART3 interrupt */
-#define LPC43M0_IRQ_I2S0 (LPC43_IRQ_EXTINT+28) /* I2S0 | I2S1 | QEI interrupt */
-#define LPC43M0_IRQ_I2S1 (LPC43_IRQ_EXTINT+28) /* I2S0 | I2S1 | QEI interrupt */
-#define LPC43M0_IRQ_QEI (LPC43_IRQ_EXTINT+28) /* I2S0 | I2S1 | QEI interrupt */
-#define LPC43M0_IRQ_CAN0 (LPC43_IRQ_EXTINT+29) /* C_CAN0 interrupt */
-
-#define LPC43_IRQ_NEXTINT (LPC43_IRQ_EXTINT+53)
-#define LPC43_IRQ_NIRQS (LPC43_IRQ_EXTINT+LPC43_IRQ_NEXTINT)
-
-/* GPIO interrupts. The LPC43xx supports several interrupts on ports 0 and
- * 2 (only). We go through some special efforts to keep the number of IRQs
- * to a minimum in this sparse interrupt case.
+#define LPC43M4_IRQ_DAC (LPC43_IRQ_EXTINT+0) /* D/A */
+#define LPC43M4_IRQ_M0CORE (LPC43_IRQ_EXTINT+1) /* M0 Core */
+#define LPC43M4_IRQ_DMA (LPC43_IRQ_EXTINT+2) /* DMA */
+#define LPC43M4_IRQ_FLASHEEPROM (LPC43_IRQ_EXTINT+4) /* EEPROM interrupts (BankA or BankB) */
+#define LPC43M4_IRQ_ETHERNET (LPC43_IRQ_EXTINT+5) /* Ethernet interrupt */
+#define LPC43M4_IRQ_SDIO (LPC43_IRQ_EXTINT+6) /* SD/MMC interrupt */
+#define LPC43M4_IRQ_LCD (LPC43_IRQ_EXTINT+7) /* LCD */
+#define LPC43M4_IRQ_USB0 (LPC43_IRQ_EXTINT+8) /* USB0 OTG interrupt */
+#define LPC43M4_IRQ_USB1 (LPC43_IRQ_EXTINT+9) /* USB1 interrupt */
+#define LPC43M4_IRQ_SCT (LPC43_IRQ_EXTINT+10) /* SCT combined interrupt */
+#define LPC43M4_IRQ_RITIMER (LPC43_IRQ_EXTINT+11) /* RITIMER interrupt */
+#define LPC43M4_IRQ_TIMER0 (LPC43_IRQ_EXTINT+12) /* TIMER0 interrupt */
+#define LPC43M4_IRQ_TIMER1 (LPC43_IRQ_EXTINT+13) /* TIMER1 interrupt */
+#define LPC43M4_IRQ_TIMER2 (LPC43_IRQ_EXTINT+14) /* TIMER2 interrupt */
+#define LPC43M4_IRQ_TIMER3 (LPC43_IRQ_EXTINT+15) /* TIMER3 interrupt */
+#define LPC43M4_IRQ_MCPWM (LPC43_IRQ_EXTINT+16) /* Motor control PWM interrupt */
+#define LPC43M4_IRQ_ADC0 (LPC43_IRQ_EXTINT+17) /* ADC0 interrupt */
+#define LPC43M4_IRQ_I2C0 (LPC43_IRQ_EXTINT+18) /* I2C0 interrupt */
+#define LPC43M4_IRQ_I2C1 (LPC43_IRQ_EXTINT+19) /* I2C1 interrupt */
+#define LPC43M4_IRQ_SPI (LPC43_IRQ_EXTINT+20) /* SPI interrupt */
+#define LPC43M4_IRQ_ADC1 (LPC43_IRQ_EXTINT+21) /* ADC1 interrupt */
+#define LPC43M4_IRQ_SSP0 (LPC43_IRQ_EXTINT+22) /* SSP0 interrupt */
+#define LPC43M4_IRQ_SSP1 (LPC43_IRQ_EXTINT+23) /* SSP1 interrupt */
+#define LPC43M4_IRQ_USART0 (LPC43_IRQ_EXTINT+24) /* USART0 interrupt */
+#define LPC43M4_IRQ_UART1 (LPC43_IRQ_EXTINT+25) /* UART1/Modem interrupt */
+#define LPC43M4_IRQ_USART2 (LPC43_IRQ_EXTINT+26) /* USART2 interrupt */
+#define LPC43M4_IRQ_USART3 (LPC43_IRQ_EXTINT+27) /* USART3/IrDA interrupt */
+#define LPC43M4_IRQ_I2S0 (LPC43_IRQ_EXTINT+28) /* I2S0 interrupt */
+#define LPC43M4_IRQ_I2S1 (LPC43_IRQ_EXTINT+29) /* I2S1 interrupt */
+#define LPC43M4_IRQ_SPIFI (LPC43_IRQ_EXTINT+30) /* SPIFI interrupt */
+#define LPC43M4_IRQ_SGPIO (LPC43_IRQ_EXTINT+31) /* SGPIO interrupt */
+#define LPC43M4_IRQ_PININT0 (LPC43_IRQ_EXTINT+32) /* GPIO pin interrupt 0 */
+#define LPC43M4_IRQ_PININT1 (LPC43_IRQ_EXTINT+33) /* GPIO pin interrupt 1 */
+#define LPC43M4_IRQ_PININT2 (LPC43_IRQ_EXTINT+34) /* GPIO pin interrupt 2 */
+#define LPC43M4_IRQ_PININT3 (LPC43_IRQ_EXTINT+35) /* GPIO pin interrupt 3 */
+#define LPC43M4_IRQ_PININT4 (LPC43_IRQ_EXTINT+36) /* GPIO pin interrupt 4 */
+#define LPC43M4_IRQ_PININT5 (LPC43_IRQ_EXTINT+37) /* GPIO pin interrupt 5 */
+#define LPC43M4_IRQ_PININT6 (LPC43_IRQ_EXTINT+38) /* GPIO pin interrupt 6 */
+#define LPC43M4_IRQ_PININT7 (LPC43_IRQ_EXTINT+39) /* GPIO pin interrupt 7 */
+#define LPC43M4_IRQ_GINT0 (LPC43_IRQ_EXTINT+40) /* GPIO global interrupt 0 */
+#define LPC43M4_IRQ_GINT1 (LPC43_IRQ_EXTINT+41) /* GPIO global interrupt 1 */
+#define LPC43M4_IRQ_EVENTROUTER (LPC43_IRQ_EXTINT+42) /* Event router interrupt */
+#define LPC43M4_IRQ_CAN1 (LPC43_IRQ_EXTINT+43) /* C_CAN1 interrupt */
+#define LPC43M4_IRQ_ATIMER (LPC43_IRQ_EXTINT+46) /* ATIMER Alarm timer interrupt */
+#define LPC43M4_IRQ_RTC (LPC43_IRQ_EXTINT+47) /* RTC interrupt */
+#define LPC43M4_IRQ_WWDT (LPC43_IRQ_EXTINT+49) /* WWDT interrupt */
+#define LPC43M4_IRQ_CAN0 (LPC43_IRQ_EXTINT+51) /* C_CAN0 interrupt */
+#define LPC43M4_IRQ_QEI (LPC43_IRQ_EXTINT+52) /* QEI interrupt */
+
+#define LPC43M4_IRQ_NEXTINT (53)
+#define LPC43M4_IRQ_NIRQS (LPC43_IRQ_EXTINT+LPC43M4_IRQ_NEXTINT)
+
+/* Cortex-M4 GPIO interrupts. The LPC43xx supports several interrupts on ports 0 and 2
+ * (only). We go through some special efforts to keep the number of IRQs to a minimum in
+ * this sparse interrupt case.
*
* 28 interrupts on Port 0: p0.0 - p0.11, p0.15-p0.30
* 14 interrupts on Port 2: p2.0 - p2.13
@@ -181,102 +141,164 @@
#ifdef CONFIG_GPIO_IRQ
# warning "REVISIT"
-# define LPC43_VALID_GPIOINT0 (0x7fff8ffful) /* GPIO port 0 interrrupt set */
-# define LPC43_VALID_GPIOINT2 (0x00003ffful) /* GPIO port 2 interrupt set */
+# define LPC43M4_VALID_GPIOINT0 (0x7fff8ffful) /* GPIO port 0 interrrupt set */
+# define LPC43M4_VALID_GPIOINT2 (0x00003ffful) /* GPIO port 2 interrupt set */
/* Set 1: 12 interrupts p0.0-p0.11 */
-# define LPC43_VALID_GPIOINT0L (0x00000ffful)
-# define LPC43_VALID_SHIFT0L (0)
-# define LPC43_VALID_FIRST0L (LPC43_IRQ_EXTINT+LPC43_IRQ_NEXTINT)
-
-# define LPC43_IRQ_P0p0 (LPC43_VALID_FIRST0L+0)
-# define LPC43_IRQ_P0p1 (LPC43_VALID_FIRST0L+1)
-# define LPC43_IRQ_P0p2 (LPC43_VALID_FIRST0L+2)
-# define LPC43_IRQ_P0p3 (LPC43_VALID_FIRST0L+3)
-# define LPC43_IRQ_P0p4 (LPC43_VALID_FIRST0L+4)
-# define LPC43_IRQ_P0p5 (LPC43_VALID_FIRST0L+5)
-# define LPC43_IRQ_P0p6 (LPC43_VALID_FIRST0L+6)
-# define LPC43_IRQ_P0p7 (LPC43_VALID_FIRST0L+7)
-# define LPC43_IRQ_P0p8 (LPC43_VALID_FIRST0L+8)
-# define LPC43_IRQ_P0p9 (LPC43_VALID_FIRST0L+9)
-# define LPC43_IRQ_P0p10 (LPC43_VALID_FIRST0L+10)
-# define LPC43_IRQ_P0p11 (LPC43_VALID_FIRST0L+11)
-# define LPC43_VALID_NIRQS0L (12)
+# define LPC43M4_VALID_GPIOINT0L (0x00000ffful)
+# define LPC43M4_VALID_SHIFT0L (0)
+# define LPC43M4_VALID_FIRST0L (LPC43_IRQ_EXTINT+LPC43M4_IRQ_NEXTINT)
+
+# define LPC43M4_IRQ_P0p0 (LPC43M4_VALID_FIRST0L+0)
+# define LPC43M4_IRQ_P0p1 (LPC43M4_VALID_FIRST0L+1)
+# define LPC43M4_IRQ_P0p2 (LPC43M4_VALID_FIRST0L+2)
+# define LPC43M4_IRQ_P0p3 (LPC43M4_VALID_FIRST0L+3)
+# define LPC43M4_IRQ_P0p4 (LPC43M4_VALID_FIRST0L+4)
+# define LPC43M4_IRQ_P0p5 (LPC43M4_VALID_FIRST0L+5)
+# define LPC43M4_IRQ_P0p6 (LPC43M4_VALID_FIRST0L+6)
+# define LPC43M4_IRQ_P0p7 (LPC43M4_VALID_FIRST0L+7)
+# define LPC43M4_IRQ_P0p8 (LPC43M4_VALID_FIRST0L+8)
+# define LPC43M4_IRQ_P0p9 (LPC43M4_VALID_FIRST0L+9)
+# define LPC43M4_IRQ_P0p10 (LPC43M4_VALID_FIRST0L+10)
+# define LPC43M4_IRQ_P0p11 (LPC43M4_VALID_FIRST0L+11)
+# define LPC43M4_VALID_NIRQS0L (12)
/* Set 2: 16 interrupts p0.15-p0.30 */
-# define LPC43_VALID_GPIOINT0H (0x7fff8000ull)
-# define LPC43_VALID_SHIFT0H (15)
-# define LPC43_VALID_FIRST0H (LPC43_VALID_FIRST0L+LPC43_VALID_NIRQS0L)
-
-# define LPC43_IRQ_P0p15 (LPC43_VALID_FIRST0H+0)
-# define LPC43_IRQ_P0p16 (LPC43_VALID_FIRST0H+1)
-# define LPC43_IRQ_P0p17 (LPC43_VALID_FIRST0H+2)
-# define LPC43_IRQ_P0p18 (LPC43_VALID_FIRST0H+3)
-# define LPC43_IRQ_P0p19 (LPC43_VALID_FIRST0H+4)
-# define LPC43_IRQ_P0p20 (LPC43_VALID_FIRST0H+5)
-# define LPC43_IRQ_P0p21 (LPC43_VALID_FIRST0H+6)
-# define LPC43_IRQ_P0p22 (LPC43_VALID_FIRST0H+7)
-# define LPC43_IRQ_P0p23 (LPC43_VALID_FIRST0H+8)
-# define LPC43_IRQ_P0p24 (LPC43_VALID_FIRST0H+9)
-# define LPC43_IRQ_P0p25 (LPC43_VALID_FIRST0H+10)
-# define LPC43_IRQ_P0p26 (LPC43_VALID_FIRST0H+11)
-# define LPC43_IRQ_P0p27 (LPC43_VALID_FIRST0H+12)
-# define LPC43_IRQ_P0p28 (LPC43_VALID_FIRST0H+13)
-# define LPC43_IRQ_P0p29 (LPC43_VALID_FIRST0H+14)
-# define LPC43_IRQ_P0p30 (LPC43_VALID_FIRST0H+15)
-# define LPC43_VALID_NIRQS0H (16)
+# define LPC43M4_VALID_GPIOINT0H (0x7fff8000ull)
+# define LPC43M4_VALID_SHIFT0H (15)
+# define LPC43M4_VALID_FIRST0H (LPC43M4_VALID_FIRST0L+LPC43M4_VALID_NIRQS0L)
+
+# define LPC43M4_IRQ_P0p15 (LPC43M4_VALID_FIRST0H+0)
+# define LPC43M4_IRQ_P0p16 (LPC43M4_VALID_FIRST0H+1)
+# define LPC43M4_IRQ_P0p17 (LPC43M4_VALID_FIRST0H+2)
+# define LPC43M4_IRQ_P0p18 (LPC43M4_VALID_FIRST0H+3)
+# define LPC43M4_IRQ_P0p19 (LPC43M4_VALID_FIRST0H+4)
+# define LPC43M4_IRQ_P0p20 (LPC43M4_VALID_FIRST0H+5)
+# define LPC43M4_IRQ_P0p21 (LPC43M4_VALID_FIRST0H+6)
+# define LPC43M4_IRQ_P0p22 (LPC43M4_VALID_FIRST0H+7)
+# define LPC43M4_IRQ_P0p23 (LPC43M4_VALID_FIRST0H+8)
+# define LPC43M4_IRQ_P0p24 (LPC43M4_VALID_FIRST0H+9)
+# define LPC43M4_IRQ_P0p25 (LPC43M4_VALID_FIRST0H+10)
+# define LPC43M4_IRQ_P0p26 (LPC43M4_VALID_FIRST0H+11)
+# define LPC43M4_IRQ_P0p27 (LPC43M4_VALID_FIRST0H+12)
+# define LPC43M4_IRQ_P0p28 (LPC43M4_VALID_FIRST0H+13)
+# define LPC43M4_IRQ_P0p29 (LPC43M4_VALID_FIRST0H+14)
+# define LPC43M4_IRQ_P0p30 (LPC43M4_VALID_FIRST0H+15)
+# define LPC43M4_VALID_NIRQS0H (16)
/* Set 3: 14 interrupts p2.0-p2.13 */
-# define LPC43_VALID_GPIOINT2 (0x00003ffful)
-# define LPC43_VALID_SHIFT2 (0)
-# define LPC43_VALID_FIRST2 (LPC43_VALID_FIRST0H+LPC43_VALID_NIRQS0H)
-
-# define LPC43_IRQ_P2p0 (LPC43_VALID_FIRST2+0)
-# define LPC43_IRQ_P2p1 (LPC43_VALID_FIRST2+1)
-# define LPC43_IRQ_P2p2 (LPC43_VALID_FIRST2+2)
-# define LPC43_IRQ_P2p3 (LPC43_VALID_FIRST2+3)
-# define LPC43_IRQ_P2p4 (LPC43_VALID_FIRST2+4)
-# define LPC43_IRQ_P2p5 (LPC43_VALID_FIRST2+5)
-# define LPC43_IRQ_P2p6 (LPC43_VALID_FIRST2+6)
-# define LPC43_IRQ_P2p7 (LPC43_VALID_FIRST2+7)
-# define LPC43_IRQ_P2p8 (LPC43_VALID_FIRST2+8)
-# define LPC43_IRQ_P2p9 (LPC43_VALID_FIRST2+9)
-# define LPC43_IRQ_P2p10 (LPC43_VALID_FIRST2+10)
-# define LPC43_IRQ_P2p11 (LPC43_VALID_FIRST2+11)
-# define LPC43_IRQ_P2p12 (LPC43_VALID_FIRST2+12)
-# define LPC43_IRQ_P2p13 (LPC43_VALID_FIRST2+13)
-# define LPC43_VALID_NIRQS2 (14)
-# define LPC43_NGPIOAIRQS (LPC43_VALID_NIRQS0L+LPC43_VALID_NIRQS0H+LPC43_VALID_NIRQS2)
+# define LPC43M4_VALID_GPIOINT2 (0x00003ffful)
+# define LPC43M4_VALID_SHIFT2 (0)
+# define LPC43M4_VALID_FIRST2 (LPC43M4_VALID_FIRST0H+LPC43M4_VALID_NIRQS0H)
+
+# define LPC43M4_IRQ_P2p0 (LPC43M4_VALID_FIRST2+0)
+# define LPC43M4_IRQ_P2p1 (LPC43M4_VALID_FIRST2+1)
+# define LPC43M4_IRQ_P2p2 (LPC43M4_VALID_FIRST2+2)
+# define LPC43M4_IRQ_P2p3 (LPC43M4_VALID_FIRST2+3)
+# define LPC43M4_IRQ_P2p4 (LPC43M4_VALID_FIRST2+4)
+# define LPC43M4_IRQ_P2p5 (LPC43M4_VALID_FIRST2+5)
+# define LPC43M4_IRQ_P2p6 (LPC43M4_VALID_FIRST2+6)
+# define LPC43M4_IRQ_P2p7 (LPC43M4_VALID_FIRST2+7)
+# define LPC43M4_IRQ_P2p8 (LPC43M4_VALID_FIRST2+8)
+# define LPC43M4_IRQ_P2p9 (LPC43M4_VALID_FIRST2+9)
+# define LPC43M4_IRQ_P2p10 (LPC43M4_VALID_FIRST2+10)
+# define LPC43M4_IRQ_P2p11 (LPC43M4_VALID_FIRST2+11)
+# define LPC43M4_IRQ_P2p12 (LPC43M4_VALID_FIRST2+12)
+# define LPC43M4_IRQ_P2p13 (LPC43M4_VALID_FIRST2+13)
+# define LPC43M4_VALID_NIRQS2 (14)
+# define LPC43M4_NGPIOAIRQS (LPC43M4_VALID_NIRQS0L+LPC43M4_VALID_NIRQS0H+LPC43M4_VALID_NIRQS2)
+#else
+# define LPC43M4_NGPIOAIRQS (0)
+#endif
+
+/* Total number of IRQ numbers (This will need to be revisited if/when the Cortex-M0 is
+ * supported
+ */
+
+#define NR_IRQS (LPC43_IRQ_EXTINT+LPC43M4_IRQ_NEXTINT+LPC43M4_NGPIOAIRQS)
+
+/* Cortex-M0 External interrupts (vectors >= 16) */
+
+#define LPC43M0_IRQ_RTC (LPC43_IRQ_EXTINT+0) /* RT interrupt */
+#define LPC43M0_IRQ_M4CORE (LPC43_IRQ_EXTINT+1) /* Interrupt from the M4 core */
+#define LPC43M0_IRQ_DMA (LPC43_IRQ_EXTINT+2) /* DMA interrupt */
+#define LPC43M0_IRQ_FLASHEEPROM (LPC43_IRQ_EXTINT+4) /* EEPROM (Bank A or B) | A Timer */
+#define LPC43M0_IRQ_ATIMER (LPC43_IRQ_EXTINT+4) /* EEPROM (Bank A or B) | A Timer */
+#define LPC43M0_IRQ_ETHERNET (LPC43_IRQ_EXTINT+5) /* Ethernet interrupt */
+#define LPC43M0_IRQ_SDIO (LPC43_IRQ_EXTINT+6) /* SDIO interrupt */
+#define LPC43M0_IRQ_LCD (LPC43_IRQ_EXTINT+7) /* LCD interrupt */
+#define LPC43M0_IRQ_USB0 (LPC43_IRQ_EXTINT+8) /* USB0 OTG interrupt */
+#define LPC43M0_IRQ_USB1 (LPC43_IRQ_EXTINT+9) /* USB1 interrupt */
+#define LPC43M0_IRQ_SCT (LPC43_IRQ_EXTINT+10) /* SCT combined interrupt */
+#define LPC43M0_IRQ_RITIMER (LPC43_IRQ_EXTINT+11) /* RI Timer | WWDT interrupt */
+#define LPC43M0_IRQ_WWDT (LPC43_IRQ_EXTINT+11) /* RI Timer | WWDT interrupt */
+#define LPC43M0_IRQ_TIMER0 (LPC43_IRQ_EXTINT+12) /* TIMER0 interrupt */
+#define LPC43M0_IRQ_GINT1 (LPC43_IRQ_EXTINT+13) /* GINT1 GPIO global interrupt 1 */
+#define LPC43M0_IRQ_PININT4 (LPC43_IRQ_EXTINT+14) /* GPIO pin interrupt 4 */
+#define LPC43M0_IRQ_TIMER3 (LPC43_IRQ_EXTINT+15) /* TIMER interrupt */
+#define LPC43M0_IRQ_MCPWM (LPC43_IRQ_EXTINT+16) /* Motor control PWM interrupt */
+#define LPC43M0_IRQ_ADC0 (LPC43_IRQ_EXTINT+17) /* ADC0 interrupt */
+#define LPC43M0_IRQ_I2C0 (LPC43_IRQ_EXTINT+18) /* I2C0 | I2C1 interrupt */
+#define LPC43M0_IRQ_I2C1 (LPC43_IRQ_EXTINT+18) /* I2C0 | I2C1 interrupt */
+#define LPC43M0_IRQ_SGPIO (LPC43_IRQ_EXTINT+19) /* SGPIO interrupt */
+#define LPC43M0_IRQ_SPI (LPC43_IRQ_EXTINT+20) /* SPI | DAC interrupt */
+#define LPC43M0_IRQ_DAC (LPC43_IRQ_EXTINT+20) /* SPI | DAC interrupt */
+#define LPC43M0_IRQ_ADC1 (LPC43_IRQ_EXTINT+21) /* ADC1 interrupt */
+#define LPC43M0_IRQ_SSP0 (LPC43_IRQ_EXTINT+22) /* SSP0 | SSP1 interrupt */
+#define LPC43M0_IRQ_SSP1 (LPC43_IRQ_EXTINT+22) /* SSP0 | SSP1 interrupt */
+#define LPC43M0_IRQ_EVENTROUTER (LPC43_IRQ_EXTINT+23) /* Event router interrupt */
+#define LPC43M0_IRQ_USART0 (LPC43_IRQ_EXTINT+24) /* USART0 interrupt */
+#define LPC43M0_IRQ_UART1 (LPC43_IRQ_EXTINT+25) /* UART1 Modem/UART1 interrupt */
+#define LPC43M0_IRQ_USART2 (LPC43_IRQ_EXTINT+26) /* USART2 | C_CAN1 interrupt */
+#define LPC43M0_IRQ_CAN1 (LPC43_IRQ_EXTINT+26) /* USART2 | C_CAN1 interrupt */
+#define LPC43M0_IRQ_USART3 (LPC43_IRQ_EXTINT+27) /* USART3 interrupt */
+#define LPC43M0_IRQ_I2S0 (LPC43_IRQ_EXTINT+28) /* I2S0 | I2S1 | QEI interrupt */
+#define LPC43M0_IRQ_I2S1 (LPC43_IRQ_EXTINT+28) /* I2S0 | I2S1 | QEI interrupt */
+#define LPC43M0_IRQ_QEI (LPC43_IRQ_EXTINT+28) /* I2S0 | I2S1 | QEI interrupt */
+#define LPC43M0_IRQ_CAN0 (LPC43_IRQ_EXTINT+29) /* C_CAN0 interrupt */
+
+#define LPC43M0_IRQ_NEXTINT (30)
+#define LPC43M0_IRQ_NIRQS (LPC43_IRQ_EXTINT+LPC43M0_IRQ_NEXTINT)
+
+/* Cortex-M0 GPIO interrupts */
+
+#ifdef CONFIG_GPIO_IRQ
+# warning "REVISIT"
+# define LPC43M0_NGPIOAIRQS (0)
#else
-# define LPC43_NGPIOAIRQS (0)
+# define LPC43M0_NGPIOAIRQS (0)
#endif
-/* Total number of IRQ numbers */
+/* Total number of IRQ numbers (This will need to be revisited if/when the Cortex-M0 is
+ * supported)
+ */
-#define NR_IRQS (LPC43_IRQ_EXTINT+LPC43_IRQ_NEXTINT+LPC43_NGPIOAIRQS)
+#if 0
+#define NR_IRQS (LPC43_IRQ_EXTINT+LPC43M0_IRQ_NEXTINT+LPC43M0_NGPIOAIRQS)
+#endif
-/****************************************************************************
+/********************************************************************************************
* Public Types
- ****************************************************************************/
+ ********************************************************************************************/
#ifndef __ASSEMBLY__
typedef void (*vic_vector_t)(uint32_t *regs);
#endif
-/****************************************************************************
+/********************************************************************************************
* Inline functions
- ****************************************************************************/
+ ********************************************************************************************/
-/****************************************************************************
+/********************************************************************************************
* Public Variables
- ****************************************************************************/
+ ********************************************************************************************/
-/****************************************************************************
+/********************************************************************************************
* Public Function Prototypes
- ****************************************************************************/
+ ********************************************************************************************/
#ifndef __ASSEMBLY__
#ifdef __cplusplus
diff --git a/nuttx/arch/arm/src/lpc43xx/Make.defs b/nuttx/arch/arm/src/lpc43xx/Make.defs
new file mode 100644
index 000000000..d2a4eb746
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc43xx/Make.defs
@@ -0,0 +1,61 @@
+############################################################################
+# arch/arm/src/lpc43xx/Make.defs
+#
+# Copyright (C) 2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+HEAD_ASRC =
+
+CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
+CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \
+ up_createstack.c up_mdelay.c up_udelay.c up_exit.c \
+ up_initialize.c up_initialstate.c up_interruptcontext.c \
+ up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
+ up_releasepending.c up_releasestack.c up_reprioritizertr.c \
+ up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \
+ up_usestack.c up_doirq.c up_hardfault.c up_svcall.c
+
+ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
+CMN_ASRCS += up_exception.S
+CMN_CSRCS += up_vectors.c
+endif
+
+ifeq ($(CONFIG_DEBUG_STACK),y)
+CMN_CSRCS += up_checkstack.c
+endif
+
+ifeq ($(CONFIG_ARCH_FPU),y)
+CMN_ASRCS += up_fpu.S
+endif
+
+CHIP_ASRCS =
+CHIP_CSRCS =
diff --git a/nuttx/arch/arm/src/lpc43xx/chip.h b/nuttx/arch/arm/src/lpc43xx/chip.h
index 5b0918582..35150d08c 100644
--- a/nuttx/arch/arm/src/lpc43xx/chip.h
+++ b/nuttx/arch/arm/src/lpc43xx/chip.h
@@ -46,79 +46,93 @@
#include <arch/lpc43xx/chip.h>
-/* Include the chip memory map, pin configuration, and vector definition. These
- * header files may or may not be shared between different chips. That decisions
+/* For each chip supported in chip.h, the following are provided to customize the
+ * environment for the specific LPC43XX chip:
+ *
+ * Define ARMV7M_PERIPHERAL_INTERRUPTS - This is needed by common/up_vectors.c. This
+ * definition provides the number of "external" interrupt vectors supported by
+ * the specific LPC43 chip.
+ *
+ * For the Cortex-M3 core, this should always be equal to the value
+ * LPC43M4_IRQ_NEXTINT defined in include/lpc43xx/irq.h. For the Cortex-M0
+ * core, this should always be equal to the value LPC43M0_IRQ_NEXTINT defined
+ * in include/lpc43xx/irq.h (At present, only the Cortex-M4 core is supported)
+ *
+ * Include the chip-specific memory map header file, and
+ * Include the chip-specific pin configuration.
+ *
+ * These header files may or may not be shared between different chips. That decisions
* depends on the similarity of the chip peripheral.
*/
#if defined(CONFIG_ARCH_CHIP_LPC4310FBD144)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4310fbd144_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4310FET100)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4310fet100_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4320FBD144)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4320fbd144_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4320FET100)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4320fet100_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4330FBD144)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4330fbd144_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4330FET100)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4330fet100_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4330FET180)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4330fet180_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4330FET256)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4330fet256_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4350FBD208)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4350fbd208_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4350FET180)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4350fet180_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4350FET256)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc4310203050_memorymap.h"
# include "chip/lpc4310203050_pinconfig.h"
-# include "chip/lpc4350fet256_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4353FBD208)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc435357_memorymap.h"
# include "chip/lpc4353fbd208_pinconfig.h"
-# include "chip/lpc4353fbd208_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4353FET180)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc435357_memorymap.h"
# include "chip/lpc4353fet180_pinconfig.h"
-# include "chip/lpc4353fet180_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4353FET256)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc435357_memorymap.h"
# include "chip/lpc4353fet256_pinconfig.h"
-# include "chip/lpc4353fet256_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4357FET180)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc435357_memorymap.h"
# include "chip/lpc4357fet180_pinconfig.h"
-# include "chip/lpc4357fet180_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4357FBD208)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc435357_memorymap.h"
# include "chip/lpc4357fbd208_pinconfig.h"
-# include "chip/lpc4357fbd208_vectors.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4357FET256)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc435357_memorymap.h"
# include "chip/lpc4357fet256_pinconfig.h"
-# include "chip/lpc4357fet256_vectors.h"
#else
# error "Unsupported LPC43xx chip"
#endif
diff --git a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_gpio.h b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_gpio.h
index 49c0fea62..97117466b 100644
--- a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_gpio.h
+++ b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_gpio.h
@@ -45,51 +45,8 @@
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
-/* Indices */
-
-#deine LPC43_GPIO_PORT0 0
-#deine LPC43_GPIO_PORT1 1
-#deine LPC43_GPIO_PORT2 2
-#deine LPC43_GPIO_PORT3 3
-#deine LPC43_GPIO_PORT4 4
-#deine LPC43_GPIO_PORT5 5
-#deine LPC43_GPIO_PORT6 6
-#deine LPC43_GPIO_PORT7 7
-
-#deine LPC43_GPIO_PIN0 0
-#deine LPC43_GPIO_PIN1 1
-#deine LPC43_GPIO_PIN2 2
-#deine LPC43_GPIO_PIN3 3
-#deine LPC43_GPIO_PIN4 4
-#deine LPC43_GPIO_PIN5 5
-#deine LPC43_GPIO_PIN6 6
-#deine LPC43_GPIO_PIN7 7
-#deine LPC43_GPIO_PIN8 8
-#deine LPC43_GPIO_PIN9 9
-#deine LPC43_GPIO_PIN10 10
-#deine LPC43_GPIO_PIN11 11
-#deine LPC43_GPIO_PIN12 12
-#deine LPC43_GPIO_PIN13 13
-#deine LPC43_GPIO_PIN14 14
-#deine LPC43_GPIO_PIN15 15
-#deine LPC43_GPIO_PIN16 16
-#deine LPC43_GPIO_PIN17 17
-#deine LPC43_GPIO_PIN18 18
-#deine LPC43_GPIO_PIN19 19
-#deine LPC43_GPIO_PIN20 20
-#deine LPC43_GPIO_PIN21 21
-#deine LPC43_GPIO_PIN22 22
-#deine LPC43_GPIO_PIN23 23
-#deine LPC43_GPIO_PIN24 24
-#deine LPC43_GPIO_PIN25 25
-#deine LPC43_GPIO_PIN26 26
-#deine LPC43_GPIO_PIN27 27
-#deine LPC43_GPIO_PIN28 28
-#deine LPC43_GPIO_PIN29 29
-#deine LPC43_GPIO_PIN30 30
-#deine LPC43_GPIO_PIN31 31
-
-/* Register Offsets *********************************************************************************/
+
+ /* Register Offsets *********************************************************************************/
/* Pin interrupt registers (relative to LPC43_GPIOINT_BASE) */
diff --git a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_scu.h b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_scu.h
index 59678c114..64c6dc6f8 100644
--- a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_scu.h
+++ b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_scu.h
@@ -218,7 +218,7 @@
* PF_0 to PF_11
*/
/* Bits 0-4: Same as common bit definitions */
-#define SCU_NDPIN_EHS (1 << 5) /* Bit 5: EHS Select Slew rate.
+#define SCU_NDPIN_EHS (1 << 5) /* Bit 5: EHS Select Slew rate */
/* Bits 6-31: Same as common bit definitions */
/* Pin configuration registers for high-speed pins
*
@@ -240,7 +240,7 @@
* P3_3 and pins CLK0 to CLK3
*/
/* Bits 0-4: Same as common bit definitions */
-#define SCU_HSPIN_EHS (1 << 5) /* Bit 5: EHS Select Slew rate.
+#define SCU_HSPIN_EHS (1 << 5) /* Bit 5: EHS Select Slew rate */
/* Bits 6-31: Same as common bit definitions */
/* Pin configuration register for USB1 pins USB1_DP/USB1_DM */
@@ -324,7 +324,7 @@
#define SCU_EMCDELAYCLK_SHIFT (0) /* Bits 0-15: EMC_CLKn SDRAM clock output delay */
#define SCU_EMCDELAYCLK_MASK (0xffff << SCU_EMCDELAYCLK_SHIFT)
-# define SCU_EMCDELAYCLK(n( ((n) << SCU_EMCDELAYCLK_SHIFT) /* 0=no delay, N*0x1111 = N*0.5 ns delay */
+# define SCU_EMCDELAYCLK(n) ((n) << SCU_EMCDELAYCLK_SHIFT) /* 0=no delay, N*0x1111 = N*0.5 ns delay */
/* Bits 16-31: Reserved */
/* Pin interrupt select register 0 */
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_config.h b/nuttx/arch/arm/src/lpc43xx/lpc43_config.h
index a71fec94a..c969553cb 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_config.h
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_config.h
@@ -45,6 +45,19 @@
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
+
+/* Required configuration settings */
+
+/* There are two version of the FPU support built into the most NuttX Cortex-M4 ports.
+ * The current LPC43xx port support only one of these options, the "Non-Lazy Floating
+ * Point Register Save". As a consequence, CONFIG_ARMV7M_CMNVECTOR must be defined
+ * in *all* LPC43xx configuration files.
+ */
+
+#ifndef CONFIG_ARMV7M_CMNVECTOR
+# error "CONFIG_ARMV7M_CMNVECTOR must be defined for the LPC43xx"
+#endif
+
/* Are any UARTs enabled? */
#undef HAVE_UART
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.h b/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.h
index b3aa0c583..1ceb3f4f0 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.h
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.h
@@ -41,6 +41,7 @@
********************************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/irq.h>
/* Include the chip capabilities and GPIO definitions file */
@@ -61,7 +62,7 @@
* 1111 1100 0000 0000
* 5432 1098 7654 3210
* ---- ---- ---- ----
- * Normal: .MM. .... PPPB BBBB
+ * Normal: .MMV .... PPPB BBBB
* Interrupt: .MMG GPII PPPB BBBB
*/
@@ -83,6 +84,17 @@
#define GPIO_IS_INPUT(p) ((p) & GPIO_MODE_MASK) == GPIO_MODE_OUTPUT)
#define GPIO_IS_INTERRUPT(p) ((p) & GPIO_MODE_MASK) == GPIO_MODE_INTERRUPT)
+/* Initial value (for GPIO outputs only)
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * ...V .... .... ....
+ */
+
+#define GPIO_VALUE_ONE (1 << 12) /* Bit 12: 1=High */
+#define GPIO_VALUE_ZERO (0) /* Bit 12: 0=Low */
+
/* Group Interrupt Selection (valid only for interrupt GPIO pins):
*
* 1111 1100 0000 0000
@@ -212,9 +224,17 @@
* Public Data
********************************************************************************************/
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
/* Base addresses for each GPIO block */
-extern const uint32_t g_gpiobase[NUM_GPIO_PORTS];
+EXTERN const uint32_t g_gpiobase[NUM_GPIO_PORTS];
/********************************************************************************************
* Public Functions
@@ -298,5 +318,6 @@ EXTERN int lpc43_dumpgpio(uint16_t gpiocfg, const char *msg);
#if defined(__cplusplus)
}
#endif
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_LPC43XX_GPIO_H */
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.h b/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.h
index 133a79676..42ab5eb72 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.h
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.h
@@ -84,16 +84,16 @@
*/
#define PINCONF_FUNC_SHIFT (16) /* Bits 16-18: Alternate function number */
-#define PINCONF_FUNC_MASK (7 << PINCONF_MODE_SHIFT)
-# define PINCONF_FUNC(n) (0 << PINCONF_MODE_SHIFT)
-# define PINCONF_FUNC0 (1 << PINCONF_MODE_SHIFT)
-# define PINCONF_FUNC1 (2 << PINCONF_MODE_SHIFT)
-# define PINCONF_FUNC2 (3 << PINCONF_MODE_SHIFT)
-# define PINCONF_FUNC3 (4 << PINCONF_MODE_SHIFT)
-# define PINCONF_FUNC4 (5 << PINCONF_MODE_SHIFT)
-# define PINCONF_FUNC5 (6 << PINCONF_MODE_SHIFT)
-# define PINCONF_FUNC6 (7 << PINCONF_MODE_SHIFT)
-# define PINCONF_FUNC7 (8 << PINCONF_MODE_SHIFT)
+#define PINCONF_FUNC_MASK (7 << PINCONF_FUNC_SHIFT)
+# define PINCONF_FUNC(n) (0 << PINCONF_FUNC_SHIFT)
+# define PINCONF_FUNC0 (1 << PINCONF_FUNC_SHIFT)
+# define PINCONF_FUNC1 (2 << PINCONF_FUNC_SHIFT)
+# define PINCONF_FUNC2 (3 << PINCONF_FUNC_SHIFT)
+# define PINCONF_FUNC3 (4 << PINCONF_FUNC_SHIFT)
+# define PINCONF_FUNC4 (5 << PINCONF_FUNC_SHIFT)
+# define PINCONF_FUNC5 (6 << PINCONF_FUNC_SHIFT)
+# define PINCONF_FUNC6 (7 << PINCONF_FUNC_SHIFT)
+# define PINCONF_FUNC7 (8 << PINCONF_FUNC_SHIFT)
/* Pull-up/down resisters. These selections are available for all pins but may not
* make sense for all pins. NOTE: that both pull up and down is not precluded.
@@ -121,11 +121,11 @@
*/
#define PINCONF_DRIVE_SHIFT (12) /* Bits 12-13 = Pin drive strength */
-#define PINCONF_DRIVE_MASK (3 << PINCONF_MODE_SHIFT)
-# define PINCONF_DRIVE_NORMAL (0 << PINCONF_MODE_SHIFT)
-# define PINCONF_DRIVE_MEDIUM (1 << PINCONF_MODE_SHIFT)
-# define PINCONF_DRIVE_HIGH (2 << PINCONF_MODE_SHIFT)
-# define PINCONF_DRIVE_ULTRA (3 << PINCONF_MODE_SHIFT)
+#define PINCONF_DRIVE_MASK (3 << PINCONF_DRIVE_SHIFT)
+# define PINCONF_DRIVE_NORMAL (0 << PINCONF_DRIVE_SHIFT)
+# define PINCONF_DRIVE_MEDIUM (1 << PINCONF_DRIVE_SHIFT)
+# define PINCONF_DRIVE_HIGH (2 << PINCONF_DRIVE_SHIFT)
+# define PINCONF_DRIVE_ULTRA (3 << PINCONF_DRIVE_SHIFT)
/* Input buffer enable
*
@@ -241,6 +241,14 @@
* Public Data
********************************************************************************************/
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
/********************************************************************************************
* Public Functions
********************************************************************************************/
@@ -279,5 +287,6 @@ EXTERN int lpc43_dumppinconfig(uint32_t pinconf, const char *msg);
#if defined(__cplusplus)
}
#endif
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_LPC43XX_PINCONFIG_H */