From c7b072472b974b59b144ee4e2a3fe4cab92baf82 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 27 Jun 2012 21:35:36 +0000 Subject: Add LPC32xx memory map and interrupt numbers git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4877 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/include/lpc43xx/irq.h | 296 ++++++++++++++++++++++ nuttx/arch/arm/src/lpc43xx/chip/lpc43_memorymap.h | 244 +++++++++++++----- 2 files changed, 479 insertions(+), 61 deletions(-) create mode 100644 nuttx/arch/arm/include/lpc43xx/irq.h mode change 100755 => 100644 nuttx/arch/arm/src/lpc43xx/chip/lpc43_memorymap.h (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/include/lpc43xx/irq.h b/nuttx/arch/arm/include/lpc43xx/irq.h new file mode 100644 index 000000000..c25cfcf5c --- /dev/null +++ b/nuttx/arch/arm/include/lpc43xx/irq.h @@ -0,0 +1,296 @@ +/**************************************************************************** + * arch/arm/include/lpc43xxx/irq.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ + +/* This file should never be included directed but, rather, + * only indirectly through nuttx/irq.h + */ + +#ifndef __ARCH_ARM_INCLUDE_LPC43XX_IRQ_H +#define __ARCH_ARM_INCLUDE_LPC43XX_IRQ_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#ifndef __ASSEMBLY__ +# include +#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. + */ + +/* 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 */ + +/* 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. + * + * 28 interrupts on Port 0: p0.0 - p0.11, p0.15-p0.30 + * 14 interrupts on Port 2: p2.0 - p2.13 + * -- + * 42 + */ + +#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 */ + + /* 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) + + /* 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) + + /* 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) +#else +# define LPC43_NGPIOAIRQS (0) +#endif + +/* Total number of IRQ numbers */ + +#define NR_IRQS (LPC43_IRQ_EXTINT+LPC43_IRQ_NEXTINT+LPC43_NGPIOAIRQS) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +#ifndef __ASSEMBLY__ +typedef void (*vic_vector_t)(uint32_t *regs); +#endif + +/**************************************************************************** + * Inline functions + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif + +#endif /* __ARCH_ARM_INCLUDE_LPC43XX_IRQ_H */ + diff --git a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_memorymap.h b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_memorymap.h old mode 100755 new mode 100644 index 28216f9c4..ab069bde7 --- a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_memorymap.h +++ b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_memorymap.h @@ -1,61 +1,183 @@ -/************************************************************************************ - * arch/arm/src/lpc43xx/chip.h - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC43XX_CHIP_LPC43_MEMORYMAP_H -#define __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_MEMORYMAP_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_MEMORYMAP_H */ +/************************************************************************************ + * arch/arm/src/lpc43xx/chip.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC43XX_CHIP_LPC43_MEMORYMAP_H +#define __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_MEMORYMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Memory Map ***********************************************************************/ +/* See arch/arm/include/lpc43xx/chip.h for the actual sizes of FLASH and SRAM + * regions + */ + +#define LPC43_SHADOW_BASE 0x00000000 /* -0x0fffffff: 256Mb shadow area */ +#define LPC43_LOCSRAM_BASE 0x10000000 /* -0x1fffffff: Local SRAM and external memory */ +#define LPC43_AHBSRAM_BASE 0x20000000 /* -0x27ffffff: AHB SRAM */ +#define LPC43_DYCS0_BASE 0x28000000 /* -0x2fffffff: 128Mb dynamic external memory */ +#define LPC43_DYCS1_BASE 0x30000000 /* -0x2fffffff: 256Mb dynamic external memory */ +#define LPC43_PERIPH_BASE 0x40000000 /* -0x5fffffff: Peripherals */ +#define LPC43_DYCS2_BASE 0x60000000 /* -0x6fffffff: 256Mb dynamic external memory */ +#define LPC43_DYCS3_BASE 0x70000000 /* -0x7fffffff: 256Mb dynamic external memory */ +#define LPC43_SPIFI_DATA_BASE 0x80000000 /* -0x87ffffff: 256Mb dynamic external memory */ +#define LPC43_ARM_BASE 0xe0000000 /* -0xe00fffff: ARM private */ + +/* Local SRAM Banks and external memory */ + +#define LPC43_LOCSRAM_BANK0_BASE (LPC43_LOCSRAM_BASE + 0x00000000) +#define LPC43_LOCSRAM_BANK1_BASE (LPC43_LOCSRAM_BASE + 0x00080000) +#define LPC43_ROM_BASE (LPC43_LOCSRAM_BASE + 0x00400000) +#define LPC43_LOCSRAM_SPIFI_BASE (LPC43_LOCSRAM_BASE + 0x04000000) +#define LPC43_EXTMEM_CS0_BASE (LPC43_LOCSRAM_BASE + 0x0c000000) +#define LPC43_EXTMEM_CS1_BASE (LPC43_LOCSRAM_BASE + 0x0d000000) +#define LPC43_EXTMEM_CS2_BASE (LPC43_LOCSRAM_BASE + 0x0e000000) +#define LPC43_EXTMEM_CS3_BASE (LPC43_LOCSRAM_BASE + 0x0f000000) + +/* AHB SRAM */ + +#define LPC43_AHBSRAM_BANK0_BASE (LPC43_AHBSRAM_BASE) +#define LPC43_AHBSRAM_BANK1_BASE (LPC43_AHBSRAM_BASE + 0x00008000) +#define LPC43_AHBSRAM_BANK2_BASE (LPC43_AHBSRAM_BASE + 0x0000c000) +#define LPC43_AHBSRAM_BITBAND_BASE (LPC43_AHBSRAM_BASE + 0x0000c000) + +/* Peripherals */ + +#define LPC43_AHBPERIPH_BASE (LPC43_PERIPH_BASE + 0x00000000) +#define LPC43_RTCPERIPH_BASE (LPC43_PERIPH_BASE + 0x00040000) +#define LPC43_CLKPERIPH_BASE (LPC43_PERIPH_BASE + 0x00050000) +#define LPC43_APB0PERIPH_BASE (LPC43_PERIPH_BASE + 0x00080000) +#define LPC43_APB1PERIPH_BASE (LPC43_PERIPH_BASE + 0x000a0000) +#define LPC43_APB2PERIPH_BASE (LPC43_PERIPH_BASE + 0x000c0000) +#define LPC43_APB3PERIPH_BASE (LPC43_PERIPH_BASE + 0x000e0000) +#define LPC43_GPIO_BASE (LPC43_PERIPH_BASE + 0x000f4000) +#define LPC43_SPI_BASE (LPC43_PERIPH_BASE + 0x00100000) +#define LPC43_SGPIO_BASE (LPC43_PERIPH_BASE + 0x00101000) +#define LPC43_PERIPH_BITBAND_BASE (LPC43_PERIPH_BASE + 0x02000000) + +/* AHB Peripherals */ + +#define LPC43_SCT_BASE (LPC43_AHBPERIPH_BASE + 0x00000000) +#define LPC43_DMA_BASE (LPC43_AHBPERIPH_BASE + 0x00002000) +#define LPC43_SPIFI_PERIPH_BASE (LPC43_AHBPERIPH_BASE + 0x00003000) +#define LPC43_MMCSD_BASE (LPC43_AHBPERIPH_BASE + 0x00004000) +#define LPC43_EMC_BASE (LPC43_AHBPERIPH_BASE + 0x00005000) +#define LPC43_USB0_BASE (LPC43_AHBPERIPH_BASE + 0x00006000) +#define LPC43_USB1_BASE (LPC43_AHBPERIPH_BASE + 0x00007000) +#define LPC43_LCD_BASE (LPC43_AHBPERIPH_BASE + 0x00008000) +#define LPC43_ETHERNET_BASE (LPC43_AHBPERIPH_BASE + 0x00010000) + +/* RTC Domain Peripherals */ + +#define LPC43_ALARM_BASE (LPC43_RTCPERIPH_BASE + 0x00000000) +#define LPC43_BACKUP_BASE (LPC43_RTCPERIPH_BASE + 0x00001000) +#define LPC43_PWRMODE_BASE (LPC43_RTCPERIPH_BASE + 0x00002000) +#define LPC43_CREG_BASE (LPC43_RTCPERIPH_BASE + 0x00003000) +#define LPC43_EVROUTER_BASE (LPC43_RTCPERIPH_BASE + 0x00004000) +#define LPC43_OTPC_BASE (LPC43_RTCPERIPH_BASE + 0x00005000) +#define LPC43_RTC_BASE (LPC43_RTCPERIPH_BASE + 0x00006000) + +/* Clocking and Reset Peripherals */ + +#define LPC43_CGU_BASE (LPC43_CLKPERIPH_BASE + 0x00000000) +#define LPC43_CCU1_BASE (LPC43_CLKPERIPH_BASE + 0x00001000) +#define LPC43_CCU2_BASE (LPC43_CLKPERIPH_BASE + 0x00002000) +#define LPC43_RGU_BASE (LPC43_CLKPERIPH_BASE + 0x00003000) + +/* APB0 Peripherals */ + +#define LPC43_WWDT_BASE (LPC43_APB0PERIPH_BASE + 0x00000000) +#define LPC43_USART0_BASE (LPC43_APB0PERIPH_BASE + 0x00001000) +#define LPC43_UART1_BASE (LPC43_APB0PERIPH_BASE + 0x00002000) +#define LPC43_SSP0_BASE (LPC43_APB0PERIPH_BASE + 0x00003000) +#define LPC43_TIMER0_BASE (LPC43_APB0PERIPH_BASE + 0x00004000) +#define LPC43_TIMER1_BASE (LPC43_APB0PERIPH_BASE + 0x00005000) +#define LPC43_SCU_BASE (LPC43_APB0PERIPH_BASE + 0x00006000) +#define LPC43_GPIOINT_BASE (LPC43_APB0PERIPH_BASE + 0x00007000) +#define LPC43_GRP0INT_BASE (LPC43_APB0PERIPH_BASE + 0x00008000) +#define LPC43_GRP1INT_BASE (LPC43_APB0PERIPH_BASE + 0x00009000) + +/* APB1 Peripherals */ + +#define LPC43_MCPWM_BASE (LPC43_APB1PERIPH_BASE + 0x00000000) +#define LPC43_I2C0_BASE (LPC43_APB1PERIPH_BASE + 0x00001000) +#define LPC43_I2S0_BASE (LPC43_APB1PERIPH_BASE + 0x00002000) +#define LPC43_I2S1_BASE (LPC43_APB1PERIPH_BASE + 0x00003000) +#define LPC43_CAN1_BASE (LPC43_APB1PERIPH_BASE + 0x00004000) + +/* APB2 Peripherals */ + +#define LPC43_RITIMER_BASE (LPC43_APB2PERIPH_BASE + 0x00000000) +#define LPC43_USART2_BASE (LPC43_APB2PERIPH_BASE + 0x00001000) +#define LPC43_USART3_BASE (LPC43_APB2PERIPH_BASE + 0x00002000) +#define LPC43_TIMER2_BASE (LPC43_APB2PERIPH_BASE + 0x00003000) +#define LPC43_TIMER3_BASE (LPC43_APB2PERIPH_BASE + 0x00004000) +#define LPC43_SSP1_BASE (LPC43_APB2PERIPH_BASE + 0x00005000) +#define LPC43_QEI_BASE (LPC43_APB2PERIPH_BASE + 0x00006000) +#define LPC43_GIMA_BASE (LPC43_APB2PERIPH_BASE + 0x00007000) + +/* APB3 Peripherals */ + +#define LPC43_I2C1_BASE (LPC43_APB3PERIPH_BASE + 0x00000000) +#define LPC43_DAC_BASE (LPC43_APB3PERIPH_BASE + 0x00001000) +#define LPC43_CAN0_BASE (LPC43_APB3PERIPH_BASE + 0x00002000) +#define LPC43_ADC0_BASE (LPC43_APB3PERIPH_BASE + 0x00003000) +#define LPC43_ADC1_BASE (LPC43_APB3PERIPH_BASE + 0x00004000) + +/* ARM Private */ + +#define LPC43_SCS_BASE (LPC43_ARM_BASE + 0x0000e000) +#define LPC43_DEBUGMCU_BASE (LPC43_ARM_BASE + 0x00042000) + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_MEMORYMAP_H */ -- cgit v1.2.3