summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-08-21 02:09:12 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-08-21 02:09:12 +0000
commit009650825eb7b48d3bd7714e359c606bc4724bc5 (patch)
tree6b297472892c5b2beead17d92ebec5d097b1bede
parent31131eee3a58b2e0c04ae4e81a74d461707e3668 (diff)
downloadpx4-nuttx-009650825eb7b48d3bd7714e359c606bc4724bc5.tar.gz
px4-nuttx-009650825eb7b48d3bd7714e359c606bc4724bc5.tar.bz2
px4-nuttx-009650825eb7b48d3bd7714e359c606bc4724bc5.zip
Add mapping for the page table
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2872 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/arm/pg_macros.h68
-rw-r--r--nuttx/arch/arm/src/arm/up_head.S115
-rw-r--r--nuttx/arch/arm/src/arm/up_nommuhead.S2
-rw-r--r--nuttx/arch/arm/src/dm320/dm320_boot.c2
-rwxr-xr-xnuttx/arch/arm/src/lpc313x/lpc313x_boot.c14
-rwxr-xr-xnuttx/include/nuttx/page.h49
6 files changed, 196 insertions, 54 deletions
diff --git a/nuttx/arch/arm/src/arm/pg_macros.h b/nuttx/arch/arm/src/arm/pg_macros.h
index 9384e378e..4c69ca12d 100644
--- a/nuttx/arch/arm/src/arm/pg_macros.h
+++ b/nuttx/arch/arm/src/arm/pg_macros.h
@@ -59,35 +59,85 @@
# error "Cannot support both CONFIG_PAGING and CONFIG_ARCH_ROMPGTABLE"
# endif
+ /* Page Size Selections ***************************************************/
+
/* Create some friendly definitions to handle some differences between
* small and tiny pages.
*/
# if CONFIG_PAGING_PAGESIZE == 1024
+
+ /* Number of pages in an L2 table per L1 entry */
+
# define PTE_NPAGES PTE_TINY_NPAGES
+
+ /* L2 Page table address */
+
# define PG_L2_BASE_PADDR PGTABLE_FINE_BASE_PADDR
# define PG_L2_BASE_VADDR PGTABLE_FINE_BASE_VADDR
-# define MMU_L1_TEXTFLAGS (PMD_TYPE_FINE|PMD_BIT4|PTE_CACHEABLE)
+
+ /* MMU Flags for each memory region */
+
+# define MMU_L1_TEXTFLAGS (PMD_TYPE_FINE|PMD_BIT4)
# define MMU_L2_TEXTFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRO|PTE_CACHEABLE)
-# define MMU_L1_DATAFLAGS (PMD_TYPE_FINE|PMD_BIT4|PTE_CACHEABLE)
-# define MMU_L2_DATAFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRW|PTE_CACHEABLE)
+# define MMU_L1_DATAFLAGS (PMD_TYPE_FINE|PMD_BIT4)
+# define MMU_L2_DATAFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRW|PTE_CACHEABLE|PTE_BUFFERABLE)
+# define MMU_L1_PGTABFLAGS (PMD_TYPE_FINE|PMD_BIT4)
+# define MMU_L2_PGTABFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRW)
+
# elif CONFIG_PAGING_PAGESIZE == 4096
-# define PTE_NPAGES PTE_SMALL_NPAGES
+
+ /* Number of pages in an L2 table per L1 entry */
+
+# define PTE_NPAGES PTE_SMALL_NPAGES
+
+ /* L2 Page table address */
+
# define PG_L2_BASE_PADDR PGTABLE_COARSE_BASE_PADDR
-# define PG_L2_BASE_vADDR PGTABLE_COARSE_BASE_VADDR
-# define MMU_L1_TEXTFLAGS (PMD_TYPE_COARSE|PMD_BIT4|PTE_CACHEABLE)
+# define PG_L2_BASE_VADDR PGTABLE_COARSE_BASE_VADDR
+
+ /* MMU Flags for each memory region. */
+
+# define MMU_L1_TEXTFLAGS (PMD_TYPE_COARSE|PMD_BIT4)
# define MMU_L2_TEXTFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRO|PTE_CACHEABLE)
-# define MMU_L1_DATAFLAGS (PMD_TYPE_COARSE|PMD_BIT4|PTE_CACHEABLE|PTE_BUFFERABLE)
+# define MMU_L1_DATAFLAGS (PMD_TYPE_COARSE|PMD_BIT4)
# define MMU_L2_DATAFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRW|PTE_CACHEABLE|PTE_BUFFERABLE)
+# define MMU_L1_PGTABFLAGS (PMD_TYPE_COARSE|PMD_BIT4)
+# define MMU_L2_PGTABFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRW)
+
# else
# error "Need extended definitions for CONFIG_PAGING_PAGESIZE"
# endif
#define PT_SIZE (PTE_NPAGES * 4)
-/* We position the data section PTE's just after the text section PTE's */
+/* We position the data section PTEs just after the text section PTE's */
#define PG_L2_DATA_PADDR (PG_L2_BASE_PADDR + 4*PG_TEXT_NPAGES)
+#define PG_L2_DATA_VADDR (PG_L2_BASE_VADDR + 4*PG_TEXT_NPAGES)
+
+/* Page Table Info: The number of pages in the in the page table
+ * (PG_PGTABLE_NPAGES). We position the pagetable PTEs just after
+ * the data section PTEs.
+ */
+
+#define PG_PGTABLE_NPAGES (PGTABLE_SIZE >> PAGESHIFT)
+#define PG_L2_PGTABLE_PADDR (PG_L2_DATA_PADDR + 4*PG_DATA_NPAGES)
+#define PG_L2_PGTABLE_VADDR (PG_L2_DATA_VADDR + 4*PG_DATA_NPAGES)
+
+/* This is the total number of pages used in the initial page table setup
+ * in up_head.S
+ */
+
+#define PG_STATIC_NPAGES (PG_TEXT_NPAGES + PG_DATA_PAGES + PG_PGTABLE_NPAGES)
+
+/* For page managment purposes, the following summarize the "heap" of
+ * free pages
+ */
+
+#define PG_POOL_FIRSTPAGE PG_STATIC_NPAGES
+#define PG_POOL_NPAGES CONFIG_PAGING_NLOCKED
+
#endif /* CONFIG_PAGING */
/****************************************************************************
@@ -184,7 +234,7 @@
*
* Scratch registers (modified):
* addr, npages, tmp
- * l2 - L2 page table physical address
+ * l2 - L2 page table physical address
* addr - Physical address in the L1 page table.
* npages - The number of pages remaining to be accounted for
* tmp - scratch
diff --git a/nuttx/arch/arm/src/arm/up_head.S b/nuttx/arch/arm/src/arm/up_head.S
index 9f7c47d22..8bdba5baa 100644
--- a/nuttx/arch/arm/src/arm/up_head.S
+++ b/nuttx/arch/arm/src/arm/up_head.S
@@ -180,18 +180,41 @@ __start:
str r3, [r4, r0, lsr #18] /* identity mapping */
#ifdef CONFIG_PAGING
- /* Populate the L1 table for the locked and paged text regions */
+ /* Map the read-only .text region in place. This must be done
+ * before the MMU is enabled and the virtual addressing takes
+ * effect. First populate the L1 table for the locked and paged
+ * text regions.
+ *
+ * We could probably make the the pg_span and pg_map macros into
+ * call-able subroutines, but we would have to be carefully during
+ * this phase while we are operating in a physical address space.
+ */
adr r0, .Ltxtspan
ldmia r0, {r0, r1, r2, r3}
pg_span r0, r1, r2, r3, r4
- /* Populate the L2 table for the locked text region only */
+ /* Then populate the L2 table for the locked text region only. */
adr r0, .Ltxtmap
ldmia r0, {r0, r1, r2, r3}
pg_map r0, r1, r2, r3, r4
- #else
+
+ /* Make sure that the page table is itself mapped and and read/write-able.
+ * First, populate the L1 table:
+ */
+
+ adr r0, .Lptabspan
+ ldmia r0, {r0, r1, r2, r3}
+ pg_span r0, r1, r2, r3, r4
+
+ /* Then populate the L2 table. */
+
+ adr r0, .Lptabmap
+ ldmia r0, {r0, r1, r2, r3}
+ pg_map r0, r1, r2, r3, r4
+
+#else
/* Create a virtual single section mapping for the first MB of the .text
* address space. Now, we have the first 1MB mapping to both phyical and
* virtual addresses. The rest of the .text mapping will be completed in
@@ -303,7 +326,7 @@ __start:
* PC_Relative Data
****************************************************************************/
- /* These addresses are all virtual address */
+ /* Most addresses are all virtual address */
.type .LCvstart, %object
.LCvstart:
@@ -312,17 +335,43 @@ __start:
#ifndef CONFIG_ARCH_ROMPGTABLE
.type .LCmmuflags, %object
.LCmmuflags:
- .long MMU_MEMFLAGS
+ .long MMU_MEMFLAGS /* MMU flags for memory sections */
#endif
- .type .LCppagetable, %object
+ .type .LCppgtable, %object
.LCppgtable:
- .long PGTABLE_BASE_PADDR /* Physical start of DRAM */
+ .long PGTABLE_BASE_PADDR /* Physical start of page table */
#ifndef CONFIG_ARCH_ROMPGTABLE
- .type .LCvpagetable, %object
+ .type .LCvpgtable, %object
.LCvpgtable:
- .long PGTABLE_BASE_VADDR /* Virtual start of DRAM */
+ .long PGTABLE_BASE_VADDR /* Virtual start of page table */
+#endif
+
+#ifdef CONFIG_PAGING
+.Ltxtspan:
+ .long PG_L2_BASE_PADDR /* Physical address of L2 table */
+ .long PG_LOCKED_VBASE /* Virtual address of locked base */
+ .long PG_TEXT_NPAGES /* Total mapped text pages */
+ .long MMU_L1_TEXTFLAGS /* L1 MMU flags to use */
+
+.Ltxtmap:
+ .long PG_L2_BASE_PADDR /* Physical address of L2 table */
+ .long PG_LOCKED_PBASE /* Physical address of locked base */
+ .long CONFIG_PAGING_NLOCKED /* Number of pages in the locked region */
+ .long MMU_L2_TEXTFLAGS /* L2 MMU flags to use */
+
+.Lptabspan:
+ .long PG_L2_PGTABLE_PADDR /* Physical address of L2 table */
+ .long PGTABLE_BASE_VADDR /* Virtual address of the page table */
+ .long PG_TEXT_NPAGES /* Total mapped page table pages */
+ .long MMU_L1_PGTABFLAGS /* L1 MMU flags to use */
+
+.Lptabmap:
+ .long PG_L2_PGTABLE_PADDR /* Physical address of L2 table */
+ .long PGTABLE_BASE_PADDR /* Physical address of the page table */
+ .long CONFIG_PAGING_NLOCKED /* Total mapped page table pages */
+ .long MMU_L2_PGTABFLAGS /* L2 MMU flags to use */
#endif
.size _start, .-_start
@@ -353,15 +402,15 @@ __start:
#if defined(CONFIG_PAGING)
/* Populate the L1 table for the data regions */
- adr r0, .Ldatamap
+ adr r0, .Ldataspan
ldmia r0, {r0, r1, r2, r3}
pg_span r0, r1, r2, r3, r4
/* Populate the L2 table for the data region */
adr r0, .Ldatamap
- ldmia r0, {r0, r1, r2, r3, r4}
- pg_map r0, r1, r2, r4, r3
+ ldmia r0, {r0, r1, r2, r3}
+ pg_map r0, r1, r2, r3, r4
#elif defined(CONFIG_BOOT_RUNFROMFLASH)
# error "Logic not implemented"
@@ -424,7 +473,13 @@ __start:
*/
#if defined(CONFIG_BOOT_RUNFROMFLASH) || defined(CONFIG_PAGING)
-# error "Logic not implemented"
+ adr r3, .Ldatainit
+ ldmia r3, {r0, r1, r2}
+
+1: ldmia r0!, {r3 - r10}
+ stmia r1!, {r3 - r10}
+ cmp r1, r2
+ blt 1b
#endif
/* Perform early C-level, platform-specific initialization */
@@ -452,25 +507,25 @@ __start:
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE-4
#ifdef CONFIG_PAGING
-.Ltxtspan:
- .long PG_L2_BASE_PADDR
- .long PG_LOCKED_PBASE
- .long PG_TEXT_NPAGES
- .long MMU_L1_TEXTFLAGS
-
-.Ltxtmap:
- .long PG_L2_BASE_PADDR
- .long PG_LOCKED_PBASE
- .long CONFIG_PAGING_NLOCKED
- .long MMU_L2_TEXTFLAGS
+.Ldataspan:
+ .long PG_L2_DATA_PADDR /* Physical address of L2 table */
+ .long PG_DATA_PBASE /* Physical address of data base */
+ .long PG_DATA_NPAGED /* Number of pages in the data region */
+ .long MMU_L1_DATAFLAGS /* L1 MMU flags to use */
.Ldatamap:
- .long PG_L2_DATA_PADDR
- .long PG_DATA_PBASE
- .long PG_DATA_NPAGED
- .long MMU_L1_DATAFLAGS
- .long MMU_L2_DATAFLAGS
- #endif
+ .long PG_L2_DATA_PADDR /* Physical address of L2 table */
+ .long PG_DATA_VBASE /* Virtual address of data base */
+ .long PG_DATA_NPAGED /* Number of pages in the data region */
+ .long MMU_L2_DATAFLAGS /* L2 MMU flags to use */
+#endif
+
+#if defined(CONFIG_BOOT_RUNFROMFLASH) || defined(CONFIG_PAGING)
+.Ldatainit:
+ .long _eronly /* Where .data defaults are stored in FLASH */
+ .long _sdata /* Where .data needs to reside in SDRAM */
+ .long _edata
+#endif
.size .Lvstart, .-.Lvstart
/* Data section variables */
diff --git a/nuttx/arch/arm/src/arm/up_nommuhead.S b/nuttx/arch/arm/src/arm/up_nommuhead.S
index 509985296..afd195192 100644
--- a/nuttx/arch/arm/src/arm/up_nommuhead.S
+++ b/nuttx/arch/arm/src/arm/up_nommuhead.S
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/arm/up_nommuhead.S
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/dm320/dm320_boot.c b/nuttx/arch/arm/src/dm320/dm320_boot.c
index b8f5f1879..be541d1c6 100644
--- a/nuttx/arch/arm/src/dm320/dm320_boot.c
+++ b/nuttx/arch/arm/src/dm320/dm320_boot.c
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/dm320/dm320_boot.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c b/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c
index 31f66b060..c0c3a154d 100755
--- a/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c
+++ b/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc313x/lpc313x_boot.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -234,6 +234,10 @@ static void up_vectormapping(void)
/************************************************************************************
* Name: up_copyvectorblock
+ *
+ * Description:
+ * Copy the interrupt block to its final destination.
+ *
************************************************************************************/
static void up_copyvectorblock(void)
@@ -267,6 +271,14 @@ static void up_copyvectorblock(void)
* Public Functions
************************************************************************************/
+/************************************************************************************
+ * Name: up_boot
+ *
+ * Description:
+ * Complete boot operations started in up_head.S
+ *
+ ************************************************************************************/
+
void up_boot(void)
{
/* __start provided the basic MMU mappings for SRAM. Now provide mappings for all
diff --git a/nuttx/include/nuttx/page.h b/nuttx/include/nuttx/page.h
index 9ae2dd5a0..28545154c 100755
--- a/nuttx/include/nuttx/page.h
+++ b/nuttx/include/nuttx/page.h
@@ -77,7 +77,8 @@
#define PG_ALIGNUP(addr) (((addr) + PAGEMASK) & ~PAGEMASK)
/* CONFIG_PAGING_NLOCKED - This is the number of locked pages in the memory
- * map. The size of locked address region will then be:
+ * map. The size of locked address region will then be given by
+ * PG_LOCKED_SIZE.
*/
#define PG_LOCKED_SIZE (CONFIG_PAGING_NLOCKED << PAGESHIFT)
@@ -87,6 +88,12 @@
* not defined, then this logic will be set to then to CONFIG_DRAM_START
* and CONFIG_DRAM_VSTART (i.e., assuming that the base address of the
* locked region is at the virtual address of the beginning of RAM).
+ *
+ * NOTE: In some architectures, it may be necessary to take some memory
+ * from the beginning of this region for vectors or for a page table.
+ * In such cases, CONFIG_PAGING_LOCKED_P/VBASE should take that into
+ * consideration to prevent overlapping the locked memory region and the
+ * system data at the beginning of SRAM.
*/
#if defined(CONFIG_PAGING_LOCKED_PBASE) && defined(CONFIG_PAGING_LOCKED_VBASE)
@@ -110,10 +117,19 @@
#define PG_PAGED_SIZE (CONFIG_PAGING_NPAGED << PAGESHIFT)
-/* This positions the paging Read-Only text section */
+/* This positions the paging Read-Only text section. If the configuration
+ * did not override the default, the paged region will immediately follow
+ * the locked region.
+ */
+
+#if defined(CONFIG_PAGING_LOCKED_PBASE) && defined(CONFIG_PAGING_LOCKED_VBASE)
+# define PG_LOCKED_PBASE CONFIG_PAGING_LOCKED_PBASE
+# define PG_LOCKED_VBASE CONFIG_PAGING_LOCKED_VBASE
+#else
+# define PG_PAGED_PBASE PG_LOCKED_PEND
+# define PG_PAGED_VBASE PG_LOCKED_VEND
+#endif
-#define PG_PAGED_PBASE PG_LOCKED_PEND
-#define PG_PAGED_VBASE PG_LOCKED_VEND
#define PG_PAGED_PEND (PG_PAGED_PBASE + PG_PAGED_SIZE)
#define PG_PAGED_VEND (PG_PAGED_VBASE + PG_PAGED_SIZE)
@@ -123,23 +139,32 @@
#define PG_TEXT_SIZE (PG_TEXT_NPAGES << PAGESHIFT)
/* CONFIG_PAGING_NDATA - This is the number of data pages in the memory
- * map. The size of data address region will then be:
+ * map. The data region will extend to the end of RAM unless overridden
+ * by a setting in the configuration file.
+ *
+ * NOTE: In some architectures, it may be necessary to take some memory
+ * from the end of RAM for page tables or other system usage. The
+ * configuration settings and linker directives must be cognizant of that.
+ * CONFIG_PAGING_NDATA should be defined to prevent the data region from
+ * extending all the way to the end of memory.
*/
#define PG_RAM_PAGES (CONFIG_DRAM_SIZE >> PAGESHIFT)
-#if PG_RAM_PAGES <= PG_TEXT_NPAGES
-# error "Not enough memory for this page layout"
-#endif
#ifdef CONFIG_PAGING_NDATA
-# PG_DATA_NPAGED CONFIG_PAGING_NDATA
+# PG_DATA_NPAGES CONFIG_PAGING_NDATA
+#elif PG_RAM_PAGES > PG_TEXT_NPAGES
+# PG_DATA_NPAGES (PG_RAM_PAGES - PG_TEXT_NPAGES)
#else
-# PG_DATA_NPAGED (PG_RAM_PAGES - PG_TEXT_NPAGES)
+# error "Not enough memory for this page layout"
#endif
-#define PG_DATA_SIZE (CONFIG_PAGING_NPAGED << PAGESHIFT)
+#define PG_DATA_SIZE (PG_DATA_NPAGES << PAGESHIFT)
-/* This positions the Read/Write data region */
+/* This positions the Read/Write data region. If the configuration
+ * did not override the default, the paged region will immediately follow
+ * the paged region and will extend to the end of memory.
+ */
#if defined(CONFIG_PAGING_DATA_PBASE) && defined(CONFIG_PAGING_DATA_VBASE)
# define PG_DATA_PBASE CONFIG_PAGING_DATA_PBASE