summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-31 17:10:19 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-31 17:10:19 +0000
commita08f6c421f6fe0211fc94396707013e2e748903d (patch)
tree7d4b45bc155d85d8042c93b69ef44af069b62b55
parent33a5527f2b45a9b33aacfab8b78120f9a772c6ad (diff)
downloadpx4-nuttx-a08f6c421f6fe0211fc94396707013e2e748903d.tar.gz
px4-nuttx-a08f6c421f6fe0211fc94396707013e2e748903d.tar.bz2
px4-nuttx-a08f6c421f6fe0211fc94396707013e2e748903d.zip
Add basic logic to configure MMU for LPC3131x
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2468 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/arm/up_head.S73
-rwxr-xr-xnuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c3
-rwxr-xr-xnuttx/arch/arm/src/lpc313x/lpc313x_boot.c100
-rwxr-xr-xnuttx/arch/arm/src/lpc313x/lpc313x_dma.h4
-rwxr-xr-xnuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h362
-rwxr-xr-xnuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h4
-rwxr-xr-xnuttx/arch/arm/src/lpc313x/lpc313x_nand.h4
-rwxr-xr-xnuttx/configs/ea3131/ostest/defconfig30
-rw-r--r--nuttx/configs/mx1ads/ostest/defconfig15
-rw-r--r--nuttx/configs/ntosd-dm320/nettest/defconfig15
-rw-r--r--nuttx/configs/ntosd-dm320/nsh/defconfig15
-rw-r--r--nuttx/configs/ntosd-dm320/ostest/defconfig15
-rw-r--r--nuttx/configs/ntosd-dm320/poll/defconfig15
-rw-r--r--nuttx/configs/ntosd-dm320/thttpd/defconfig15
-rw-r--r--nuttx/configs/ntosd-dm320/udp/defconfig15
-rw-r--r--nuttx/configs/ntosd-dm320/uip/defconfig15
16 files changed, 528 insertions, 172 deletions
diff --git a/nuttx/arch/arm/src/arm/up_head.S b/nuttx/arch/arm/src/arm/up_head.S
index 33d00366c..3226a86ec 100644
--- a/nuttx/arch/arm/src/arm/up_head.S
+++ b/nuttx/arch/arm/src/arm/up_head.S
@@ -90,13 +90,14 @@
* Definitions
****************************************************************************/
-/* The physical address of the beginning of SDRAM is provided by
- * CONFIG_DRAM_START. The size of installed SDRAM is provided by
- * CONFIG_DRAM_SIZE. The virtual address of SDRAM is provided by
- * CONFIG_DRAM_VSTART.
+/* EXE_NSECTIONS determines the number of 1Mb pages to map for the executable
+ * address region. This is based on CONFIG_DRAM_SIZE. For most ARM9
+ * architectures, CONFIG_DRAM_SIZE describes the size of installed SDRAM.
+ * But for other architectures, this might refer to the size of FLASH or
+ * SRAM regions. (bad choice of naming).
*/
-#define NSDRAM_SECTIONS (CONFIG_DRAM_SIZE >> 20)
+#define EXE_NSECTIONS ((CONFIG_DRAM_SIZE+0x000fffff) >> 20)
/****************************************************************************
* Assembly Macros
@@ -127,12 +128,11 @@
* Name: __start
****************************************************************************/
-/* We assume the bootloader has already initialized most of the h/w for
- * us and that only leaves us having to do some os specific things
- * below.
+/* We assume the bootloader has already initialized most of the h/w for us
+ * and that only leaves us having to do some os specific things below.
*/
.text
- .global __start
+ .global __start
.type __start, #function
__start:
/* Make sure that we are in SVC mode with all IRQs disabled */
@@ -159,16 +159,15 @@ __start:
teq r0, r2
bne .Lpgtableclear
- /* Create identity mapping for first MB section to support
- * this startup logic executing out of the physical address
- * space. This identity mapping will be removed by .Lvstart
- * (see below).
+ /* Create identity mapping for first MB section to support this startup
+ * logic executing out of the physical address space. This identity
+ * mapping will be removed by .Lvstart (see below).
*/
mksection r0, r4 /* r0=phys. base section */
ldr r1, .LCmmuflags /* FLGS=MMU_MEMFLAGS */
- add r3, r1, r0 /* r3=flags + base */
- str r3, [r4, r0, lsr #18] /* identity mapping */
+ add r3, r1, r0 /* r3=flags + base */
+ str r3, [r4, r0, lsr #18] /* identity mapping */
/* Create a "normal" single section mapping for the first
* MB of memory. Now, we have the first 1MB mapping to
@@ -179,13 +178,13 @@ __start:
ldr r2, .LCvpgtable /* r2=virt. page table */
mksection r0, r2 /* r0=virt. base section */
- str r3, [r4, r0, lsr #18] /* identity mapping */
+ str r3, [r4, r0, lsr #18] /* identity mapping */
/* The following logic will set up the ARM920/ARM926 for normal operation */
mov r0, #0
mcr p15, 0, r0, c7, c7 /* Invalidate I,D caches */
- mcr p15, 0, r0, c7, c10, 4 /* Drain write buffer */
+ mcr p15, 0, r0, c7, c10, 4 /* Drain write buffer */
mcr p15, 0, r0, c8, c7 /* Invalidate I,D TLBs */
mcr p15, 0, r4, c2, c0 /* Load page table pointer */
@@ -200,7 +199,7 @@ __start:
ldr lr, .LCvstart /* Abs. virtual address */
- mov r0, #0x1f /* Domains 0, 1 = client */
+ mov r0, #0x1f /* Domains 0, 1 = client */
mcr p15, 0, r0, c3, c0 /* Load domain access register */
mrc p15, 0, r0, c1, c0 /* Get control register */
@@ -245,9 +244,9 @@ __start:
mov pc, lr
-/**********************************************************************************
+/****************************************************************************
* PC_Relative Data
- **********************************************************************************/
+ ****************************************************************************/
/* These addresses are all virtual address */
@@ -265,9 +264,9 @@ __start:
.long CONFIG_DRAM_VSTART /* Virtual start of DRAM */
.size _start, .-_start
-/**********************************************************************************
+/****************************************************************************
* Name: .Lvstart
- **********************************************************************************/
+ ***************************************************************************/
/* The following is executed after the MMU has been enabled. This uses
* absolute addresses; this is not position independent.
@@ -282,16 +281,15 @@ __start:
ldr r4, .LCvpgtable /* r4=virtual page table */
ldr r1, .LCppgtable /* r1=phys. page table */
mksection r3, r1 /* r2=phys. base addr */
- mov r0, #0 /* flags + base = 0 */
- str r0, [r4, r3, lsr #18] /* Undo identity mapping */
+ mov r0, #0 /* flags + base = 0 */
+ str r0, [r4, r3, lsr #18] /* Undo identity mapping */
- /* Now setup the pagetables for our normal SDRAM mappings
- * mapped region. We round NUTTX_START_VADDR down to the
- * nearest megabyte boundary.
+ /* Now setup the pagetables for our normal SDRAM mappings mapped region.
+ * We round NUTTX_START_VADDR down to the nearest megabyte boundary.
*/
ldr r1, .LCmmuflags /* FLGS=MMU_MEMFLAGS */
- add r3, r3, r1 /* r3=flags + base */
+ add r3, r3, r1 /* r3=flags + base */
add r0, r4, #(NUTTX_START_VADDR & 0xff000000) >> 18
bic r2, r3, #0x00f00000
@@ -300,9 +298,11 @@ __start:
add r0, r0, #(NUTTX_START_VADDR & 0x00f00000) >> 18
str r3, [r0], #4
- /* Now map the remaining NSDRAM_SECTIONS-1 SDRAM sections */
+ /* Now map the remaining EXE_NSECTIONS-1 sections of the executable
+ * memory region.
+ */
- .rept NSDRAM_SECTIONS-1
+ .rept EXE_NSECTIONS-1
add r3, r3, #SECTION_SIZE
str r3, [r0], #4
.endr
@@ -331,12 +331,13 @@ __start:
b os_start
/* Variables:
- * _sbss is the start of the BSS region (see ld.script)
- * _ebss is the end of the BSS regsion (see ld.script)
- * The idle task stack starts at the end of BSS and is
- * of size CONFIG_IDLETHREAD_STACKSIZE. The heap continues
- * from there until the end of memory. See g_heapbase
- * below.
+ *
+ * _sbss is the start of the BSS region (see ld.script)
+ * _ebss is the end of the BSS regsion (see ld.script)
+ *
+ * The idle task stack starts at the end of BSS and is of size
+ * CONFIG_IDLETHREAD_STACKSIZE. The heap continues from there until the
+ * end of memory. See g_heapbase below.
*/
.Linitparms:
diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c b/nuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c
index ec0d924b8..f87d67ab6 100755
--- a/nuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c
+++ b/nuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c
@@ -45,6 +45,7 @@
#include <nuttx/arch.h>
#include <arch/board/board.h>
+#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "lpc313x_memorymap.h"
@@ -145,7 +146,7 @@ void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
{
up_ledon(LED_HEAPALLOCATE);
*heap_start = (FAR void*)g_heapbase;
- *heap_size = (LPC313X_SRAM_VADDR + CONFIG_DRAM_SIZE) - g_heapbase;
+ *heap_size = (LPC313X_INTSRAM_VSECTION + LPC313X_ISRAM_SIZE) - g_heapbase;
}
/************************************************************************
diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c b/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c
index 9141fdf24..758e38430 100755
--- a/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c
+++ b/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c
@@ -78,28 +78,48 @@ extern uint32_t _vector_end; /* End+1 of vector block */
* Private Variables
************************************************************************************/
-#warning "All MMU logic commented out"
-#if 0 /* Not ready yet */
+/* This table describes how to map a set of 1Mb pages to space the physical address
+ * space of the LPCD313x.
+ */
+
+#ifndef CONFIG_ARM_ROMPGTABLE
static const struct section_mapping_s section_mapping[] =
{
- { DM320_PERIPHERALS_PSECTION, DM320_PERIPHERALS_VSECTION,
- DM320_PERIPHERALS_MMUFLAGS, DM320_PERIPHERALS_NSECTIONS},
- { DM320_FLASH_PSECTION, DM320_FLASH_VSECTION,
- DM320_FLASH_MMUFLAGS, DM320_FLASH_NSECTIONS},
- { DM320_CFI_PSECTION, DM320_CFI_VSECTION,
- DM320_CFI_MMUFLAGS, DM320_CFI_NSECTIONS},
- { DM320_SSFDC_PSECTION, DM320_SSFDC_VSECTION,
- DM320_SSFDC_MMUFLAGS, DM320_SSFDC_NSECTIONS},
- { DM320_CE1_PSECTION, DM320_CE1_VSECTION,
- DM320_CE1_MMUFLAGS, DM320_CE1_NSECTIONS},
- { DM320_CE2_PSECTION, DM320_CE2_VSECTION,
- DM320_CE2_MMUFLAGS, DM320_CE2_NSECTIONS},
- { DM320_VLYNQ_PSECTION, DM320_VLYNQ_VSECTION,
- DM320_VLYNQ_MMUFLAGS, DM320_VLYNQ_NSECTIONS},
- { DM320_USBOTG_PSECTION, DM320_USBOTG_VSECTION,
- DM320_USBOTG_MMUFLAGS, DM320_USBOTG_NSECTIONS}
+ { LPC313X_SHADOWSPACE_PSECTION, LPC313X_SHADOWSPACE_VSECTION,
+ LPC313X_SHADOWSPACE_MMUFLAGS, LPC313X_SHADOWSPACE_NSECTIONS},
+ { LPC313X_INTSRAM_PSECTION, LPC313X_INTSRAM_VSECTION,
+ LPC313X_INTSRAM_MMUFLAGS, LPC313X_INTSRAM_NSECTIONS},
+ { LPC313X_APB0_PSECTION, LPC313X_APB0_VSECTION,
+ LPC313X_APB0_MMUFLAGS, LPC313X_APB0_NSECTIONS},
+ { LPC313X_APB1_PSECTION, LPC313X_APB1_VSECTION,
+ LPC313X_APB1_MMUFLAGS, LPC313X_APB1_NSECTIONS},
+ { LPC313X_APB2_PSECTION, LPC313X_APB2_VSECTION,
+ LPC313X_APB2_MMUFLAGS, LPC313X_APB2_NSECTIONS},
+ { LPC313X_APB3_PSECTION, LPC313X_APB3_VSECTION,
+ LPC313X_APB3_MMUFLAGS, LPC313X_APB3_NSECTIONS},
+ { LPC313X_APB4MPMC_PSECTION, LPC313X_APB4MPMC_VSECTION,
+ LPC313X_APB4MPMC_MMUFLAGS, LPC313X_APB4MPMC_NSECTIONS},
+ { LPC313X_MCI_PSECTION, LPC313X_MCI_VSECTION,
+ LPC313X_MCI_MMUFLAGS, LPC313X_MCI_NSECTIONS},
+ { LPC313X_USBOTG_PSECTION, LPC313X_USBOTG_VSECTION,
+ LPC313X_USBOTG_MMUFLAGS, LPC313X_USBOTG_NSECTIONS},
+#if defined(CONFIG_LPC313X_EXTSRAM0) && CONFIG_LPC313X_EXTSRAM0SIZE > 0
+ { LPC313X_EXTSRAM_PSECTION, LPC313X_EXTSRAM_VSECTION,
+ LPC313X_EXTSDRAM_MMUFLAGS, LPC313X_EXTSRAM_NSECTIONS},
+#endif
+#if defined(CONFIG_LPC313X_EXTSDRAM) && CONFIG_LPC313X_EXTSDRAMSIZE > 0
+ { LPC313X_EXTSDRAM0_PSECTION, LPC313X_EXTSDRAM0_VSECTION,
+ LPC313X_EXTSDRAM_MMUFLAGS, LPC313X_EXTSDRAM0_NSECTIONS},
+#endif
+ { LPC313X_INTC_PSECTION, LPC313X_INTC_VSECTION,
+ LPC313X_INTC_MMUFLAGS, LPC313X_INTC_NSECTIONS},
+#ifdef CONFIG_LPC313X_EXTNAND
+ { LPC313X_NAND_PSECTION, LPC313X_NAND_VSECTION
+ LPC313X_NAND_MMUFLAGS, LPC313X_NAND_NSECTIONS},
+#endif
};
#define NMAPPINGS (sizeof(section_mapping) / sizeof(struct section_mapping_s))
+#endif
/************************************************************************************
* Private Functions
@@ -109,6 +129,7 @@ static const struct section_mapping_s section_mapping[] =
* Name: up_setlevel1entry
************************************************************************************/
+#ifndef CONFIG_ARM_ROMPGTABLE
static inline void up_setlevel1entry(uint32_t paddr, uint32_t vaddr, uint32_t mmuflags)
{
uint32_t *pgtable = (uint32_t*)PGTABLE_BASE_VADDR;
@@ -118,6 +139,7 @@ static inline void up_setlevel1entry(uint32_t paddr, uint32_t vaddr, uint32_t mm
pgtable[index] = (paddr | mmuflags);
}
+#endif
/************************************************************************************
* Name: up_setlevel2coarseentry
@@ -145,6 +167,7 @@ static inline void up_setlevel2coarseentry(uint32_t ctabvaddr, uint32_t paddr,
* Name: up_setupmappings
************************************************************************************/
+#ifndef CONFIG_ARM_ROMPGTABLE
static void up_setupmappings(void)
{
int i, j;
@@ -163,16 +186,27 @@ static void up_setupmappings(void)
}
}
}
+#endif
/************************************************************************************
* Name: up_vectormapping
+ *
+ * Description:
+ * Setup a special mapping for the interrupt vectors when (1) the interrupt
+ * vectors are not positioned in ROM, and when (2) the interrupt vectors are
+ * located at the high address, 0xffff0000. When the interrupt vectors are located
+ * in ROM, we just have to assume that they were set up correctly; When vectors
+ * are located in low memory, 0x00000000, the shadow memory region will be mapped
+ * to support them.
+ *
************************************************************************************/
+#if !defined(CONFIG_ARM_ROMPGTABLE) && !defined(CONFIG_ARM_LOWVECTORS)
static void up_vectormapping(void)
{
- uint32_t vector_paddr = DM320_IRAM_PADDR;
- uint32_t vector_vaddr = DM320_VECTOR_VADDR;
- uint32_t end_paddr = vector_paddr + DM320_IRAM_SIZE;
+ uint32_t vector_paddr = LPC313X_VECTOR_PADDR;
+ uint32_t vector_vaddr = LPC313X_VECTOR_VADDR;
+ uint32_t end_paddr = vector_paddr + VECTOR_TABLE_SIZE;
/* We want to keep our interrupt vectors and interrupt-related logic in zero-wait
* state internal RAM (IRAM). The DM320 has 16Kb of IRAM positioned at physical
@@ -181,20 +215,18 @@ static void up_vectormapping(void)
while (vector_paddr < end_paddr)
{
- up_setlevel2coarseentry(PGTABLE_COARSE_BASE_VADDR,
- vector_paddr,
- vector_vaddr,
- MMU_L2_VECTORFLAGS);
+ up_setlevel2coarseentry(PGTABLE_COARSE_BASE_VADDR, vector_paddr,
+ vector_vaddr, MMU_L2_VECTORFLAGS);
vector_paddr += 4096;
vector_vaddr += 4096;
}
/* Now set the level 1 descriptor to refer to the level 2 coarse page table. */
- up_setlevel1entry(PGTABLE_COARSE_BASE_PADDR,
- DM320_VECTOR_VCOARSE,
- MMU_L1_VECTORFLAGS);
+ up_setlevel1entry(PGTABLE_COARSE_BASE_PADDR, LPC313X_VECTOR_VCOARSE,
+ MMU_L1_VECTORFLAGS);
}
+#endif
/************************************************************************************
* Name: up_copyvectorblock
@@ -204,14 +236,13 @@ static void up_copyvectorblock(void)
{
uint32_t *src = (uint32_t*)&_vector_start;
uint32_t *end = (uint32_t*)&_vector_end;
- uint32_t *dest = (uint32_t*)VECTOR_BASE;
+ uint32_t *dest = (uint32_t*)LPC313X_VECTOR_VADDR;
while (src < end)
{
*dest++ = *src++;
}
}
-#endif /* 0 */
/************************************************************************************
* Public Functions
@@ -219,26 +250,27 @@ static void up_copyvectorblock(void)
void up_boot(void)
{
-#warning "All MMU logic commented out"
-#if 0 /* Not ready yet */
/* __start provided the basic MMU mappings for SDRAM. Now provide mappings for all
* IO regions (Including the vector region).
*/
+#ifndef CONFIG_ARM_ROMPGTABLE
up_setupmappings();
/* Provide a special mapping for the IRAM interrupt vector positioned in high
* memory.
*/
+#ifndef CONFIG_ARM_LOWVECTORS
up_vectormapping();
+#endif
+#endif
/* Setup up vector block. _vector_start and _vector_end are exported from
* up_vector.S
*/
up_copyvectorblock();
-#endif /* 0 */
/* Reset all clocks */
@@ -255,7 +287,7 @@ void up_boot(void)
/* Map first 4KB of ARM space to ISRAM area */
- putreg32(LPC313X_INTSRAM0_PSECTION, LPC313X_SYSCREG_ARM926SHADOWPTR);
+ putreg32(LPC313X_INTSRAM0_PADDR, LPC313X_SYSCREG_ARM926SHADOWPTR);
/* Perform common, low-level chip initialization (might do nothing) */
diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_dma.h b/nuttx/arch/arm/src/lpc313x/lpc313x_dma.h
index 8efb74e53..a36edeffe 100755
--- a/nuttx/arch/arm/src/lpc313x/lpc313x_dma.h
+++ b/nuttx/arch/arm/src/lpc313x/lpc313x_dma.h
@@ -49,8 +49,8 @@
/* DMA register base address offset into the APB4 domain ****************************************/
-#define LPC313X_DMA_VBASE (LPC313X_APB4_VSECTION+LPC313X_APB4_DMA_OFFSET)
-#define LPC313X_DMA_PBASE (LPC313X_APB4_PSECTION+LPC313X_APB4_DMA_OFFSET)
+#define LPC313X_DMA_VBASE (LPC313X_APB4_VADDR+LPC313X_APB4_DMA_OFFSET)
+#define LPC313X_DMA_PBASE (LPC313X_APB4_PADDR+LPC313X_APB4_DMA_OFFSET)
/* DMA channel offsets (with respect to the DMA register base address) **************************/
diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h b/nuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h
index 18839bf01..6f639641c 100755
--- a/nuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h
+++ b/nuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h
@@ -48,102 +48,282 @@
/* LPC313X Physical (unmapped) Memory Map */
-#define LPC313X_SHADOWSPACE_PSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */
- /* 0x00001000-0xff027fff: Reserved */
-#define LPC313X_INTSRAM0_PSECTION 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */
-#define LPC313X_INTSRAM1_PSECTION 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */
- /* 0x11058000-11ffffffff: Reserved */
-#define LPC313X_INTSROM0_PSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */
- /* 0x12020000-0x12ffffff: Reserved */
-#define LPC313X_APB0_PSECTION 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */
-#define LPC313X_APB1_PSECTION 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */
- /* 0x1300c000-0x14ffffff: Reserved */
-#define LPC313X_APB2_PSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */
-#define LPC313X_APB3_PSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */
-#define LPC313X_APB4_PSECTION 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */
-#define LPC313X_MPMC_PSECTION 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */
- /* 0x17009000-0x17ffffff: Reserved */
-#define LPC313X_MCI_PSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */
- /* 0x18000900-0x18ffffff: Reserved */
-#define LPC313X_USBOTG_PSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */
- /* 0x19001000-0x1fffffff: Reserved */
-#define LPC313X_EXTSRAM0_PSECTION 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */
-#define LPC313X_EXTSRAM1_PSECTION 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */
-#define LPC313X_EXTSDRAM0_PSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */
- /* 0x40000000-0x5fffffff: Reserved */
-#define LPC313X_INTC_PSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */
- /* 0x60001000-0x6fffffff: Reserved */
-#define LPC313X_NAND_PSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */
- /* 0x70000800-0xffffffff: Reserved */
+#define LPC313X_SHADOWSPACE_PSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */
+ /* 0x00001000-0xff027fff: Reserved */
+#define LPC313X_INTSRAM_PSECTION 0x11028000 /* Internal SRAM 0+1 192Kb */
+# define LPC313X_INTSRAM0_PADDR 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */
+# define LPC313X_INTSRAM1_PADDR 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */
+ /* 0x11058000-11ffffffff: Reserved */
+#define LPC313X_INTSROM0_PSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */
+ /* 0x12020000-0x12ffffff: Reserved */
+#define LPC313X_APB0_PSECTION 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */
+#define LPC313X_APB1_PSECTION 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */
+ /* 0x1300c000-0x14ffffff: Reserved */
+#define LPC313X_APB2_PSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */
+#define LPC313X_APB3_PSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */
+#define LPC313X_APB4MPMC_PSECTION 0x17000000 /* 8Kb */
+# define LPC313X_APB4_PADDR 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */
+# define LPC313X_MPMC_PADDR 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */
+ /* 0x17009000-0x17ffffff: Reserved */
+#define LPC313X_MCI_PSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */
+ /* 0x18000900-0x18ffffff: Reserved */
+#define LPC313X_USBOTG_PSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */
+ /* 0x19001000-0x1fffffff: Reserved */
+#define LPC313X_EXTSRAM_PSECTION 0x20000000 /* 64-128Kb */
+# define LPC313X_EXTSRAM0_PADDR 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */
+# define LPC313X_EXTSRAM1_PADDR 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */
+#define LPC313X_EXTSDRAM0_PSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */
+ /* 0x40000000-0x5fffffff: Reserved */
+#define LPC313X_INTC_PSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */
+ /* 0x60001000-0x6fffffff: Reserved */
+#define LPC313X_NAND_PSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */
+ /* 0x70000800-0xffffffff: Reserved */
/* APB0-4 Domain Offsets */
-#define LPC313X_APB0_EVNTRTR_OFFSET 0x00000000 /* Event Router */
-#define LPC313X_APB0_ADC_OFFSET 0x00002000 /* ADC 10-bit */
-#define LPC313X_APB0_WDT_OFFSET 0x00002400 /* WDT */
-#define LPC313X_APB0_SYSCREG_OFFSET 0x00002800 /* SYSCREG block */
-#define LPC313X_APB0_IOCONFIG_OFFSET 0x00003000 /* IOCONFIG */
-#define LPC313X_APB0_GCU_OFFSET 0x00004000 /* GCU */
- /* 0x00005000 Reserved */
-#define LPC313X_APB0_RNG_OFFSET 0x00006000 /* RNG */
-
-#define LPC313X_APB1_TIMER0_OFFSET 0x00000000 /* TIMER0 */
-#define LPC313X_APB1_TIMER1_OFFSET 0x00000400 /* TIMER1 */
-#define LPC313X_APB1_TIMER2_OFFSET 0x00000800 /* TIMER2 */
-#define LPC313X_APB1_TIMER3_OFFSET 0x00000c00 /* TIMER3 */
-#define LPC313X_APB1_PWM_OFFSET 0x00001000 /* PWM */
-#define LPC313X_APB1_I2C0_OFFSET 0x00002000 /* I2C0 */
-#define LPC313X_APB1_I2C1_OFFSET 0x00002400 /* I2C1 */
-
-#define LPC313X_APB2_PCM_OFFSET 0x00000000 /* PCM */
-#define LPC313X_APB2_LCD_OFFSET 0x00000400 /* LCD */
- /* 0x00000800 Reserved */
-#define LPC313X_APB2_UART_OFFSET 0x00001000 /* UART */
-#define LPC313X_APB2_SPI_OFFSET 0x00002000 /* SPI */
- /* 0x00003000 Reserved */
-
-#define LPC313X_APB3_I2SCONFIG_OFFSET 0x00000000 /* I2S System Configuration */
-#define LPC313X_APB3_I2STX0_OFFSET 0x00000080 /* I2S TX0 */
-#define LPC313X_APB3_I2STX1_OFFSET 0x00000100 /* I2S TX1 */
-#define LPC313X_APB3_I2SRX0_OFFSET 0x00000180 /* I2S RX0 */
-#define LPC313X_APB3_I2SRX1_OFFSET 0x00000200 /* I2S RX1 */
- /* 0x00000280 Reserved */
-
-#define LPC313X_APB4_DMA_OFFSET 0x00000000 /* DMA */
-#define LPC313X_APB4_NAND_OFFSET 0x00000800 /* NAND FLASH Controller */
- /* 0x00001000 Reserved */
-
-/* Sizes of sections/regions */
-/* To be provided */
-
-/* LPC313X Virtual (mapped) Memory Map */
-/* Temporary for now, just to get through compilation */
-
-#define LPC313X_SHADOWSPACE_VSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */
-#define LPC313X_INTSRAM0_VSECTION 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */
-#define LPC313X_INTSRAM1_VSECTION 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */
-# define LPC313X_SRAM_VADDR LPC313X_INTSRAM0_VSECTION
-#define LPC313X_INTSROM0_VSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */
-#define LPC313X_APB0_VSECTION 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */
-#define LPC313X_APB1_VSECTION 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */
-#define LPC313X_APB2_VSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */
-#define LPC313X_APB3_VSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */
-#define LPC313X_APB4_VSECTION 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */
-#define LPC313X_MPMC_VSECTION 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */
-#define LPC313X_MCI_VSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */
-#define LPC313X_USBOTG_VSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */
-#define LPC313X_EXTSRAM0_VSECTION 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */
-#define LPC313X_EXTSRAM1_VSECTION 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */
-#define LPC313X_EXTSDRAM0_VSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */
-#define LPC313X_INTC_VSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */
-#define LPC313X_NAND_VSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */
-
-/* The NuttX entry point starts at an offset from the virtual beginning of DRAM.
- * This offset reserves space for the MMU page cache.
+#define LPC313X_APB0_EVNTRTR_OFFSET 0x00000000 /* Event Router */
+#define LPC313X_APB0_ADC_OFFSET 0x00002000 /* ADC 10-bit */
+#define LPC313X_APB0_WDT_OFFSET 0x00002400 /* WDT */
+#define LPC313X_APB0_SYSCREG_OFFSET 0x00002800 /* SYSCREG block */
+#define LPC313X_APB0_IOCONFIG_OFFSET 0x00003000 /* IOCONFIG */
+#define LPC313X_APB0_GCU_OFFSET 0x00004000 /* GCU */
+ /* 0x00005000 Reserved */
+#define LPC313X_APB0_RNG_OFFSET 0x00006000 /* RNG */
+
+#define LPC313X_APB1_TIMER0_OFFSET 0x00000000 /* TIMER0 */
+#define LPC313X_APB1_TIMER1_OFFSET 0x00000400 /* TIMER1 */
+#define LPC313X_APB1_TIMER2_OFFSET 0x00000800 /* TIMER2 */
+#define LPC313X_APB1_TIMER3_OFFSET 0x00000c00 /* TIMER3 */
+#define LPC313X_APB1_PWM_OFFSET 0x00001000 /* PWM */
+#define LPC313X_APB1_I2C0_OFFSET 0x00002000 /* I2C0 */
+#define LPC313X_APB1_I2C1_OFFSET 0x00002400 /* I2C1 */
+
+#define LPC313X_APB2_PCM_OFFSET 0x00000000 /* PCM */
+#define LPC313X_APB2_LCD_OFFSET 0x00000400 /* LCD */
+ /* 0x00000800 Reserved */
+#define LPC313X_APB2_UART_OFFSET 0x00001000 /* UART */
+#define LPC313X_APB2_SPI_OFFSET 0x00002000 /* SPI */
+ /* 0x00003000 Reserved */
+
+#define LPC313X_APB3_I2SCONFIG_OFFSET 0x00000000 /* I2S System Configuration */
+#define LPC313X_APB3_I2STX0_OFFSET 0x00000080 /* I2S TX0 */
+#define LPC313X_APB3_I2STX1_OFFSET 0x00000100 /* I2S TX1 */
+#define LPC313X_APB3_I2SRX0_OFFSET 0x00000180 /* I2S RX0 */
+#define LPC313X_APB3_I2SRX1_OFFSET 0x00000200 /* I2S RX1 */
+ /* 0x00000280 Reserved */
+
+#define LPC313X_APB4_DMA_OFFSET 0x00000000 /* DMA */
+#define LPC313X_APB4_NAND_OFFSET 0x00000800 /* NAND FLASH Controller */
+ /* 0x00001000 Reserved */
+
+/* Sizes of memory regions in bytes */
+
+#define LPC313X_SHADOWSPACE_SIZE (4*1024)
+#define LPC313X_INTSRAM0_SIZE (96*1024)
+#define LPC313X_INTSRAM1_SIZE (96*1024)
+#define LPC313X_INTSROM0_SIZE (128*1024)
+#define LPC313X_APB0_SIZE (32*1024)
+#define LPC313X_APB1_SIZE (16*1024)
+#define LPC313X_APB2_SIZE (16*1024)
+#define LPC313X_APB3_SIZE (1*1024)
+#define LPC313X_APB4_SIZE (4*1024)
+#define LPC313X_MPMC_SIZE (4*1024)
+#define LPC313X_APB4MPMC_SIZE (LPC313X_APB4_SIZE+LPC313X_MPMC_SIZE)
+#define LPC313X_MCI_SIZE (1*1024)
+#define LPC313X_USBOTG_SIZE (4*1024)
+#define LPC313X_INTC_SIZE (4*1024)
+#define LPC313X_NAND_SIZE (2*1024)
+
+#if defined(CONFIG_ARCH_CHIP_LPC3131)
+# define LPC313X_ISRAM_SIZE (LPC313X_INTSRAM0_SIZE+LPC313X_INTSRAM1_SIZE)
+#elif defined()
+# define LPC313X_ISRAM_SIZE LPC313X_INTSRAM0_SIZE
+#else
+# error "Unsupported LPC313X architecture"
+#endif
+
+/* Convert size in bytes to number of sections (in Mb). */
+
+#define _NSECTIONS(b) (((b)+0x000fffff) >> 20)
+
+/* Sizes of sections/regions. The boot logic in lpc313x_boot.c, will select
+ * 1Mb level 1 MMU mappings to span the entire physical address space.
+ * The definitiions below specifiy the number of 1Mb entries that are
+ * required to span a particular address region.
+ */
+
+#define LPC313X_SHADOWSPACE_NSECTIONS 1 /* 4Kb - <1 section */
+#define LPC313X_INTSRAM_NSECTIONS 1 /* 96 or 192Kb - <1 section */
+#define LPC313X_APB0_NSECTIONS 1 /* 32Kb - <1 section */
+#define LPC313X_APB1_NSECTIONS 1 /* 16Kb - <1 section */
+#define LPC313X_APB2_NSECTIONS 1 /* 16Kb - <1 section */
+#define LPC313X_APB3_NSECTIONS 1 /* 1Kb - <1 section */
+#define LPC313X_APB4MPMC_NSECTIONS 1 /* 8Kb - <1 section */
+#define LPC313X_MCI_NSECTIONS 1 /* 1Kb - <1 section */
+#define LPC313X_USBOTG_NSECTIONS 1 /* 4Kb - <1 section */
+#define LPC313X_EXTSRAM_NSECTIONS 1 /* 64-128Kb - <1 section */
+#define LPC313X_INTC_NSECTIONS 1 /* 4Kb - <1 section */
+#define LPC313X_NAND_NSECTIONS 1 /* 2Kb - <1 section */
+
+/* External SDRAM is a special case -- the number of sections depends upon
+ * the size of the SDRAM installed.
+ */
+
+#if defined(CONFIG_LPC313X_EXTSDRAM) && CONFIG_LPC313X_EXTSDRAMSIZE > 0
+# define LPC313X_EXTSDRAM0_NSECTIONS _NSECTIONS(CONFIG_LPC313X_EXTSDRAMSIZE)
+#endif
+
+/* Section MMU Flags */
+
+#define LPC313X_SHADOWSPACE_MMUFLAGS MMU_MEMFLAGS
+#define LPC313X_INTSRAM_MMUFLAGS MMU_MEMFLAGS
+#define LPC313X_APB0_MMUFLAGS MMU_IOFLAGS
+#define LPC313X_APB1_MMUFLAGS MMU_IOFLAGS
+#define LPC313X_APB2_MMUFLAGS MMU_IOFLAGS
+#define LPC313X_APB3_MMUFLAGS MMU_IOFLAGS
+#define LPC313X_APB4MPMC_MMUFLAGS MMU_IOFLAGS
+#define LPC313X_MCI_MMUFLAGS MMU_IOFLAGS
+#define LPC313X_USBOTG_MMUFLAGS MMU_IOFLAGS
+#define LPC313X_EXTSRAM_MMUFLAGS MMU_MEMFLAGS
+#define LPC313X_EXTSDRAM_MMUFLAGS MMU_MEMFLAGS
+#define LPC313X_INTC_MMUFLAGS MMU_IOFLAGS
+#define LPC313X_NAND_MMUFLAGS MMU_IOFLAGS
+
+/* LPC313X Virtual (mapped) Memory Map. These are the mappings that will
+ * be created if the page table lies in RAM. If the platform has another,
+ * read-only, pre-initialized page table (perhaps in ROM), then the board.h
+ * file must provide these definitions.
+ */
+
+#ifndef CONFIG_ARM_ROMPGTABLE
+# define LPC313X_SHADOWSPACE_VSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */
+# define LPC313X_INTSRAM_VSECTION 0x11028000 /* Internal SRAM 96Kb-192Kb */
+# define LPC313X_INTSRAM0_VADDR 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */
+# define LPC313X_INTSRAM1_VADDR 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */
+# define LPC313X_INTSROM0_VSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */
+# define LPC313X_APB0_VSECTION 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */
+# define LPC313X_APB1_VSECTION 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */
+# define LPC313X_APB2_VSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */
+# define LPC313X_APB3_VSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */
+# define LPC313X_APB4MPMC_VSECTION 0x17000000 /* 8Kb */
+# define LPC313X_APB4_VADDR 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */
+# define LPC313X_MPMC_VADDR 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */
+# define LPC313X_MCI_VSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */
+# define LPC313X_USBOTG_VSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */
+# define LPC313X_EXTSRAM_VSECTION 0x20020000 /* 64-128Kb */
+# define LPC313X_EXTSRAM0_VADDR 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */
+# define LPC313X_EXTSRAM1_VADDR 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */
+# define LPC313X_EXTSDRAM0_VSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */
+# define LPC313X_INTC_VSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */
+# define LPC313X_NAND_VSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */
+#endif
+
+/* The boot logic will create a temporarily mapping based on where NuttX is
+ * executing in memory. In this case, NuttX could be running from NOR FLASH,
+ * SDRAM, external SRAM, or ISRAM.
*/
-/* For now, just to get through the compilation */
+#if defined(CONFIG_BOOT_RUNFROMFLASH)
+# define NUTTX_START_VADDR LPC313X_MPMC_VADDR
+#elif defined(CONFIG_BOOT_RUNFROMSDRAM)
+# define NUTTX_START_VADDR LPC313X_EXTSDRAM0_VSECTION
+#elif defined(CONFIG_BOOT_RUNFROMEXTSRAM)
+# define NUTTX_START_VADDR LPC313X_EXTSRAM0_VADDR
+#else /* CONFIG_BOOT_RUNFROMISRAM */
+# define NUTTX_START_VADDR LPC313X_INTSRAM0_VADDR
+#endif
+
+/* Determine the address of the MMU page table. We will try to place that page
+ * table at the beginng of ISRAM0 if the vectors are at the high address, 0xffff:0000
+ * or at the end of ISRAM1 (or ISRAM0 on a LPC3130) if the vectors are at 0x0000:0000
+ *
+ * Or... the user may specify the address of the page table explicitly be defining
+ * CONFIG_PGTABLE_VADDR and CONFIG_PGTABLE_PADDR in the configuration or board.h file.
+ */
+
+#if !defined(PGTABLE_BASE_PADDR) || !defined(PGTABLE_BASE_VADDR)
+
+ /* Sanity check.. if one is undefined, both should be undefined */
+
+# if defined(PGTABLE_BASE_PADDR) || defined(PGTABLE_BASE_VADDR)
+# error "One of PGTABLE_BASE_PADDR or PGTABLE_BASE_VADDR is defined"
+# endif
+
+ /* A sanity check, if the configuration says that the page table is read-only
+ * and pre-initialized (maybe ROM), then it should have also defined CONFIG_PGTABLE_BASE
+ */
+
+# ifdef CONFIG_ARM_ROMPGTABLE
+# error "CONFIG_ARM_ROMPGTABLE defined; CONFIG_PGTABLE_BASE not defined"
+# else
+
+ /* We must declare the page table in ISRAM0 or 1. We decide depending upon
+ * where the vector table was place.
+ */
+
+# ifdef CONFIG_ARM_ROMPGTABLE /* Vectors located at 0x0000:0000 */
+
+ /* In this case, ISRAM0 will be shadowed at address 0x0000:0000. The page
+ * table must lie at the top 16Kb of ISRAM1 (or ISRAM0 if this is a LPC3130)
+ */
+
+# ifndef PGTABLE_BASE_VADDR
+# if CONFIG_ARCH_CHIP_LPC3131
+# define PGTABLE_BASE_PADDR (LPC313X_INTSRAM1_PADDR+LPC313X_INTSRAM1_SIZE-PGTABLE_SIZE)
+# define PGTABLE_BASE_VADDR (LPC313X_INTSRAM1_VADDR+LPC313X_INTSRAM1_SIZE-PGTABLE_SIZE)
+# else
+# define PGTABLE_BASE_PADDR (LPC313X_INTSRAM0_PADDR+LPC313X_INTSRAM0_SIZE-PGTABLE_SIZE)
+# define PGTABLE_BASE_VADDR (LPC313X_INTSRAM0_VADDR+LPC313X_INTSRAM0_SIZE-PGTABLE_SIZE)
+# endif
+# endif
+# else
+
+ /* Otherwise, ISRAM1 (or ISRAM0 for the LPC3130) will be mapped so that
+ * the end of the SRAM region will provide memory for the vectors. The page
+ * table will then be places at the first 16Kb of ISRAM0 (which will be in
+ * the shadow memory region.
+ */
+
+# define PGTABLE_BASE_PADDR LPC313X_SHADOWSPACE_PSECTION
+# define PGTABLE_BASE_VADDR LPC313X_SHADOWSPACE_VSECTION
+# endif
+# endif
+#endif
+
+/* 16Kb of memory is reserved hold the page table for the virtual mappings. A
+ * portion of this table is not accessible in the virtual address space (for
+ * normal operation). We will reuse this memory for coarse page tables as follows:
+ */
+
+#define PGTABLE_COARSE_BASE_PADDR (PGTABLE_BASE_PADDR+0x00000800)
+#define PGTABLE_COARSE_END_PADDR (PGTABLE_BASE_PADDR+0x00003000)
+#define PTTABLE_PERIPHERALS_PADDR (PGTABLE_BASE_PADDR+0x00003000)
+#define PGTABLE_END_PADDR (PGTABLE_BASE_PADDR+0x00004000)
+
+#define PGTABLE_COARSE_BASE_VADDR (PGTABLE_BASE_VADDR+0x00000800)
+#define PGTABLE_COARSE_END_VADDR (PGTABLE_BASE_VADDR+0x00003000)
+#define PTTABLE_PERIPHERALS_VADDR (PGTABLE_BASE_VADDR+0x00003000)
+#define PGTABLE_END_VADDR (PGTABLE_BASE_VADDR+0x00004000)
+
+#define PGTBALE_COARSE_TABLE_SIZE (4*256)
+#define PGTABLE_COARSE_ALLOC (PGTABLE_COARSE_END_VADDR-PGTABLE_COARSE_BASE_VADDR)
+#define PGTABLE_NCOARSE_TABLES (PGTABLE_COARSE_SIZE / PGTBALE_COARSE_TABLE_ALLOC)
+
+/* Determine the base address of the vector table */
-#define NUTTX_START_VADDR 0x00000000
+#define VECTOR_TABLE_SIZE 0x00010000
+#ifdef CONFIG_ARM_LOWVECTORS /* Vectors located at 0x0000:0000 */
+# define LPC313X_VECTOR_PADDR LPC313X_SHADOWSPACE_PSECTION
+# define LPC313X_VECTOR_VADDR 0x00000000
+# define LPC313X_VECTOR_VCOARSE 0x00000000
+#else /* Vectors located at 0xffff:0000 */
+# if CONFIG_ARCH_CHIP_LPC3131
+# define LPC313X_VECTOR_PADDR (LPC313X_INTSRAM1_PADDR+LPC313X_INTSRAM1_SIZE-VECTOR_TABLE_SIZE)
+# else
+# define LPC313X_VECTOR_PADDR (LPC313X_INTSRAM0_PADDR+LPC313X_INTSRAM0_SIZE-VECTOR_TABLE_SIZE)
+# endif
+# define LPC313X_VECTOR_VADDR 0xffff0000
+# define LPC313X_VECTOR_VCOARSE 0xfff00000
+#endif
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h b/nuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h
index 773250754..5e62e6b91 100755
--- a/nuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h
+++ b/nuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h
@@ -49,8 +49,8 @@
/* MPMC register base address offset into the MPMC domain ***************************************/
-#define LPC313X_MPMC_VBASE (LPC313X_MPMC_VSECTION)
-#define LPC313X_MPMC_PBASE (LPC313X_MPMC_PSECTION)
+#define LPC313X_MPMC_VBASE (LPC313X_MPMC_VADDR)
+#define LPC313X_MPMC_PBASE (LPC313X_MPMC_PADDR)
/* MPMC register offsets (with respect to the base of the MPMC domain) **************************/
diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_nand.h b/nuttx/arch/arm/src/lpc313x/lpc313x_nand.h
index fee0dd405..1c04055bb 100755
--- a/nuttx/arch/arm/src/lpc313x/lpc313x_nand.h
+++ b/nuttx/arch/arm/src/lpc313x/lpc313x_nand.h
@@ -49,8 +49,8 @@
/* NAND FLASH controller register base address offset into the APB4 domain **********************/
-#define LPC313X_NAND_VBASE (LPC313X_APB4_VSECTION+LPC313X_APB4_NAND_OFFSET)
-#define LPC313X_NAND_PBASE (LPC313X_APB4_PSECTION+LPC313X_APB4_NAND_OFFSET)
+#define LPC313X_NAND_VBASE (LPC313X_APB4_VADDR+LPC313X_APB4_NAND_OFFSET)
+#define LPC313X_NAND_PBASE (LPC313X_APB4_PADDR+LPC313X_APB4_NAND_OFFSET)
/* NAND FLASH controller register offsets (with respect to the base of the APB4 domain) *********/
diff --git a/nuttx/configs/ea3131/ostest/defconfig b/nuttx/configs/ea3131/ostest/defconfig
index 86fa0ecdf..8f0a73a3f 100755
--- a/nuttx/configs/ea3131/ostest/defconfig
+++ b/nuttx/configs/ea3131/ostest/defconfig
@@ -49,7 +49,11 @@
# CONFIG_ARCH_BOARD_name - for use in C code
# CONFIG_ENDIAN_BIG - define if big endian (default is little endian)
# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
-# CONFIG_DRAM_SIZE - Describes the installed DRAM.
+# CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the
+# size of installed DRAM. For the LPC313X, it is used only to
+# deterimine how to map the executable regions. It is SDRAM size
+# only if you are executing out of the external SDRAM; or it could
+# be NOR FLASH size, external SRAM size, or internal SRAM size.
# CONFIG_DRAM_START - The start address of DRAM (physical)
# CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual)
# CONFIG_ARCH_IRQPRIO - The LPC313x supports interrupt prioritization
@@ -78,9 +82,8 @@ CONFIG_ARCH_BOARD=ea3131
CONFIG_ARCH_BOARD_EA3131=y
CONFIG_BOARD_LOOPSPERMSEC=16945
CONFIG_DRAM_SIZE=0x01000000
-CONFIG_DRAM_START=0x01000000
-CONFIG_DRAM_VSTART=0x00000000
-CONFIG_DRAM_NUTTXENTRY=0x01008000
+CONFIG_DRAM_START=0x11028000
+CONFIG_DRAM_VSTART=0x11028000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
@@ -91,6 +94,20 @@ CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=n
#
+# ARM-specific configuration
+#
+# CONFIG_ARM_LOWVECTORS - define if vectors reside at address 0x0000:00000
+# Undefine if vectors reside at address 0xffff:0000
+# CONFIG_ARM_ROMPGTABLE - A pre-initialized, read-only page table is available
+# CONFIG_PGTABLE_BASE must also be defined in this case.
+# CONFIG_PGTABLE_BASE - The (physical) base address of the pre-initialized
+# read-only page table vector. This must be provided if CONFIG_ARM_ROMPGTABLE
+# is defined.
+#
+CONFIG_ARM_LOWVECTORS=y
+CONFIG_ARM_ROMPGTABLE=n
+#CONFIG_PGTABLE_BASE=
+
# Identify toolchain and linker options
#
CONFIG_LPC313X_CODESOURCERYW=n
@@ -123,6 +140,9 @@ CONFIG_LPC313X_UART=y
# configured as part of the NuttX heap.
# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed
# external SDRAM memory
+# CONFIG_LPC313X_EXTNAND - Select if external NAND is present
+# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed
+# external NAND memory
#
CONFIG_LPC313X_EXTSRAM0=n
CONFIG_LPC313X_EXTSRAM0HEAP=n
@@ -133,6 +153,8 @@ CONFIG_LPC313X_EXTSRAM1SIZE=(128*1024)
CONFIG_LPC313X_EXTSDRAM=n
CONFIG_LPC313X_EXTSDRAMHEAP=n
CONFIG_LPC313X_EXTSDRAMSIZE=(64*1024*1024)
+CONFIG_LPC313X_EXTNAND=n
+CONFIG_LPC313X_EXTNANDSIZE=(64*1024*1024)
#
# LPC313X specific device driver settings
diff --git a/nuttx/configs/mx1ads/ostest/defconfig b/nuttx/configs/mx1ads/ostest/defconfig
index 5fd3d8909..6948c2bb5 100644
--- a/nuttx/configs/mx1ads/ostest/defconfig
+++ b/nuttx/configs/mx1ads/ostest/defconfig
@@ -77,6 +77,21 @@ CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
#
+# ARM-specific configuration
+#
+# CONFIG_ARM_LOWVECTORS - define if vectors reside at address 0x0000:00000
+# Undefine if vectors reside at address 0xffff:0000
+# CONFIG_ARM_ROMPGTABLE - A pre-initialized, read-only page table is available
+# CONFIG_PGTABLE_BASE must also be defined in this case.
+# CONFIG_PGTABLE_BASE - The (physical) base address of the pre-initialized
+# read-only page table vector. This must be provided if CONFIG_ARM_ROMPGTABLE
+# is defined.
+#
+CONFIG_ARM_LOWVECTORS=n
+CONFIG_ARM_ROMPGTABLE=n
+#CONFIG_PGTABLE_BASE=
+
+#
# IMX specific serial device driver settings
#
# CONFIG_UARTn_DISABLE - select to disable all support for
diff --git a/nuttx/configs/ntosd-dm320/nettest/defconfig b/nuttx/configs/ntosd-dm320/nettest/defconfig
index a4a78f685..5c013f92d 100644
--- a/nuttx/configs/ntosd-dm320/nettest/defconfig
+++ b/nuttx/configs/ntosd-dm320/nettest/defconfig
@@ -74,6 +74,21 @@ CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=n
#
+# ARM-specific configuration
+#
+# CONFIG_ARM_LOWVECTORS - define if vectors reside at address 0x0000:00000
+# Undefine if vectors reside at address 0xffff:0000
+# CONFIG_ARM_ROMPGTABLE - A pre-initialized, read-only page table is available
+# CONFIG_PGTABLE_BASE must also be defined in this case.
+# CONFIG_PGTABLE_BASE - The (physical) base address of the pre-initialized
+# read-only page table vector. This must be provided if CONFIG_ARM_ROMPGTABLE
+# is defined.
+#
+CONFIG_ARM_LOWVECTORS=n
+CONFIG_ARM_ROMPGTABLE=n
+#CONFIG_PGTABLE_BASE=
+
+#
# DM320 specific device driver settings
#
# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
diff --git a/nuttx/configs/ntosd-dm320/nsh/defconfig b/nuttx/configs/ntosd-dm320/nsh/defconfig
index 07ced4a1a..0c77a0882 100644
--- a/nuttx/configs/ntosd-dm320/nsh/defconfig
+++ b/nuttx/configs/ntosd-dm320/nsh/defconfig
@@ -74,6 +74,21 @@ CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=n
#
+# ARM-specific configuration
+#
+# CONFIG_ARM_LOWVECTORS - define if vectors reside at address 0x0000:00000
+# Undefine if vectors reside at address 0xffff:0000
+# CONFIG_ARM_ROMPGTABLE - A pre-initialized, read-only page table is available
+# CONFIG_PGTABLE_BASE must also be defined in this case.
+# CONFIG_PGTABLE_BASE - The (physical) base address of the pre-initialized
+# read-only page table vector. This must be provided if CONFIG_ARM_ROMPGTABLE
+# is defined.
+#
+CONFIG_ARM_LOWVECTORS=n
+CONFIG_ARM_ROMPGTABLE=n
+#CONFIG_PGTABLE_BASE=
+
+#
# DM320 specific device driver settings
#
# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
diff --git a/nuttx/configs/ntosd-dm320/ostest/defconfig b/nuttx/configs/ntosd-dm320/ostest/defconfig
index 06ec1bb9a..904918639 100644
--- a/nuttx/configs/ntosd-dm320/ostest/defconfig
+++ b/nuttx/configs/ntosd-dm320/ostest/defconfig
@@ -74,6 +74,21 @@ CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=y
#
+# ARM-specific configuration
+#
+# CONFIG_ARM_LOWVECTORS - define if vectors reside at address 0x0000:00000
+# Undefine if vectors reside at address 0xffff:0000
+# CONFIG_ARM_ROMPGTABLE - A pre-initialized, read-only page table is available
+# CONFIG_PGTABLE_BASE must also be defined in this case.
+# CONFIG_PGTABLE_BASE - The (physical) base address of the pre-initialized
+# read-only page table vector. This must be provided if CONFIG_ARM_ROMPGTABLE
+# is defined.
+#
+CONFIG_ARM_LOWVECTORS=n
+CONFIG_ARM_ROMPGTABLE=n
+#CONFIG_PGTABLE_BASE=
+
+#
# DM320 specific device driver settings
#
# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
diff --git a/nuttx/configs/ntosd-dm320/poll/defconfig b/nuttx/configs/ntosd-dm320/poll/defconfig
index 9b95280ca..ffb97dbf3 100644
--- a/nuttx/configs/ntosd-dm320/poll/defconfig
+++ b/nuttx/configs/ntosd-dm320/poll/defconfig
@@ -74,6 +74,21 @@ CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=n
#
+# ARM-specific configuration
+#
+# CONFIG_ARM_LOWVECTORS - define if vectors reside at address 0x0000:00000
+# Undefine if vectors reside at address 0xffff:0000
+# CONFIG_ARM_ROMPGTABLE - A pre-initialized, read-only page table is available
+# CONFIG_PGTABLE_BASE must also be defined in this case.
+# CONFIG_PGTABLE_BASE - The (physical) base address of the pre-initialized
+# read-only page table vector. This must be provided if CONFIG_ARM_ROMPGTABLE
+# is defined.
+#
+CONFIG_ARM_LOWVECTORS=n
+CONFIG_ARM_ROMPGTABLE=n
+#CONFIG_PGTABLE_BASE=
+
+#
# DM320 specific device driver settings
#
# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
diff --git a/nuttx/configs/ntosd-dm320/thttpd/defconfig b/nuttx/configs/ntosd-dm320/thttpd/defconfig
index 207b5922a..e5eb6ee76 100644
--- a/nuttx/configs/ntosd-dm320/thttpd/defconfig
+++ b/nuttx/configs/ntosd-dm320/thttpd/defconfig
@@ -74,6 +74,21 @@ CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=n
#
+# ARM-specific configuration
+#
+# CONFIG_ARM_LOWVECTORS - define if vectors reside at address 0x0000:00000
+# Undefine if vectors reside at address 0xffff:0000
+# CONFIG_ARM_ROMPGTABLE - A pre-initialized, read-only page table is available
+# CONFIG_PGTABLE_BASE must also be defined in this case.
+# CONFIG_PGTABLE_BASE - The (physical) base address of the pre-initialized
+# read-only page table vector. This must be provided if CONFIG_ARM_ROMPGTABLE
+# is defined.
+#
+CONFIG_ARM_LOWVECTORS=n
+CONFIG_ARM_ROMPGTABLE=n
+#CONFIG_PGTABLE_BASE=
+
+#
# DM320 specific device driver settings
#
# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
diff --git a/nuttx/configs/ntosd-dm320/udp/defconfig b/nuttx/configs/ntosd-dm320/udp/defconfig
index d9ea60acc..ffea2b946 100644
--- a/nuttx/configs/ntosd-dm320/udp/defconfig
+++ b/nuttx/configs/ntosd-dm320/udp/defconfig
@@ -74,6 +74,21 @@ CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=n
#
+# ARM-specific configuration
+#
+# CONFIG_ARM_LOWVECTORS - define if vectors reside at address 0x0000:00000
+# Undefine if vectors reside at address 0xffff:0000
+# CONFIG_ARM_ROMPGTABLE - A pre-initialized, read-only page table is available
+# CONFIG_PGTABLE_BASE must also be defined in this case.
+# CONFIG_PGTABLE_BASE - The (physical) base address of the pre-initialized
+# read-only page table vector. This must be provided if CONFIG_ARM_ROMPGTABLE
+# is defined.
+#
+CONFIG_ARM_LOWVECTORS=n
+CONFIG_ARM_ROMPGTABLE=n
+#CONFIG_PGTABLE_BASE=
+
+#
# DM320 specific device driver settings
#
# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
diff --git a/nuttx/configs/ntosd-dm320/uip/defconfig b/nuttx/configs/ntosd-dm320/uip/defconfig
index 87afda326..288a65f0e 100644
--- a/nuttx/configs/ntosd-dm320/uip/defconfig
+++ b/nuttx/configs/ntosd-dm320/uip/defconfig
@@ -74,6 +74,21 @@ CONFIG_ARCH_INTERRUPTSTACK=0
CONFIG_ARCH_STACKDUMP=n
#
+# ARM-specific configuration
+#
+# CONFIG_ARM_LOWVECTORS - define if vectors reside at address 0x0000:00000
+# Undefine if vectors reside at address 0xffff:0000
+# CONFIG_ARM_ROMPGTABLE - A pre-initialized, read-only page table is available
+# CONFIG_PGTABLE_BASE must also be defined in this case.
+# CONFIG_PGTABLE_BASE - The (physical) base address of the pre-initialized
+# read-only page table vector. This must be provided if CONFIG_ARM_ROMPGTABLE
+# is defined.
+#
+CONFIG_ARM_LOWVECTORS=n
+CONFIG_ARM_ROMPGTABLE=n
+#CONFIG_PGTABLE_BASE=
+
+#
# DM320 specific device driver settings
#
# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the