summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_head.S11
-rw-r--r--nuttx/configs/eagle100/ostest/ld.script2
-rw-r--r--nuttx/configs/mcu123-lpc214x/ostest/ld.script2
-rw-r--r--nuttx/configs/olimex-strp711/ostest/defconfig4
-rw-r--r--nuttx/configs/olimex-strp711/ostest/ld.script46
5 files changed, 37 insertions, 28 deletions
diff --git a/nuttx/arch/arm/src/str71x/str71x_head.S b/nuttx/arch/arm/src/str71x/str71x_head.S
index 2e5eaef5c..fd7f263e7 100644
--- a/nuttx/arch/arm/src/str71x/str71x_head.S
+++ b/nuttx/arch/arm/src/str71x/str71x_head.S
@@ -509,19 +509,16 @@ __flashstart:
strcc r0, [r4], #4
bcc 1b
- /* Copy system .data sections to new home in RAM. */
-
-#ifdef CONFIG_BOOT_RUNFROMFLASH
+ /* Copy system .data sections from FLASH to new home in RAM. */
adr r3, LC2
ldmia r3, {r0, r1, r2}
-1: ldmia r0!, {r3 - r10}
+2: ldmia r0!, {r3 - r10}
stmia r1!, {r3 - r10}
cmp r1, r2
- blt 1b
+ blt 2b
-#endif
/* Initialize clocking */
bl str71x_prccuinit
@@ -602,11 +599,9 @@ LC0: .long _sbss
.long _ebss
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE-4
-#ifdef CONFIG_BOOT_RUNFROMFLASH
LC2: .long _eronly /* Where .data defaults are stored in FLASH */
.long _sdata /* Where .data needs to reside in SDRAM */
.long _edata
-#endif
.size __start, .-__start
/* This global variable is unsigned long g_heapbase and is
diff --git a/nuttx/configs/eagle100/ostest/ld.script b/nuttx/configs/eagle100/ostest/ld.script
index df687adaa..8af2ce81d 100644
--- a/nuttx/configs/eagle100/ostest/ld.script
+++ b/nuttx/configs/eagle100/ostest/ld.script
@@ -57,7 +57,7 @@ SECTIONS
*(.fixup)
*(.gnu.warning)
*(.rodata)
- *(.rodata.str1.1)
+ *(.rodata.str1.*)
*(.glue_7)
*(.glue_7t)
*(.got) /* Global offset table */
diff --git a/nuttx/configs/mcu123-lpc214x/ostest/ld.script b/nuttx/configs/mcu123-lpc214x/ostest/ld.script
index ecd740527..04e381b8b 100644
--- a/nuttx/configs/mcu123-lpc214x/ostest/ld.script
+++ b/nuttx/configs/mcu123-lpc214x/ostest/ld.script
@@ -1,7 +1,7 @@
/****************************************************************************
* configs/mcu123-lpc214x/ostest/ld.script
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 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/configs/olimex-strp711/ostest/defconfig b/nuttx/configs/olimex-strp711/ostest/defconfig
index e9734c1d8..ca65ef5d5 100644
--- a/nuttx/configs/olimex-strp711/ostest/defconfig
+++ b/nuttx/configs/olimex-strp711/ostest/defconfig
@@ -626,8 +626,10 @@ CONFIG_EXAMPLES_NSH_MMCSDMINOR=0
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
# operation from FLASH but must copy initialized .data sections to RAM.
+# (This option does not appy to the STR71x -- it always runs from flash).
# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH
# but copy themselves entirely into RAM for better performance.
+# (This option does not appy to the STR71x -- it is never copied to RAM).
# CONFIG_CUSTOM_STACK - The up_ implementation will handle
# all stack operations outside of the nuttx model.
# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
@@ -643,7 +645,7 @@ CONFIG_EXAMPLES_NSH_MMCSDMINOR=0
# CONFIG_HEAP_BASE - The beginning of the heap
# CONFIG_HEAP_SIZE - The size of the heap
#
-CONFIG_BOOT_RUNFROMFLASH=y
+CONFIG_BOOT_RUNFROMFLASH=n
CONFIG_BOOT_COPYTORAM=n
CONFIG_CUSTOM_STACK=n
CONFIG_STACK_POINTER=
diff --git a/nuttx/configs/olimex-strp711/ostest/ld.script b/nuttx/configs/olimex-strp711/ostest/ld.script
index c2a198791..053b9938d 100644
--- a/nuttx/configs/olimex-strp711/ostest/ld.script
+++ b/nuttx/configs/olimex-strp711/ostest/ld.script
@@ -33,52 +33,64 @@
*
****************************************************************************/
+/* The str71x has 256Kb of non-volatile memory beginning at address
+ * 0x4000:0000 for program storage (Bank0, an addition 16Kb is available
+ * for data storage in Bank1). The OS entry point is via the reset vector
+ * at address 0x00000000 where the FLASH is remapped at reset.
+ *
+ * The str71x has 64Kb of on-chip static RAM beginning at address
+ * 0x2000:0000. The .data section will be relocated from _eronly
+ * to _sdata at boot time.
+ */
+
+/* The STR711 has 256Kb of FLASH beginning at address 0x4000:0000 and 64Kb
+ * of SRAM beginning at address 0x2000:0000
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x40000000, LENGTH = 256K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
+}
+
OUTPUT_ARCH(arm)
ENTRY(_stext)
SECTIONS
{
- /* The str71x has 256Kb of non-volatile memory beginning at address
- * 0x40000000 for program storage (Bank0, an addition 16Kb is avalable
- * for data storage in Bank1). The OS entry point is via the reset vector
- * at address 0x00000000 where the FLASH is remapped at reset.
- */
-
- . = 0x40000000;
.text : {
_stext = ABSOLUTE(.);
+ *(.vectors)
*(.text)
*(.fixup)
*(.gnu.warning)
*(.rodata)
- *(.rodata.str1.4)
+ *(.rodata.str1.*)
*(.glue_7)
*(.glue_7t)
*(.got) /* Global offset table */
_etext = ABSOLUTE(.);
- }
- _eronly = ABSOLUTE(.); /* This is where the .data section
- * is relocated for execution out
- * FLASH */
+ } > flash
- /* The str71x has 64Kb of on-chip static RAM beginning at address
- * 0x20000000. The .data section will be relocated from _eronly
+ /* This is where the .data section is relocated for execution out
+ * FLASH. The .data section will be relocated from _eronly
* to _sdata at boot time.
*/
- . = 0x20000000;
+ _eronly = ABSOLUTE(.);
+
.data : {
_sdata = ABSOLUTE(.);
*(.data)
CONSTRUCTORS
_edata = ABSOLUTE(.);
- }
+ } > sram AT > flash
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
*(.bss)
*(COMMON)
_ebss = ABSOLUTE(.);
- }
+ } > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }