forked from Archive/PX4-Autopilot
Move ld.script files from configuration directories to script/ directory
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5249 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
parent
2327d0eedc
commit
d300539524
|
@ -3500,4 +3500,9 @@
|
||||||
initial reset in the open/setup logic. Opening the ADC driver works
|
initial reset in the open/setup logic. Opening the ADC driver works
|
||||||
the first time, but not the second because the device is left in a
|
the first time, but not the second because the device is left in a
|
||||||
powered down state on the last close.
|
powered down state on the last close.
|
||||||
|
* configs/olimex-lpc1766stck/scripts: Replace all of the identical
|
||||||
|
ld.script files with the common one in this directory.
|
||||||
|
* configs/stm3220g-eval/scripts: Replace all of the identical
|
||||||
|
ld.script files with the common one in this directory.
|
||||||
|
* configs/hymini-stm32v/scripts: Replace all of the identical
|
||||||
|
ld.script files with the common one in this directory.
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/hymini-stm32v/buttons/Make.defs
|
# configs/hymini-stm32v/buttons/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/buttons/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/buttons/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,112 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/buttons/ld.script
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 48Kb of SRAM beginning at address 0x2000:0000. 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103V has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,111 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/buttons/ld.script.dfu
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the
|
|
||||||
* Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct
|
|
||||||
* load .text load address is 0x08003000 (leaving 464Kb).
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/hymini-stm32v/nsh/Make.defs
|
# configs/hymini-stm32v/nsh/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,112 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/nsh/ld.script
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 64Kb of SRAM beginning at address 0x2000:0000. 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,111 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/nsh/ld.script.dfu
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the
|
|
||||||
* Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct
|
|
||||||
* load .text load address is 0x08003000 (leaving 464Kb).
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/hymini-stm32v/nsh2/Make.defs
|
# configs/hymini-stm32v/nsh2/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh2/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh2/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,112 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/nsh2/ld.script
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 48Kb of SRAM beginning at address 0x2000:0000. 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,111 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/nsh2/ld.script.dfu
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the
|
|
||||||
* Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct
|
|
||||||
* load .text load address is 0x08003000 (leaving 464Kb).
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/hymini-stm32v/nx/Make.defs
|
# configs/hymini-stm32v/nx/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nx/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nx/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,111 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/nx/ld.script.dfu
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the
|
|
||||||
* Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct
|
|
||||||
* load .text load address is 0x08003000 (leaving 464Kb).
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/hymini-stm32v/nxlines/Make.defs
|
# configs/hymini-stm32v/nxlines/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -89,13 +89,13 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nxlines/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nxlines/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,112 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/nxlines/ld.script
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 48Kb of SRAM beginning at address 0x2000:0000. 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,111 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/nxlines/ld.script.dfu
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the
|
|
||||||
* Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct
|
|
||||||
* load .text load address is 0x08003000 (leaving 464Kb).
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
6
nuttx/configs/hymini-stm32v/usbserial/ld.script → nuttx/configs/hymini-stm32v/scripts/ld.script
Executable file → Normal file
6
nuttx/configs/hymini-stm32v/usbserial/ld.script → nuttx/configs/hymini-stm32v/scripts/ld.script
Executable file → Normal file
|
@ -1,10 +1,10 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* configs/hymini-stm32v/usbserial/ld.script
|
* configs/hymini-stm32v/scripts/ld.script
|
||||||
*
|
*
|
||||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
* Laurent Latil <laurent@latil.nom.fr>
|
* Laurent Latil <laurent@latil.nom.fr>
|
||||||
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
* are met:
|
* are met:
|
|
@ -1,7 +1,7 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* configs/hymini-stm32v/nx/ld.script
|
* configs/hymini-stm32v/scripts/ld.script.dfu
|
||||||
*
|
*
|
||||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -34,15 +34,14 @@
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and
|
/* The STM32F103VCT6 has 256Kb of FLASH beginning at address 0x0800:0000 and
|
||||||
* 48Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH,
|
* 48Kb of SRAM beginning at address 0x2000:0000. Here we assume that the
|
||||||
* FLASH memory is aliased to address 0x0000:0000 where the code expects to
|
* Hy-Mini STM32v's DFU bootloader is being used. In that case, the correct
|
||||||
* begin execution by jumping to the entry point in the 0x0800:0000 address
|
* load .text load address is 0x08003000 (leaving 244Kb).
|
||||||
* range.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
MEMORY
|
MEMORY
|
||||||
{
|
{
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K
|
flash (rx) : ORIGIN = 0x08003000, LENGTH = 244K
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K
|
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/hymini-stm32v/usbserial/Make.defs
|
# configs/hymini-stm32v/usbserial/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/usbserial/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/usbserial/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,111 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/usbserial/ld.script.dfu
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the
|
|
||||||
* Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct
|
|
||||||
* load .text load address is 0x08003000 (leaving 464Kb).
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/hymini-stm32v/usbstorage/Make.defs
|
# configs/hymini-stm32v/usbstorage/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -86,14 +86,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/usbstorage/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/usbstorage/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,112 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/usbstorage/ld.script
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 64Kb of SRAM beginning at address 0x2000:0000. 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,111 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/hymini-stm32v/usbstorage/ld.script.dfu
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the
|
|
||||||
* Hy-Mini STM32v's DFU bootloader is being used. In that case, the corrct
|
|
||||||
* load .text load address is 0x08003000 (leaving 464Kb).
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/* The STM32F103VCT6 has 48Kb of SRAM beginning at the following address */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/ftpc/Make.defs
|
# configs/olimex-lpc1766stk/ftpc/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ftpc/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ftpc/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/ftpc/ld.script
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/hidkbd/Make.defs
|
# configs/olimex-lpc1766stk/hidkbd/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/hidkbd/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/hidkbd/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/hidkbd/ld.script
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/nettest/Make.defs
|
# configs/olimex-lpc1766stk/nettest/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nettest/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nettest/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/nettest/ld.script
|
|
||||||
*
|
|
||||||
* Copyright (C) 2010-2011 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/nsh/Make.defs
|
# configs/olimex-lpc1766stk/nsh/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/nx/Make.defs
|
# configs/olimex-lpc1766stk/nx/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nx/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nx/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/nx/ld.script
|
|
||||||
*
|
|
||||||
* Copyright (C) 2010-2011 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/ostest/Make.defs
|
# configs/olimex-lpc1766stk/ostest/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/ostest/ld.script
|
|
||||||
*
|
|
||||||
* Copyright (C) 2010-2011 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* configs/olimex-lpc1766stk/nsh/ld.script
|
* configs/olimex-lpc1766stk/scripts/ld.script
|
||||||
*
|
*
|
||||||
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
* Copyright (C) 2010-2012 Gregory Nutt. All rights reserved.
|
||||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -66,7 +66,7 @@ SECTIONS
|
||||||
_etext = ABSOLUTE(.);
|
_etext = ABSOLUTE(.);
|
||||||
} > flash
|
} > flash
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
_eronly = ABSOLUTE(.);
|
||||||
|
|
||||||
.data : {
|
.data : {
|
||||||
_sdata = ABSOLUTE(.);
|
_sdata = ABSOLUTE(.);
|
||||||
|
@ -86,14 +86,16 @@ SECTIONS
|
||||||
} >sram
|
} >sram
|
||||||
__exidx_end = ABSOLUTE(.);
|
__exidx_end = ABSOLUTE(.);
|
||||||
|
|
||||||
.bss : { /* BSS */
|
.bss : {
|
||||||
_sbss = ABSOLUTE(.);
|
_sbss = ABSOLUTE(.);
|
||||||
*(.bss .bss.*)
|
*(.bss .bss.*)
|
||||||
*(.gnu.linkonce.b.*)
|
*(.gnu.linkonce.b.*)
|
||||||
*(COMMON)
|
*(COMMON)
|
||||||
_ebss = ABSOLUTE(.);
|
_ebss = ABSOLUTE(.);
|
||||||
} > sram
|
} > sram
|
||||||
|
|
||||||
/* Stabs debugging sections. */
|
/* Stabs debugging sections. */
|
||||||
|
|
||||||
.stab 0 : { *(.stab) }
|
.stab 0 : { *(.stab) }
|
||||||
.stabstr 0 : { *(.stabstr) }
|
.stabstr 0 : { *(.stabstr) }
|
||||||
.stab.excl 0 : { *(.stab.excl) }
|
.stab.excl 0 : { *(.stab.excl) }
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/slip-httpd/Make.defs
|
# configs/olimex-lpc1766stk/slip-httpd/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/slip-httpd/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/slip-httpd/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/slip-httpd/ld.script
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/thttpd/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/thttpd/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/thttpd/ld.script
|
|
||||||
*
|
|
||||||
* Copyright (C) 2010-2011 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/usbserial/Make.defs
|
# configs/olimex-lpc1766stk/usbserial/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/usbserial/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/usbserial/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/usbserial/ld.script
|
|
||||||
*
|
|
||||||
* Copyright (C) 2010-2011 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/usbstorage/Make.defs
|
# configs/olimex-lpc1766stk/usbstorage/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/usbstorage/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/usbstorage/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/usbstorage/ld.script
|
|
||||||
*
|
|
||||||
* Copyright (C) 2010-2011 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,7 +1,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
# configs/olimex-lpc1766stk/wlan/Make.defs
|
# configs/olimex-lpc1766stk/wlan/Make.defs
|
||||||
#
|
#
|
||||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
# Copyright (C) 2011, 2012 Gregory Nutt. All rights reserved.
|
||||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
@ -74,14 +74,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/wlan/ld.script}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/wlan/ld.script
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,109 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/olimex-lpc1766stk/wlan/ld.script
|
|
||||||
*
|
|
||||||
* 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
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The LPC1766 has 256Kb of FLASH beginning at address 0x0000:0000 and
|
|
||||||
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
|
|
||||||
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
|
|
||||||
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
|
|
||||||
* into the 32Kb CPU SRAM address range.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
|
||||||
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.); /* See below */
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} >sram
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.bss : { /* BSS */
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/dhcpd/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/dhcpd/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nettest/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nettest/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,121 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/stm3220g-eval/nettest/ld.script
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 128Kb of SRAM. SRAM is split up into two blocks:
|
|
||||||
*
|
|
||||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
|
||||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
.init_section : {
|
|
||||||
_sinit = ABSOLUTE(.);
|
|
||||||
*(.init_array .init_array.*)
|
|
||||||
_einit = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} > flash
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,121 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/stm3220g-eval/nsh/ld.script
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 128Kb of SRAM. SRAM is split up into two blocks:
|
|
||||||
*
|
|
||||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
|
||||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
.init_section : {
|
|
||||||
_sinit = ABSOLUTE(.);
|
|
||||||
*(.init_array .init_array.*)
|
|
||||||
_einit = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} > flash
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh2/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nsh2/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,121 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/stm3220g-eval/nsh2/ld.script
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 128Kb of SRAM. SRAM is split up into two blocks:
|
|
||||||
*
|
|
||||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
|
||||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
.init_section : {
|
|
||||||
_sinit = ABSOLUTE(.);
|
|
||||||
*(.init_array .init_array.*)
|
|
||||||
_einit = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} > flash
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nxwm/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/nxwm/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,121 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/stm3220g-eval/nxwm/ld.script
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 128Kb of SRAM. SRAM is split up into two blocks:
|
|
||||||
*
|
|
||||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
|
||||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
.init_section : {
|
|
||||||
_sinit = ABSOLUTE(.);
|
|
||||||
*(.init_array .init_array.*)
|
|
||||||
_einit = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} > flash
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,120 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/stm3220g-eval/ostest/ld.script
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F207IGH6U has 1024Kb of FLASH two blocks:
|
|
||||||
*
|
|
||||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
|
||||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
.init_section : {
|
|
||||||
_sinit = ABSOLUTE(.);
|
|
||||||
*(.init_array .init_array.*)
|
|
||||||
_einit = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} > flash
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
|
@ -1,5 +1,5 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* configs/stm3220g-eval/dhcpd/ld.script
|
* configs/stm3220g-eval/scripts/ld.script
|
||||||
*
|
*
|
||||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
|
@ -110,14 +110,14 @@ ifeq ($(WINTOOL),y)
|
||||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/telnetd/$(LDSCRIPT)}"
|
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||||
MAXOPTIMIZATION = -O2
|
MAXOPTIMIZATION = -O2
|
||||||
else
|
else
|
||||||
# Linux/Cygwin-native toolchain
|
# Linux/Cygwin-native toolchain
|
||||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/telnetd/$(LDSCRIPT)
|
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CC = $(CROSSDEV)gcc
|
CC = $(CROSSDEV)gcc
|
||||||
|
|
|
@ -1,121 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/stm3220g-eval/telnetd/ld.script
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The STM32F207IGH6U has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
|
||||||
* 128Kb of SRAM. SRAM is split up into two blocks:
|
|
||||||
*
|
|
||||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
|
||||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
|
|
||||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
ENTRY(_stext)
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
.init_section : {
|
|
||||||
_sinit = ABSOLUTE(.);
|
|
||||||
*(.init_array .init_array.*)
|
|
||||||
_einit = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} > flash
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} >sram
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* 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) }
|
|
||||||
}
|
|
Loading…
Reference in New Issue