aboutsummaryrefslogtreecommitdiff
path: root/nuttx-configs/px4fmu-v1/scripts
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-08-02 23:11:04 -0700
committerpx4dev <px4@purgatory.org>2013-08-02 23:11:04 -0700
commitecc7bc5bca40e9d5e0a7271105dea9b3441af0a8 (patch)
tree2dbe20984da5cc24405e00ab43a88664e8fdc757 /nuttx-configs/px4fmu-v1/scripts
parent9d6ec6b3655fcd902be7a7fe4f2a24033c714afb (diff)
downloadpx4-firmware-ecc7bc5bca40e9d5e0a7271105dea9b3441af0a8.tar.gz
px4-firmware-ecc7bc5bca40e9d5e0a7271105dea9b3441af0a8.tar.bz2
px4-firmware-ecc7bc5bca40e9d5e0a7271105dea9b3441af0a8.zip
Clean out unused trash from the NuttX configs.
Diffstat (limited to 'nuttx-configs/px4fmu-v1/scripts')
-rw-r--r--nuttx-configs/px4fmu-v1/scripts/gnu-elf.ld129
-rw-r--r--nuttx-configs/px4fmu-v1/scripts/ld.script58
2 files changed, 42 insertions, 145 deletions
diff --git a/nuttx-configs/px4fmu-v1/scripts/gnu-elf.ld b/nuttx-configs/px4fmu-v1/scripts/gnu-elf.ld
deleted file mode 100644
index 1f29f02f5..000000000
--- a/nuttx-configs/px4fmu-v1/scripts/gnu-elf.ld
+++ /dev/null
@@ -1,129 +0,0 @@
-/****************************************************************************
- * configs/stm32f4discovery/scripts/gnu-elf.ld
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-SECTIONS
-{
- .text 0x00000000 :
- {
- _stext = . ;
- *(.text)
- *(.text.*)
- *(.gnu.warning)
- *(.stub)
- *(.glue_7)
- *(.glue_7t)
- *(.jcr)
-
- /* C++ support: The .init and .fini sections contain specific logic
- * to manage static constructors and destructors.
- */
-
- *(.gnu.linkonce.t.*)
- *(.init) /* Old ABI */
- *(.fini) /* Old ABI */
- _etext = . ;
- }
-
- .rodata :
- {
- _srodata = . ;
- *(.rodata)
- *(.rodata1)
- *(.rodata.*)
- *(.gnu.linkonce.r*)
- _erodata = . ;
- }
-
- .data :
- {
- _sdata = . ;
- *(.data)
- *(.data1)
- *(.data.*)
- *(.gnu.linkonce.d*)
- _edata = . ;
- }
-
- /* C++ support. For each global and static local C++ object,
- * GCC creates a small subroutine to construct the object. Pointers
- * to these routines (not the routines themselves) are stored as
- * simple, linear arrays in the .ctors section of the object file.
- * Similarly, pointers to global/static destructor routines are
- * stored in .dtors.
- */
-
- .ctors :
- {
- _sctors = . ;
- *(.ctors) /* Old ABI: Unallocated */
- *(.init_array) /* New ABI: Allocated */
- _edtors = . ;
- }
-
- .dtors :
- {
- _sdtors = . ;
- *(.dtors) /* Old ABI: Unallocated */
- *(.fini_array) /* New ABI: Allocated */
- _edtors = . ;
- }
-
- .bss :
- {
- _sbss = . ;
- *(.bss)
- *(.bss.*)
- *(.sbss)
- *(.sbss.*)
- *(.gnu.linkonce.b*)
- *(COMMON)
- _ebss = . ;
- }
-
- /* Stabs debugging sections. */
-
- .stab 0 : { *(.stab) }
- .stabstr 0 : { *(.stabstr) }
- .stab.excl 0 : { *(.stab.excl) }
- .stab.exclstr 0 : { *(.stab.exclstr) }
- .stab.index 0 : { *(.stab.index) }
- .stab.indexstr 0 : { *(.stab.indexstr) }
- .comment 0 : { *(.comment) }
- .debug_abbrev 0 : { *(.debug_abbrev) }
- .debug_info 0 : { *(.debug_info) }
- .debug_line 0 : { *(.debug_line) }
- .debug_pubnames 0 : { *(.debug_pubnames) }
- .debug_aranges 0 : { *(.debug_aranges) }
-}
diff --git a/nuttx-configs/px4fmu-v1/scripts/ld.script b/nuttx-configs/px4fmu-v1/scripts/ld.script
index f6560743b..ced5b21b7 100644
--- a/nuttx-configs/px4fmu-v1/scripts/ld.script
+++ b/nuttx-configs/px4fmu-v1/scripts/ld.script
@@ -1,7 +1,7 @@
/****************************************************************************
- * configs/stm32f4discovery/scripts/ld.script
+ * configs/px4fmu-v1/scripts/ld.script
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -42,41 +42,67 @@
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
- * the 0x0800:0000 address
- * range.
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x4000 of flash is reserved for the bootloader.
*/
MEMORY
{
- flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
- sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
+ flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
+ ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
}
OUTPUT_ARCH(arm)
-EXTERN(_vectors)
-ENTRY(_stext)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
- *(.text .text.*)
+ *(.text .text.*)
*(.fixup)
*(.gnu.warning)
- *(.rodata .rodata.*)
+ *(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
- *(.glue_7)
- *(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
+
+ /*
+ * This is a hack to make the newlib libm __errno() call
+ * use the NuttX get_errno_ptr() function.
+ */
+ __errno = get_errno_ptr;
} > flash
- .init_section : {
- _sinit = ABSOLUTE(.);
- *(.init_array .init_array.*)
- _einit = ABSOLUTE(.);
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Construction data for parameters.
+ */
+ __param ALIGN(4): {
+ __param_start = ABSOLUTE(.);
+ KEEP(*(__param*))
+ __param_end = ABSOLUTE(.);
} > flash
.ARM.extab : {