From 81ddf0a8db0be4f28d0df909e17dccd36a5bc687 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 6 Sep 2012 22:25:51 +0000 Subject: Repairs needed after Kconfig changes for LPC31 git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5105 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/ea3131/README.txt | 36 +++---- nuttx/configs/ea3131/locked/mklocked.sh | 6 +- nuttx/configs/ea3131/nsh/Make.defs | 14 +-- nuttx/configs/ea3131/nsh/ld.script | 107 -------------------- nuttx/configs/ea3131/nsh/setenv.sh | 31 ++++-- nuttx/configs/ea3131/ostest/Make.defs | 18 ++-- nuttx/configs/ea3131/ostest/ld.script | 107 -------------------- nuttx/configs/ea3131/ostest/setenv.sh | 31 ++++-- nuttx/configs/ea3131/pgnsh/Make.defs | 18 ++-- nuttx/configs/ea3131/pgnsh/ld.script | 151 ----------------------------- nuttx/configs/ea3131/pgnsh/setenv.sh | 31 ++++-- nuttx/configs/ea3131/scripts/ld.script | 108 +++++++++++++++++++++ nuttx/configs/ea3131/scripts/pg-ld.script | 151 +++++++++++++++++++++++++++++ nuttx/configs/ea3131/src/Makefile | 6 +- nuttx/configs/ea3131/src/ea3131_internal.h | 6 +- nuttx/configs/ea3131/src/up_boot.c | 10 +- nuttx/configs/ea3131/src/up_fillpage.c | 8 +- nuttx/configs/ea3131/src/up_mem.c | 12 +-- nuttx/configs/ea3131/src/up_nsh.c | 8 +- nuttx/configs/ea3131/src/up_spi.c | 8 +- nuttx/configs/ea3131/usbserial/Make.defs | 18 ++-- nuttx/configs/ea3131/usbserial/ld.script | 108 --------------------- nuttx/configs/ea3131/usbserial/setenv.sh | 31 ++++-- nuttx/configs/ea3131/usbstorage/Make.defs | 18 ++-- nuttx/configs/ea3131/usbstorage/ld.script | 107 -------------------- nuttx/configs/ea3131/usbstorage/setenv.sh | 31 ++++-- nuttx/configs/ea3152/README.txt | 34 +++---- nuttx/configs/ea3152/ostest/Make.defs | 16 +-- nuttx/configs/ea3152/ostest/ld.script | 107 -------------------- nuttx/configs/ea3152/ostest/setenv.sh | 29 +++++- nuttx/configs/ea3152/scripts/ld.script | 107 ++++++++++++++++++++ nuttx/configs/ea3152/src/Makefile | 4 +- nuttx/configs/ea3152/src/ea3152_internal.h | 2 +- nuttx/configs/ea3152/src/up_boot.c | 6 +- nuttx/configs/ea3152/src/up_fillpage.c | 4 +- nuttx/configs/ea3152/src/up_mem.c | 8 +- nuttx/configs/ea3152/src/up_nsh.c | 4 +- nuttx/configs/ea3152/src/up_spi.c | 4 +- nuttx/configs/stm3240g-eval/nxwm/setenv.sh | 8 -- 39 files changed, 649 insertions(+), 864 deletions(-) delete mode 100644 nuttx/configs/ea3131/nsh/ld.script delete mode 100644 nuttx/configs/ea3131/ostest/ld.script delete mode 100644 nuttx/configs/ea3131/pgnsh/ld.script create mode 100644 nuttx/configs/ea3131/scripts/ld.script create mode 100644 nuttx/configs/ea3131/scripts/pg-ld.script delete mode 100644 nuttx/configs/ea3131/usbserial/ld.script delete mode 100644 nuttx/configs/ea3131/usbstorage/ld.script delete mode 100644 nuttx/configs/ea3152/ostest/ld.script create mode 100644 nuttx/configs/ea3152/scripts/ld.script (limited to 'nuttx/configs') diff --git a/nuttx/configs/ea3131/README.txt b/nuttx/configs/ea3131/README.txt index 19f848c81..f3239e476 100644 --- a/nuttx/configs/ea3131/README.txt +++ b/nuttx/configs/ea3131/README.txt @@ -43,12 +43,12 @@ GNU Toolchain Options add one of the following configuration options to your .config (or defconfig) file: - CONFIG_LPC31XX_CODESOURCERYW=y : CodeSourcery under Windows - CONFIG_LPC31XX_CODESOURCERYL=y : CodeSourcery under Linux - CONFIG_LPC31XX_DEVKITARM=y : devkitARM under Windows - CONFIG_LPC31XX_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) + CONFIG_LPC31_CODESOURCERYW=y : CodeSourcery under Windows + CONFIG_LPC31_CODESOURCERYL=y : CodeSourcery under Linux + CONFIG_LPC31_DEVKITARM=y : devkitARM under Windows + CONFIG_LPC31_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) - If you are not using CONFIG_LPC31XX_BUILDROOT, then you may also have to modify + If you are not using CONFIG_LPC31_BUILDROOT, then you may also have to modify the PATH in the setenv.h file if your make cannot find the tools. NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are @@ -381,7 +381,7 @@ On-Demand Paging configs/ea3131/locked/Makefile to build the first pass object, locked.r. This first pass object contains all of the code that must be in the locked text region. The Makefile in arch/arm/src/Makefile then includes this 1st - pass in build, positioning it as controlled by configs/ea3131/pgnsh/ld.script. + pass in build, positioning it as controlled by configs/ea3131/scripts/pg-ld.script. Finishing the Example: ---------------------- @@ -549,27 +549,27 @@ ARM/EA3131-specific Configuration Options Individual subsystems can be enabled: - CONFIG_LPC31XX_MCI, CONFIG_LPC31XX_SPI, CONFIG_LPC31XX_UART + CONFIG_LPC31_MCI, CONFIG_LPC31_SPI, CONFIG_LPC31_UART External memory available on the board (see also CONFIG_MM_REGIONS) - CONFIG_LPC31XX_EXTSRAM0 - Select if external SRAM0 is present - CONFIG_LPC31XX_EXTSRAM0HEAP - Select if external SRAM0 should be + CONFIG_LPC31_EXTSRAM0 - Select if external SRAM0 is present + CONFIG_LPC31_EXTSRAM0HEAP - Select if external SRAM0 should be configured as part of the NuttX heap. - CONFIG_LPC31XX_EXTSRAM0SIZE - Size (in bytes) of the installed + CONFIG_LPC31_EXTSRAM0SIZE - Size (in bytes) of the installed external SRAM0 memory - CONFIG_LPC31XX_EXTSRAM1 - Select if external SRAM1 is present - CONFIG_LPC31XX_EXTSRAM1HEAP - Select if external SRAM1 should be + CONFIG_LPC31_EXTSRAM1 - Select if external SRAM1 is present + CONFIG_LPC31_EXTSRAM1HEAP - Select if external SRAM1 should be configured as part of the NuttX heap. - CONFIG_LPC31XX_EXTSRAM1SIZE - Size (in bytes) of the installed + CONFIG_LPC31_EXTSRAM1SIZE - Size (in bytes) of the installed external SRAM1 memory - CONFIG_LPC31XX_EXTSDRAM - Select if external SDRAM is present - CONFIG_LPC31XX_EXTSDRAMHEAP - Select if external SDRAM should be + CONFIG_LPC31_EXTSDRAM - Select if external SDRAM is present + CONFIG_LPC31_EXTSDRAMHEAP - Select if external SDRAM should be configured as part of the NuttX heap. - CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed + CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed external SDRAM memory - CONFIG_LPC31XX_EXTNAND - Select if external NAND is present - CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed + CONFIG_LPC31_EXTNAND - Select if external NAND is present + CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed external NAND memory LPC313X specific device driver settings diff --git a/nuttx/configs/ea3131/locked/mklocked.sh b/nuttx/configs/ea3131/locked/mklocked.sh index ac99f4438..731accde3 100755 --- a/nuttx/configs/ea3131/locked/mklocked.sh +++ b/nuttx/configs/ea3131/locked/mklocked.sh @@ -2,8 +2,8 @@ ########################################################################### # configs/ea3131/locked/mklocked.sh # -# Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Copyright (C) 2010-2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -117,7 +117,7 @@ echo "EXTERN(up_vectoraddrexcptn)" >>ld-locked.inc echo "EXTERN(up_timerinit)" >>ld-locked.inc -answer=$(checkconfig CONFIG_LPC31XX_UART) +answer=$(checkconfig CONFIG_LPC31_UART) if [ $answer = y ]; then echo "EXTERN(up_earlyserialinit)" >>ld-locked.inc fi diff --git a/nuttx/configs/ea3131/nsh/Make.defs b/nuttx/configs/ea3131/nsh/Make.defs index e17d3c674..bff75e8e0 100644 --- a/nuttx/configs/ea3131/nsh/Make.defs +++ b/nuttx/configs/ea3131/nsh/Make.defs @@ -38,23 +38,23 @@ include ${TOPDIR}/tools/Config.mk # Setup for the selected toolchain -ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) +ifeq ($(CONFIG_LPC31_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -67,13 +67,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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}" else # Linux/Cygwin-native toolchain MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include 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 CC = $(CROSSDEV)gcc @@ -122,7 +122,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifneq ($(CONFIG_LPC31_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/nsh/ld.script b/nuttx/configs/ea3131/nsh/ld.script deleted file mode 100644 index 8c3b2db45..000000000 --- a/nuttx/configs/ea3131/nsh/ld.script +++ /dev/null @@ -1,107 +0,0 @@ -/**************************************************************************** - * configs/ea3131/nsh/ld.script - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC31xx boot ROM expects the boot image be compiled with entry point at - * 0x1102:9000. A 128b header will appear at this address (applied by - * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. - */ - -MEMORY -{ - isram (rwx) : ORIGIN = 0x11029080, LENGTH = 192K - 4224 -} - -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(.); - } > isram - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > isram - - .ARM.extab : { - *(.ARM.extab*) - } >isram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } > isram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > isram - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_info 0 : { *(.debug_info) } - .debug_line 0 : { *(.debug_line) } - .debug_pubnames 0 : { *(.debug_pubnames) } - .debug_aranges 0 : { *(.debug_aranges) } -} diff --git a/nuttx/configs/ea3131/nsh/setenv.sh b/nuttx/configs/ea3131/nsh/setenv.sh index 816dff18b..671df47f1 100755 --- a/nuttx/configs/ea3131/nsh/setenv.sh +++ b/nuttx/configs/ea3131/nsh/setenv.sh @@ -32,16 +32,35 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG=${PATH}; fi - WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" -export LPCTOOL_DIR="${WD}/configs/ea3131/tools" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# This the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# This is the path to the tools subdirectory + +export LPCTOOL_DIR="${WD}/configs/ea3152/tools" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/ea3131/ostest/Make.defs b/nuttx/configs/ea3131/ostest/Make.defs index cb0fcaff4..0ed68f285 100644 --- a/nuttx/configs/ea3131/ostest/Make.defs +++ b/nuttx/configs/ea3131/ostest/Make.defs @@ -1,8 +1,8 @@ ############################################################################ # configs/ea3131/ostest/Make.defs # -# Copyright (C) 2009 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Copyright (C) 2009,2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -38,23 +38,23 @@ include ${TOPDIR}/tools/Config.mk # Setup for the selected toolchain -ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) +ifeq ($(CONFIG_LPC31_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -67,13 +67,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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}" else # Linux/Cygwin-native toolchain MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include 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 CC = $(CROSSDEV)gcc @@ -122,7 +122,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifneq ($(CONFIG_LPC31_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/ostest/ld.script b/nuttx/configs/ea3131/ostest/ld.script deleted file mode 100644 index 531e64ce9..000000000 --- a/nuttx/configs/ea3131/ostest/ld.script +++ /dev/null @@ -1,107 +0,0 @@ -/**************************************************************************** - * configs/ea3131/ostest/ld.script - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC31xx boot ROM expects the boot image be compiled with entry point at - * 0x1102:9000. A 128b header will appear at this address (applied by - * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. - */ - -MEMORY -{ - isram (rwx) : ORIGIN = 0x11029080, LENGTH = 192K - 4224 -} - -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(.); - } > isram - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > isram - - .ARM.extab : { - *(.ARM.extab*) - } >isram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } > isram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > isram - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_info 0 : { *(.debug_info) } - .debug_line 0 : { *(.debug_line) } - .debug_pubnames 0 : { *(.debug_pubnames) } - .debug_aranges 0 : { *(.debug_aranges) } -} diff --git a/nuttx/configs/ea3131/ostest/setenv.sh b/nuttx/configs/ea3131/ostest/setenv.sh index 796add80e..a8155ab79 100755 --- a/nuttx/configs/ea3131/ostest/setenv.sh +++ b/nuttx/configs/ea3131/ostest/setenv.sh @@ -32,16 +32,35 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG=${PATH}; fi - WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" -export LPCTOOL_DIR="${WD}/configs/ea3131/tools" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# This the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# This is the path to the tools subdirectory + +export LPCTOOL_DIR="${WD}/configs/ea3152/tools" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/ea3131/pgnsh/Make.defs b/nuttx/configs/ea3131/pgnsh/Make.defs index cf712d296..d9a6794f5 100644 --- a/nuttx/configs/ea3131/pgnsh/Make.defs +++ b/nuttx/configs/ea3131/pgnsh/Make.defs @@ -1,8 +1,8 @@ ############################################################################ # configs/ea3131/pgnsh/Make.defs # -# Copyright (C) 2010 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Copyright (C) 2010,2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -38,23 +38,23 @@ include ${TOPDIR}/tools/Config.mk # Setup for the selected toolchain -ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) +ifeq ($(CONFIG_LPC31_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -67,13 +67,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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)/pgnsh/ld.script}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/pg-ld.script}" else # Linux/Cygwin-native toolchain MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx - ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/pgnsh/ld.script + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/pg-ld.script endif CC = $(CROSSDEV)gcc @@ -122,7 +122,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifneq ($(CONFIG_LPC31_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/pgnsh/ld.script b/nuttx/configs/ea3131/pgnsh/ld.script deleted file mode 100644 index c4c597567..000000000 --- a/nuttx/configs/ea3131/pgnsh/ld.script +++ /dev/null @@ -1,151 +0,0 @@ -/**************************************************************************** - * configs/ea3131/pgnsh/ld.script - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC31xx boot ROM expects the boot image be compiled with entry point at - * 0x1102:9000. A 128b header will appear at this address (applied by - * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. - * - * The .text vitual address space begins at the same location as the physical - * address space: 0x1102 8000. The virtual space is broken up into three - * regions: - * - * PHYSICAL VIRTUAL - * NAME DESCRIPTION SIZE START SIZE START - * -------- -------------------------- ----- ----------- ------- ----------- - * locked Pages locked in memory. 48Kb 0x1102 8000 48Kb 0x1102 8000 - * paged Pages in nonvolatile store. 96Kb 0x1103 4000 384Kb 0x1103 4000 - * data .data/.bss/heap. 32Kb 0x1104 c000 32Kb 0x1109 4000 - * Reserved for page table 16Kb 0x1105 4000 16Kb 0x1109 c000 - * -------- -------------------------- ----- ----------- ------- ----------- - * 192Kb 0x1105 8000 480Kb 0x110a 0000 - * - * These region sizes must match the size in pages specified for each region - * in the NuttX configuration file: CONFIG_PAGING_NLOCKED, CONFIG_PAGING_NVPAGED, - * and CONFIG_PAGING_NDATA. - * - * NOTE 1: The locked region is really big here so that you can enable lots of - * debug output without overflowing the locked region. 32Kb would probably be - * plenty if this were a real, optimized application. - * - * NOTE 2: Different compilers will compile the code to different sizes. If you - * get a link time error saying that the locked region is full, you may have to - * re-organize this memory layout (here and in defconfig) to make the locked - * region even bigger. - */ - -MEMORY -{ - locked (rx) : ORIGIN = 0x11029080, LENGTH = 48K - 4224 - paged (rx) : ORIGIN = 0x11034000, LENGTH = 384K - data (rw) : ORIGIN = 0x11094000, LENGTH = 44K -} - -OUTPUT_ARCH(arm) -ENTRY(_stext) -SECTIONS -{ - .locked : { - _slocked = ABSOLUTE(.); - *(.vectors) - up_head.o locked.r (.text .text.*) - up_head.o locked.r (.fixup) - up_head.o locked.r (.gnu.warning) - up_head.o locked.r (.rodata .rodata.*) - up_head.o locked.r (.gnu.linkonce.t.*) - up_head.o locked.r (.glue_7) - up_head.o locked.r (.glue_7t) - up_head.o locked.r (.got) - up_head.o locked.r (.gcc_except_table) - up_head.o locked.r (.gnu.linkonce.r.*) - _elocked = ABSOLUTE(.); - } >locked - - _eronly = ABSOLUTE(.); - - .paged : { - _spaged = ABSOLUTE(.); - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _epaged = ABSOLUTE(.); - } > paged - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > data AT > locked - - .ARM.extab : { - *(.ARM.extab*) - } >data - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } > data - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > data - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_info 0 : { *(.debug_info) } - .debug_line 0 : { *(.debug_line) } - .debug_pubnames 0 : { *(.debug_pubnames) } - .debug_aranges 0 : { *(.debug_aranges) } -} diff --git a/nuttx/configs/ea3131/pgnsh/setenv.sh b/nuttx/configs/ea3131/pgnsh/setenv.sh index 97775e861..82205c452 100755 --- a/nuttx/configs/ea3131/pgnsh/setenv.sh +++ b/nuttx/configs/ea3131/pgnsh/setenv.sh @@ -32,16 +32,35 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG=${PATH}; fi - WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" -export LPCTOOL_DIR="${WD}/configs/ea3131/tools" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# This the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# This is the path to the tools subdirectory + +export LPCTOOL_DIR="${WD}/configs/ea3152/tools" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/ea3131/scripts/ld.script b/nuttx/configs/ea3131/scripts/ld.script new file mode 100644 index 000000000..333117c19 --- /dev/null +++ b/nuttx/configs/ea3131/scripts/ld.script @@ -0,0 +1,108 @@ +/**************************************************************************** + * configs/ea3131/scripts/ld.script + * + * Copyright (C) 2010-2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. + * LPC31xx boot ROM expects the boot image be compiled with entry point at + * 0x1102:9000. A 128b header will appear at this address (applied by + * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. + */ + +MEMORY +{ + isram (rwx) : ORIGIN = 0x11029080, LENGTH = 192K - 4224 +} + +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(.); + } > isram + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > isram + + .ARM.extab : { + *(.ARM.extab*) + } >isram + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > isram + __exidx_end = ABSOLUTE(.); + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > isram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx/configs/ea3131/scripts/pg-ld.script b/nuttx/configs/ea3131/scripts/pg-ld.script new file mode 100644 index 000000000..90a713c7d --- /dev/null +++ b/nuttx/configs/ea3131/scripts/pg-ld.script @@ -0,0 +1,151 @@ +/**************************************************************************** + * configs/ea3131/scripts/pg-ld.script + * + * Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. + * LPC31xx boot ROM expects the boot image be compiled with entry point at + * 0x1102:9000. A 128b header will appear at this address (applied by + * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. + * + * The .text vitual address space begins at the same location as the physical + * address space: 0x1102 8000. The virtual space is broken up into three + * regions: + * + * PHYSICAL VIRTUAL + * NAME DESCRIPTION SIZE START SIZE START + * -------- -------------------------- ----- ----------- ------- ----------- + * locked Pages locked in memory. 48Kb 0x1102 8000 48Kb 0x1102 8000 + * paged Pages in nonvolatile store. 96Kb 0x1103 4000 384Kb 0x1103 4000 + * data .data/.bss/heap. 32Kb 0x1104 c000 32Kb 0x1109 4000 + * Reserved for page table 16Kb 0x1105 4000 16Kb 0x1109 c000 + * -------- -------------------------- ----- ----------- ------- ----------- + * 192Kb 0x1105 8000 480Kb 0x110a 0000 + * + * These region sizes must match the size in pages specified for each region + * in the NuttX configuration file: CONFIG_PAGING_NLOCKED, CONFIG_PAGING_NVPAGED, + * and CONFIG_PAGING_NDATA. + * + * NOTE 1: The locked region is really big here so that you can enable lots of + * debug output without overflowing the locked region. 32Kb would probably be + * plenty if this were a real, optimized application. + * + * NOTE 2: Different compilers will compile the code to different sizes. If you + * get a link time error saying that the locked region is full, you may have to + * re-organize this memory layout (here and in defconfig) to make the locked + * region even bigger. + */ + +MEMORY +{ + locked (rx) : ORIGIN = 0x11029080, LENGTH = 48K - 4224 + paged (rx) : ORIGIN = 0x11034000, LENGTH = 384K + data (rw) : ORIGIN = 0x11094000, LENGTH = 44K +} + +OUTPUT_ARCH(arm) +ENTRY(_stext) +SECTIONS +{ + .locked : { + _slocked = ABSOLUTE(.); + *(.vectors) + up_head.o locked.r (.text .text.*) + up_head.o locked.r (.fixup) + up_head.o locked.r (.gnu.warning) + up_head.o locked.r (.rodata .rodata.*) + up_head.o locked.r (.gnu.linkonce.t.*) + up_head.o locked.r (.glue_7) + up_head.o locked.r (.glue_7t) + up_head.o locked.r (.got) + up_head.o locked.r (.gcc_except_table) + up_head.o locked.r (.gnu.linkonce.r.*) + _elocked = ABSOLUTE(.); + } >locked + + _eronly = ABSOLUTE(.); + + .paged : { + _spaged = ABSOLUTE(.); + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _epaged = ABSOLUTE(.); + } > paged + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > data AT > locked + + .ARM.extab : { + *(.ARM.extab*) + } >data + + .ARM.exidx : { + __exidx_start = ABSOLUTE(.); + *(.ARM.exidx*) + __exidx_end = ABSOLUTE(.); + } > data + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > data + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx/configs/ea3131/src/Makefile b/nuttx/configs/ea3131/src/Makefile index 685bfd997..c3774db71 100644 --- a/nuttx/configs/ea3131/src/Makefile +++ b/nuttx/configs/ea3131/src/Makefile @@ -2,7 +2,7 @@ # configs/ea3131/src/Makefile # # Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -44,13 +44,13 @@ CSRCS = up_boot.c up_clkinit.c ifeq ($(CONFIG_ARCH_BUTTONS),y) CSRCS += up_buttons.c endif -ifeq ($(CONFIG_LPC31XX_EXTSDRAM),y) +ifeq ($(CONFIG_LPC31_EXTSDRAM),y) CSRCS += up_mem.c endif ifeq ($(CONFIG_ARCH_LEDS),y) CSRCS += up_leds.c endif -ifeq ($(CONFIG_LPC31XX_SPI),y) +ifeq ($(CONFIG_LPC31_SPI),y) CSRCS += up_spi.c endif ifeq ($(CONFIG_NSH_ARCHINIT),y) diff --git a/nuttx/configs/ea3131/src/ea3131_internal.h b/nuttx/configs/ea3131/src/ea3131_internal.h index ca2a5b570..4a8ae3fa4 100644 --- a/nuttx/configs/ea3131/src/ea3131_internal.h +++ b/nuttx/configs/ea3131/src/ea3131_internal.h @@ -2,8 +2,8 @@ * configs/ea3131/src/ea3131_internal.h * arch/arm/src/board/ea3131_internal.n * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2009-2010,2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -86,7 +86,7 @@ * ************************************************************************************/ -#ifdef CONFIG_LPC31XX_EXTSDRAM +#ifdef CONFIG_LPC31_EXTSDRAM extern void lpc31_meminitialize(void); #endif diff --git a/nuttx/configs/ea3131/src/up_boot.c b/nuttx/configs/ea3131/src/up_boot.c index 94c4d8a9c..1fd9069f8 100644 --- a/nuttx/configs/ea3131/src/up_boot.c +++ b/nuttx/configs/ea3131/src/up_boot.c @@ -2,8 +2,8 @@ * configs/ea3131/src/up_boot.c * arch/arm/src/board/up_boot.c * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2009,2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -75,7 +75,7 @@ void lpc31_boardinitialize(void) { /* Initialize configured, external memory resources */ -#ifdef CONFIG_LPC31XX_EXTSDRAM +#ifdef CONFIG_LPC31_EXTSDRAM lpc31_meminitialize(); #endif @@ -83,7 +83,7 @@ void lpc31_boardinitialize(void) * lpc31_spiinitialize() has been brought into the link. */ -#if defined(CONFIG_LPC31XX_SPI) +#if defined(CONFIG_LPC31_SPI) if (lpc31_spiinitialize) { lpc31_spiinitialize(); @@ -95,7 +95,7 @@ void lpc31_boardinitialize(void) * into the build. */ -#if defined(CONFIG_USBDEV) && defined(CONFIG_LPC31XX_USB) +#if defined(CONFIG_USBDEV) && defined(CONFIG_LPC31_USB) if (lpc31_usbinitialize) { lpc31_usbinitialize(); diff --git a/nuttx/configs/ea3131/src/up_fillpage.c b/nuttx/configs/ea3131/src/up_fillpage.c index 356ea599a..9fdd80864 100644 --- a/nuttx/configs/ea3131/src/up_fillpage.c +++ b/nuttx/configs/ea3131/src/up_fillpage.c @@ -2,8 +2,8 @@ * configs/ea3131/src/up_fillpage.c * arch/arm/src/board/up_fillpage.c * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2010,2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -122,7 +122,7 @@ * is not enabled. */ -# if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31XX_MCI) +# if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31_MCI) # ifdef CONFIG_PAGING_SDSLOT # error "Mountpoints and/or MCI disabled" # endif @@ -152,7 +152,7 @@ /* Verify that SPI support is enabld */ -#ifndef CONFIG_LPC31XX_SPI +#ifndef CONFIG_LPC31_SPI # error "SPI support is not enabled" #endif diff --git a/nuttx/configs/ea3131/src/up_mem.c b/nuttx/configs/ea3131/src/up_mem.c index 1559468ac..060f58eec 100644 --- a/nuttx/configs/ea3131/src/up_mem.c +++ b/nuttx/configs/ea3131/src/up_mem.c @@ -2,8 +2,8 @@ * configs/ea3131/src/up_mem.c * arch/arm/src/board/up_mem.c * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2009-2010,2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt * * References: * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 @@ -59,7 +59,7 @@ #include "lpc31_mpmc.h" #include "ea3131_internal.h" -#ifdef CONFIG_LPC31XX_EXTSDRAM +#ifdef CONFIG_LPC31_EXTSDRAM /**************************************************************************** * Pre-processor Definitions @@ -164,8 +164,8 @@ static void lpc31_sdraminitialize(void) * replaced with an apriori value. */ -#ifdef CONFIG_LPC31XX_SDRAMHCLK -# define HCLK CONFIG_LPC31XX_SDRAMHCLK +#ifdef CONFIG_LPC31_SDRAMHCLK +# define HCLK CONFIG_LPC31_SDRAMHCLK #else uint32_t hclk = lpc31_clkfreq(CLKID_MPMCCFGCLK2, DOMAINID_SYS); # define HCLK hclk @@ -356,4 +356,4 @@ void lpc31_meminitialize(void) lpc31_sdraminitialize(); } -#endif /* CONFIG_LPC31XX_EXTSDRAM */ +#endif /* CONFIG_LPC31_EXTSDRAM */ diff --git a/nuttx/configs/ea3131/src/up_nsh.c b/nuttx/configs/ea3131/src/up_nsh.c index c8dbf017b..01b16194b 100644 --- a/nuttx/configs/ea3131/src/up_nsh.c +++ b/nuttx/configs/ea3131/src/up_nsh.c @@ -2,8 +2,8 @@ * config/ea3131/src/up_nsh.c * arch/arm/src/board/up_nsh.c * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -45,7 +45,7 @@ #include #include -#ifdef CONFIG_LPC31XX_MCI +#ifdef CONFIG_LPC31_MCI # include # include #endif @@ -88,7 +88,7 @@ * is not enabled. */ -#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31XX_MCI) +#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31_MCI) # undef CONFIG_NSH_HAVEMMCSD #endif diff --git a/nuttx/configs/ea3131/src/up_spi.c b/nuttx/configs/ea3131/src/up_spi.c index 7755e55b4..18000d6b4 100644 --- a/nuttx/configs/ea3131/src/up_spi.c +++ b/nuttx/configs/ea3131/src/up_spi.c @@ -2,8 +2,8 @@ * configs/ea3131/src/up_spi.c * arch/arm/src/board/up_spi.c * - * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -52,7 +52,7 @@ #include "lpc31_internal.h" #include "ea3131_internal.h" -#ifdef CONFIG_LPC31XX_SPI +#ifdef CONFIG_LPC31_SPI #if 0 /* At present, EA3131 specific logic is hard-coded in the file lpc31_spi.c * in arch/arm/src/lpc31xx */ @@ -138,5 +138,5 @@ uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) } #endif /* 0 */ -#endif /* CONFIG_LPC31XX_SPI */ +#endif /* CONFIG_LPC31_SPI */ diff --git a/nuttx/configs/ea3131/usbserial/Make.defs b/nuttx/configs/ea3131/usbserial/Make.defs index 17c111af2..92a53d1da 100644 --- a/nuttx/configs/ea3131/usbserial/Make.defs +++ b/nuttx/configs/ea3131/usbserial/Make.defs @@ -1,8 +1,8 @@ ############################################################################ # configs/ea3131/usbserial/Make.defs # -# Copyright (C) 2010 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Copyright (C) 2010,2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -38,23 +38,23 @@ include ${TOPDIR}/tools/Config.mk # Setup for the selected toolchain -ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) +ifeq ($(CONFIG_LPC31_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -67,13 +67,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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}" else # Linux/Cygwin-native toolchain MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include 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 CC = $(CROSSDEV)gcc @@ -122,7 +122,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifneq ($(CONFIG_LPC31_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/usbserial/ld.script b/nuttx/configs/ea3131/usbserial/ld.script deleted file mode 100644 index 380051e28..000000000 --- a/nuttx/configs/ea3131/usbserial/ld.script +++ /dev/null @@ -1,108 +0,0 @@ -/**************************************************************************** - * configs/ea3131/usbserial/ld.script - * - * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC31xx boot ROM expects the boot image be compiled with entry point at - * 0x1102:9000. A 128b header will appear at this address (applied by - * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. - */ - -MEMORY -{ - isram (rwx) : ORIGIN = 0x11029080, LENGTH = 192K - 4224 -} - -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(.); - } > isram - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > isram - - .ARM.extab : { - *(.ARM.extab*) - } >isram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > isram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > isram - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_info 0 : { *(.debug_info) } - .debug_line 0 : { *(.debug_line) } - .debug_pubnames 0 : { *(.debug_pubnames) } - .debug_aranges 0 : { *(.debug_aranges) } -} diff --git a/nuttx/configs/ea3131/usbserial/setenv.sh b/nuttx/configs/ea3131/usbserial/setenv.sh index 3adbc484c..d48e40756 100755 --- a/nuttx/configs/ea3131/usbserial/setenv.sh +++ b/nuttx/configs/ea3131/usbserial/setenv.sh @@ -32,16 +32,35 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG=${PATH}; fi - WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" -export LPCTOOL_DIR="${WD}/configs/ea3131/tools" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# This the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# This is the path to the tools subdirectory + +export LPCTOOL_DIR="${WD}/configs/ea3152/tools" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/ea3131/usbstorage/Make.defs b/nuttx/configs/ea3131/usbstorage/Make.defs index 017c9b97f..e4400e3fc 100644 --- a/nuttx/configs/ea3131/usbstorage/Make.defs +++ b/nuttx/configs/ea3131/usbstorage/Make.defs @@ -1,8 +1,8 @@ ############################################################################ # configs/ea3131/usbstorage/Make.defs # -# Copyright (C) 2010 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Copyright (C) 2010,2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -38,23 +38,23 @@ include ${TOPDIR}/tools/Config.mk # Setup for the selected toolchain -ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) +ifeq ($(CONFIG_LPC31_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -67,13 +67,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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}" else # Linux/Cygwin-native toolchain MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include 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 CC = $(CROSSDEV)gcc @@ -122,7 +122,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifneq ($(CONFIG_LPC31_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/usbstorage/ld.script b/nuttx/configs/ea3131/usbstorage/ld.script deleted file mode 100644 index 9828e5c97..000000000 --- a/nuttx/configs/ea3131/usbstorage/ld.script +++ /dev/null @@ -1,107 +0,0 @@ -/**************************************************************************** - * configs/ea3131/usbstorage/ld.script - * - * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC31xx boot ROM expects the boot image be compiled with entry point at - * 0x1102:9000. A 128b header will appear at this address (applied by - * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. - */ - -MEMORY -{ - isram (rwx) : ORIGIN = 0x11029080, LENGTH = 192K - 4224 -} - -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(.); - } > isram - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > isram - - .ARM.extab : { - *(.ARM.extab*) - } >isram - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > isram - __exidx_end = ABSOLUTE(.); - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > isram - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_info 0 : { *(.debug_info) } - .debug_line 0 : { *(.debug_line) } - .debug_pubnames 0 : { *(.debug_pubnames) } - .debug_aranges 0 : { *(.debug_aranges) } -} diff --git a/nuttx/configs/ea3131/usbstorage/setenv.sh b/nuttx/configs/ea3131/usbstorage/setenv.sh index ae08707d7..2a20e7ba9 100755 --- a/nuttx/configs/ea3131/usbstorage/setenv.sh +++ b/nuttx/configs/ea3131/usbstorage/setenv.sh @@ -32,16 +32,35 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG=${PATH}; fi - WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" -export LPCTOOL_DIR="${WD}/configs/ea3131/tools" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# This the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# This is the path to the tools subdirectory + +export LPCTOOL_DIR="${WD}/configs/ea3152/tools" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/ea3152/README.txt b/nuttx/configs/ea3152/README.txt index f0450751e..44f65981e 100644 --- a/nuttx/configs/ea3152/README.txt +++ b/nuttx/configs/ea3152/README.txt @@ -42,12 +42,12 @@ GNU Toolchain Options add one of the following configuration options to your .config (or defconfig) file: - CONFIG_LPC31XX_CODESOURCERYW=y : CodeSourcery under Windows - CONFIG_LPC31XX_CODESOURCERYL=y : CodeSourcery under Linux - CONFIG_LPC31XX_DEVKITARM=y : devkitARM under Windows - CONFIG_LPC31XX_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) + CONFIG_LPC31_CODESOURCERYW=y : CodeSourcery under Windows + CONFIG_LPC31_CODESOURCERYL=y : CodeSourcery under Linux + CONFIG_LPC31_DEVKITARM=y : devkitARM under Windows + CONFIG_LPC31_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) - If you are not using CONFIG_LPC31XX_BUILDROOT, then you may also have to modify + If you are not using CONFIG_LPC31_BUILDROOT, then you may also have to modify the PATH in the setenv.h file if your make cannot find the tools. NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are @@ -355,27 +355,27 @@ ARM/EA3152-specific Configuration Options Individual subsystems can be enabled: - CONFIG_LPC31XX_MCI, CONFIG_LPC31XX_SPI, CONFIG_LPC31XX_UART + CONFIG_LPC31_MCI, CONFIG_LPC31_SPI, CONFIG_LPC31_UART External memory available on the board (see also CONFIG_MM_REGIONS) - CONFIG_LPC31XX_EXTSRAM0 - Select if external SRAM0 is present - CONFIG_LPC31XX_EXTSRAM0HEAP - Select if external SRAM0 should be + CONFIG_LPC31_EXTSRAM0 - Select if external SRAM0 is present + CONFIG_LPC31_EXTSRAM0HEAP - Select if external SRAM0 should be configured as part of the NuttX heap. - CONFIG_LPC31XX_EXTSRAM0SIZE - Size (in bytes) of the installed + CONFIG_LPC31_EXTSRAM0SIZE - Size (in bytes) of the installed external SRAM0 memory - CONFIG_LPC31XX_EXTSRAM1 - Select if external SRAM1 is present - CONFIG_LPC31XX_EXTSRAM1HEAP - Select if external SRAM1 should be + CONFIG_LPC31_EXTSRAM1 - Select if external SRAM1 is present + CONFIG_LPC31_EXTSRAM1HEAP - Select if external SRAM1 should be configured as part of the NuttX heap. - CONFIG_LPC31XX_EXTSRAM1SIZE - Size (in bytes) of the installed + CONFIG_LPC31_EXTSRAM1SIZE - Size (in bytes) of the installed external SRAM1 memory - CONFIG_LPC31XX_EXTSDRAM - Select if external SDRAM is present - CONFIG_LPC31XX_EXTSDRAMHEAP - Select if external SDRAM should be + CONFIG_LPC31_EXTSDRAM - Select if external SDRAM is present + CONFIG_LPC31_EXTSDRAMHEAP - Select if external SDRAM should be configured as part of the NuttX heap. - CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed + CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed external SDRAM memory - CONFIG_LPC31XX_EXTNAND - Select if external NAND is present - CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed + CONFIG_LPC31_EXTNAND - Select if external NAND is present + CONFIG_LPC31_EXTSDRAMSIZE - Size (in bytes) of the installed external NAND memory LPC313X specific device driver settings diff --git a/nuttx/configs/ea3152/ostest/Make.defs b/nuttx/configs/ea3152/ostest/Make.defs index 62d7bae6f..19e213b0a 100644 --- a/nuttx/configs/ea3152/ostest/Make.defs +++ b/nuttx/configs/ea3152/ostest/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # configs/ea3152/ostest/Make.defs # -# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -38,23 +38,23 @@ include ${TOPDIR}/tools/Config.mk # Setup for the selected toolchain -ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) +ifeq ($(CONFIG_LPC31_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifeq ($(CONFIG_LPC31_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -67,13 +67,13 @@ ifeq ($(WINTOOL),y) MKDEP = $(TOPDIR)/tools/mknulldeps.sh ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" 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}" else # Linux/Cygwin-native toolchain MKDEP = $(TOPDIR)/tools/mkdeps.sh ARCHINCLUDES = -I. -isystem $(TOPDIR)/include 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 CC = $(CROSSDEV)gcc @@ -122,7 +122,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) +ifneq ($(CONFIG_LPC31_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3152/ostest/ld.script b/nuttx/configs/ea3152/ostest/ld.script deleted file mode 100644 index c52988ebc..000000000 --- a/nuttx/configs/ea3152/ostest/ld.script +++ /dev/null @@ -1,107 +0,0 @@ -/**************************************************************************** - * configs/ea3152/ostest/ld.script - * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 LPC3152 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC31xx boot ROM expects the boot image be compiled with entry point at - * 0x1102:9000. A 128b header will appear at this address (applied by - * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. - */ - -MEMORY -{ - isram (rwx) : ORIGIN = 0x11029080, LENGTH = 192K - 4224 -} - -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(.); - } > isram - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > isram - - .ARM.extab : { - *(.ARM.extab*) - } >isram - - .ARM.exidx : { - __exidx_start = ABSOLUTE(.); - *(.ARM.exidx*) - __exidx_end = ABSOLUTE(.); - } > isram - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > isram - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_info 0 : { *(.debug_info) } - .debug_line 0 : { *(.debug_line) } - .debug_pubnames 0 : { *(.debug_pubnames) } - .debug_aranges 0 : { *(.debug_aranges) } -} diff --git a/nuttx/configs/ea3152/ostest/setenv.sh b/nuttx/configs/ea3152/ostest/setenv.sh index 890585f87..418f4701e 100755 --- a/nuttx/configs/ea3152/ostest/setenv.sh +++ b/nuttx/configs/ea3152/ostest/setenv.sh @@ -32,16 +32,35 @@ # POSSIBILITY OF SUCH DAMAGE. # -if [ "$(basename $0)" = "setenv.sh" ] ; then +if [ "$_" = "$0" ] ; then echo "You must source this script, not run it!" 1>&2 exit 1 fi -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG=${PATH}; fi - WD=`pwd` -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# This the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# This is the path to the tools subdirectory + export LPCTOOL_DIR="${WD}/configs/ea3152/tools" -export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" +# Add the path to the toolchain to the PATH varialble + +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/configs/ea3152/scripts/ld.script b/nuttx/configs/ea3152/scripts/ld.script new file mode 100644 index 000000000..cf5b5d519 --- /dev/null +++ b/nuttx/configs/ea3152/scripts/ld.script @@ -0,0 +1,107 @@ +/**************************************************************************** + * configs/ea3152/scripts/ld.script + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 LPC3152 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. + * LPC31xx boot ROM expects the boot image be compiled with entry point at + * 0x1102:9000. A 128b header will appear at this address (applied by + * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. + */ + +MEMORY +{ + isram (rwx) : ORIGIN = 0x11029080, LENGTH = 192K - 4224 +} + +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(.); + } > isram + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > isram + + .ARM.extab : { + *(.ARM.extab*) + } >isram + + .ARM.exidx : { + __exidx_start = ABSOLUTE(.); + *(.ARM.exidx*) + __exidx_end = ABSOLUTE(.); + } > isram + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > isram + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx/configs/ea3152/src/Makefile b/nuttx/configs/ea3152/src/Makefile index 6393f3091..91a7fe379 100644 --- a/nuttx/configs/ea3152/src/Makefile +++ b/nuttx/configs/ea3152/src/Makefile @@ -44,13 +44,13 @@ CSRCS = up_boot.c up_clkinit.c ifeq ($(CONFIG_ARCH_BUTTONS),y) CSRCS += up_buttons.c endif -ifeq ($(CONFIG_LPC31XX_EXTSDRAM),y) +ifeq ($(CONFIG_LPC31_EXTSDRAM),y) CSRCS += up_mem.c endif ifeq ($(CONFIG_ARCH_LEDS),y) CSRCS += up_leds.c endif -ifeq ($(CONFIG_LPC31XX_SPI),y) +ifeq ($(CONFIG_LPC31_SPI),y) CSRCS += up_spi.c endif ifeq ($(CONFIG_NSH_ARCHINIT),y) diff --git a/nuttx/configs/ea3152/src/ea3152_internal.h b/nuttx/configs/ea3152/src/ea3152_internal.h index 94a6e5a23..ee93c36a1 100644 --- a/nuttx/configs/ea3152/src/ea3152_internal.h +++ b/nuttx/configs/ea3152/src/ea3152_internal.h @@ -86,7 +86,7 @@ * ************************************************************************************/ -#ifdef CONFIG_LPC31XX_EXTSDRAM +#ifdef CONFIG_LPC31_EXTSDRAM extern void lpc31_meminitialize(void); #endif diff --git a/nuttx/configs/ea3152/src/up_boot.c b/nuttx/configs/ea3152/src/up_boot.c index e85cb5125..c8870cfdf 100644 --- a/nuttx/configs/ea3152/src/up_boot.c +++ b/nuttx/configs/ea3152/src/up_boot.c @@ -75,7 +75,7 @@ void lpc31_boardinitialize(void) { /* Initialize configured, external memory resources */ -#ifdef CONFIG_LPC31XX_EXTSDRAM +#ifdef CONFIG_LPC31_EXTSDRAM lpc31_meminitialize(); #endif @@ -83,7 +83,7 @@ void lpc31_boardinitialize(void) * lpc31_spiinitialize() has been brought into the link. */ -#if defined(CONFIG_LPC31XX_SPI) +#if defined(CONFIG_LPC31_SPI) if (lpc31_spiinitialize) { lpc31_spiinitialize(); @@ -95,7 +95,7 @@ void lpc31_boardinitialize(void) * into the build. */ -#if defined(CONFIG_USBDEV) && defined(CONFIG_LPC31XX_USB) +#if defined(CONFIG_USBDEV) && defined(CONFIG_LPC31_USB) if (lpc31_usbinitialize) { lpc31_usbinitialize(); diff --git a/nuttx/configs/ea3152/src/up_fillpage.c b/nuttx/configs/ea3152/src/up_fillpage.c index 019dd940c..880f70036 100644 --- a/nuttx/configs/ea3152/src/up_fillpage.c +++ b/nuttx/configs/ea3152/src/up_fillpage.c @@ -122,7 +122,7 @@ * is not enabled. */ -# if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31XX_MCI) +# if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31_MCI) # ifdef CONFIG_PAGING_SDSLOT # error "Mountpoints and/or MCI disabled" # endif @@ -152,7 +152,7 @@ /* Verify that SPI support is enabld */ -#ifndef CONFIG_LPC31XX_SPI +#ifndef CONFIG_LPC31_SPI # error "SPI support is not enabled" #endif diff --git a/nuttx/configs/ea3152/src/up_mem.c b/nuttx/configs/ea3152/src/up_mem.c index 5eae04e0f..4f6c71e87 100644 --- a/nuttx/configs/ea3152/src/up_mem.c +++ b/nuttx/configs/ea3152/src/up_mem.c @@ -59,7 +59,7 @@ #include "lpc31_mpmc.h" #include "ea3152_internal.h" -#ifdef CONFIG_LPC31XX_EXTSDRAM +#ifdef CONFIG_LPC31_EXTSDRAM /**************************************************************************** * Pre-processor Definitions @@ -164,8 +164,8 @@ static void lpc31_sdraminitialize(void) * replaced with an apriori value. */ -#ifdef CONFIG_LPC31XX_SDRAMHCLK -# define HCLK CONFIG_LPC31XX_SDRAMHCLK +#ifdef CONFIG_LPC31_SDRAMHCLK +# define HCLK CONFIG_LPC31_SDRAMHCLK #else uint32_t hclk = lpc31_clkfreq(CLKID_MPMCCFGCLK2, DOMAINID_SYS); # define HCLK hclk @@ -356,4 +356,4 @@ void lpc31_meminitialize(void) lpc31_sdraminitialize(); } -#endif /* CONFIG_LPC31XX_EXTSDRAM */ +#endif /* CONFIG_LPC31_EXTSDRAM */ diff --git a/nuttx/configs/ea3152/src/up_nsh.c b/nuttx/configs/ea3152/src/up_nsh.c index ab8f779f0..ddd0e9195 100644 --- a/nuttx/configs/ea3152/src/up_nsh.c +++ b/nuttx/configs/ea3152/src/up_nsh.c @@ -45,7 +45,7 @@ #include #include -#ifdef CONFIG_LPC31XX_MCI +#ifdef CONFIG_LPC31_MCI # include # include #endif @@ -88,7 +88,7 @@ * is not enabled. */ -#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31XX_MCI) +#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31_MCI) # undef CONFIG_NSH_HAVEMMCSD #endif diff --git a/nuttx/configs/ea3152/src/up_spi.c b/nuttx/configs/ea3152/src/up_spi.c index 7f399d9dc..2dd7b1e23 100644 --- a/nuttx/configs/ea3152/src/up_spi.c +++ b/nuttx/configs/ea3152/src/up_spi.c @@ -52,7 +52,7 @@ #include "lpc31_internal.h" #include "ea3152_internal.h" -#ifdef CONFIG_LPC31XX_SPI +#ifdef CONFIG_LPC31_SPI #if 0 /* At present, EA3152 specific logic is hard-coded in the file lpc31_spi.c * in arch/arm/src/lpc31xx */ @@ -138,5 +138,5 @@ uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) } #endif /* 0 */ -#endif /* CONFIG_LPC31XX_SPI */ +#endif /* CONFIG_LPC31_SPI */ diff --git a/nuttx/configs/stm3240g-eval/nxwm/setenv.sh b/nuttx/configs/stm3240g-eval/nxwm/setenv.sh index da7f5719f..a8ff5bb04 100755 --- a/nuttx/configs/stm3240g-eval/nxwm/setenv.sh +++ b/nuttx/configs/stm3240g-eval/nxwm/setenv.sh @@ -57,14 +57,6 @@ fi # the CodeSourcery toolchain in any other location export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" -# These are the Cygwin paths to the locations where I installed the Atollic -# toolchain under windows. You will also have to edit this if you install -# the Atollic toolchain in any other location. /usr/bin is added before -# the Atollic bin path because there is are binaries named gcc.exe and g++.exe -# at those locations as well. -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" -#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" - # This the Cygwin path to the location where I build the buildroot # toolchain. #export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -- cgit v1.2.3