From 365ffcd212b8836b7dce5ec21ea4205148bc85e5 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 4 Oct 2009 17:48:35 +0000 Subject: Started a RIDE project for STM32 git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2120 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/stm3210e-eval/README.txt | 34 +++++-- nuttx/configs/stm3210e-eval/RIDE/nuttx.ctx | 22 +++++ nuttx/configs/stm3210e-eval/RIDE/nuttx.dbi | 20 +++++ nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld | 19 ++++ nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp | 51 +++++++++++ nuttx/configs/stm3210e-eval/RIDE/nuttx.rdb | Bin 0 -> 63488 bytes nuttx/configs/stm3210e-eval/RIDE/nuttx.rprj | 4 + nuttx/configs/stm3210e-eval/ostest/Make.defs | 10 ++- nuttx/configs/stm3210e-eval/ostest/defconfig | 3 +- nuttx/configs/stm3210e-eval/ostest/ld.script | 6 +- nuttx/configs/stm3210e-eval/ostest/ld.script.dfu | 110 +++++++++++++++++++++++ nuttx/configs/stm3210e-eval/ostest/setenv.sh | 3 +- 12 files changed, 269 insertions(+), 13 deletions(-) create mode 100755 nuttx/configs/stm3210e-eval/RIDE/nuttx.ctx create mode 100755 nuttx/configs/stm3210e-eval/RIDE/nuttx.dbi create mode 100755 nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld create mode 100755 nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp create mode 100755 nuttx/configs/stm3210e-eval/RIDE/nuttx.rdb create mode 100755 nuttx/configs/stm3210e-eval/RIDE/nuttx.rprj create mode 100755 nuttx/configs/stm3210e-eval/ostest/ld.script.dfu (limited to 'nuttx/configs/stm3210e-eval') diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt index d955a7c14..0a2cc0b1a 100755 --- a/nuttx/configs/stm3210e-eval/README.txt +++ b/nuttx/configs/stm3210e-eval/README.txt @@ -7,7 +7,7 @@ Development Environment Either Linux or Cygwin on Windows can be used for the development environment. The source has been built only using the GNU toolchain (see below). Other toolchains will likely cause problems. Testing was performed using the Cygwin - environment because the Raisonance R-Link emulate and some RIDE7 development tools + environment because the Raisonance R-Link emulatator and some RIDE7 development tools were used and those tools works only under Windows. GNU Toolchain Options @@ -78,6 +78,25 @@ GNU Toolchain Options the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM path or will get the wrong version of make. +IDEs +^^^^ + + NuttX is built using command-line make. It can be used with an IDE, but some + effort will be required to create the project (There is a simple RIDE project + in the RIDE subdirectory). Here are a few tip before you start that effort: + + 1) Select the toolchain that you will be using in your .config file + 2) Start the NuttX build at least one time from the Cygwin command line + before trying to create your project. This is necessary to create + certain auto-generated files and directories that will be needed. + 3) Set up include pathes: You will need include/, arch/arm/src/stm32, + arch/arm/src/common, arch/arm/src/cortexm3, and sched/. + 4) All assembly files need to have the definition option -D __ASSEMBLY__ + on the command line. + + Startup files will probably cause you some headaches. The NuttX startup file + is arch/arm/src/stm32/stm32_vectors.S + NuttX buildroot Toolchain ^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -118,11 +137,16 @@ NuttX buildroot Toolchain DFU ^^^ - The linker files in these projects assume that you will be loading code - using STMicro built-in USB DFU loader. In this case, the code will not + The linker files in these projects can be configured to indicate that you + will be loading code using STMicro built-in USB DFU loader. You can specify + that by adding: + + CONFIG_STM32_DFU=y + + To you .config file. If CONFIG_STM32_DFU is defined, the code will not be positioned at the beginning of FLASH (0x08000000) but will be offset - to 0x08003000. If you need to change that origin, you will need to - edit the file(s) ld.script for each configuration. + to 0x08003000. If you need to change that origin for some other bootloader, + you will need to edit the file(s) ld.script.dfu for each configuration. The DFU SE PC-based software is available from the STMicro website, http://www.st.com. General usage instructions: diff --git a/nuttx/configs/stm3210e-eval/RIDE/nuttx.ctx b/nuttx/configs/stm3210e-eval/RIDE/nuttx.ctx new file mode 100755 index 000000000..a0085389f --- /dev/null +++ b/nuttx/configs/stm3210e-eval/RIDE/nuttx.ctx @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/nuttx/configs/stm3210e-eval/RIDE/nuttx.dbi b/nuttx/configs/stm3210e-eval/RIDE/nuttx.dbi new file mode 100755 index 000000000..76dbcbc6a --- /dev/null +++ b/nuttx/configs/stm3210e-eval/RIDE/nuttx.dbi @@ -0,0 +1,20 @@ +[Application] +ApplicationPath=C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\nuttx.elf +CSX=0 +HighBankAddr=400000 +BootMode=0 +Format=ELF +CodeOffset=0x0 +DataOffset=0x0 +LoaderTool=ARM +Target=ARM +DebugTool=RLINK_CORTEX +[Device] +Name=STM32F101VET6 +[ARMSigDrv options] +CXS=0 +[Debug] +Explore=No +Startup=1 +StartupSymb=main +ToolName=RLINK_CORTEX diff --git a/nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld b/nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld new file mode 100755 index 000000000..cd09bda62 --- /dev/null +++ b/nuttx/configs/stm3210e-eval/RIDE/nuttx.elf.ld @@ -0,0 +1,19 @@ + +SEARCH_DIR(".") +SEARCH_DIR("C:\Program Files\Raisonance\Ride\Lib\ARM") +STARTUP("C:\Program Files\Raisonance\Ride\lib\ARM\crt0_STM32x_HD.o") +INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\stm32_timerisr.o") +INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\stm32_vectors.o") +INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\stm32_gpio.o") +INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\stm32_irq.o") +INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\stm32_lowputc.o") +INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\stm32_rcc.o") +INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\stm32_serial.o") +INPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\stm32_start.o") +EXTERN( __io_putchar ) +EXTERN( _write ) +INPUT("STM32x_io_putchar_thumb.a") +INPUT("e_stdio_thumb.a") +INPUT("STM32F10x_thumb.lib") +OUTPUT("C:\cygwin\home\Owner\projects\nuttx\nuttx\configs\stm3210e-eval\RIDE\nuttx.elf") +INCLUDE "C:\Program Files\Raisonance\Ride\lib\ARM\STM32F101_32K_32K_FLASH.ld" diff --git a/nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp b/nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp new file mode 100755 index 000000000..e47cb3c8b --- /dev/null +++ b/nuttx/configs/stm3210e-eval/RIDE/nuttx.rapp @@ -0,0 +1,51 @@ + + + + + + + + + + + + + +
+ + +
+
+ + +
+ +
+ +
+ + +
+
+ + +
+ +
+ +
+ + +
+ +
+ +
+ + +
+ +
+
+
+
\ No newline at end of file diff --git a/nuttx/configs/stm3210e-eval/RIDE/nuttx.rdb b/nuttx/configs/stm3210e-eval/RIDE/nuttx.rdb new file mode 100755 index 000000000..ce32c4f61 Binary files /dev/null and b/nuttx/configs/stm3210e-eval/RIDE/nuttx.rdb differ diff --git a/nuttx/configs/stm3210e-eval/RIDE/nuttx.rprj b/nuttx/configs/stm3210e-eval/RIDE/nuttx.rprj new file mode 100755 index 000000000..b366ffc08 --- /dev/null +++ b/nuttx/configs/stm3210e-eval/RIDE/nuttx.rprj @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/nuttx/configs/stm3210e-eval/ostest/Make.defs b/nuttx/configs/stm3210e-eval/ostest/Make.defs index f0f3e62b7..773b3e71c 100644 --- a/nuttx/configs/stm3210e-eval/ostest/Make.defs +++ b/nuttx/configs/stm3210e-eval/ostest/Make.defs @@ -37,6 +37,12 @@ include ${TOPDIR}/.config # Setup for the selected toolchain +ifeq ($(CONFIG_STM32_DFU)y) + LDSCRIPT = ld.script.dfu +else + LDSCRIPT = ld.script +endif + ifneq ($(CONFIG_STM32_BUILDROOT),y) # Windows-native toolchains ifeq ($(CONFIG_STM32_DEVKITARM),y) @@ -51,7 +57,7 @@ endif ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft 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)/ostest/$(LDSCRIPT)}" MAXOPTIMIZATION = -O2 # The NuttX buildroot toolchain else @@ -61,7 +67,7 @@ else ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft 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)/ostest/$(LDSCRIPT) MAXOPTIMIZATION = -Os endif diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig index 0a71545ca..7c5afbdf7 100755 --- a/nuttx/configs/stm3210e-eval/ostest/defconfig +++ b/nuttx/configs/stm3210e-eval/ostest/defconfig @@ -87,11 +87,12 @@ CONFIG_ARCH_LEDS=y CONFIG_ARCH_CALIBRATION=n # -# Identify toolchain +# Identify toolchain and liner options CONFIG_STM32_CODESOURCERY=n CONFIG_STM32_DEVKITARM=n CONFIG_STM32_RAISONANCE=n CONFIG_STM32_BUILDROOT=y +CONFIG_STM32_DFU=n # # Individual subsystems can be enabled: diff --git a/nuttx/configs/stm3210e-eval/ostest/ld.script b/nuttx/configs/stm3210e-eval/ostest/ld.script index 9ae632a11..41cb64113 100755 --- a/nuttx/configs/stm3210e-eval/ostest/ld.script +++ b/nuttx/configs/stm3210e-eval/ostest/ld.script @@ -34,14 +34,12 @@ ****************************************************************************/ /* 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 - * STM3210E-EVAL's DFU bootloader is being used. In that case, the corrct - * load .text load address is 0x08003000 (leaving 464Kb). + * 64Kb of SRAM beginning at address 0x2000:0000. */ MEMORY { - flash (rx) : ORIGIN = 0x08003000, LENGTH = 464K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K } diff --git a/nuttx/configs/stm3210e-eval/ostest/ld.script.dfu b/nuttx/configs/stm3210e-eval/ostest/ld.script.dfu new file mode 100755 index 000000000..720195871 --- /dev/null +++ b/nuttx/configs/stm3210e-eval/ostest/ld.script.dfu @@ -0,0 +1,110 @@ +/**************************************************************************** + * configs/stm3210e-eval/ostest/ld.script.dfu + * + * 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 STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and + * 64Kb of SRAM beginning at address 0x2000:0000. Here we assume that the + * STM3210E-EVAL'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(.); /* See below */ + + /* The STM32F103Z has 64Kb 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 + + .ARM.exidx : { + __exidx_start = ABSOLUTE(.); + *(.ARM.exidx*) + __exidx_end = ABSOLUTE(.); + } >sram + + .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) } +} diff --git a/nuttx/configs/stm3210e-eval/ostest/setenv.sh b/nuttx/configs/stm3210e-eval/ostest/setenv.sh index e01711125..fcb428c2f 100755 --- a/nuttx/configs/stm3210e-eval/ostest/setenv.sh +++ b/nuttx/configs/stm3210e-eval/ostest/setenv.sh @@ -40,7 +40,8 @@ fi if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi WD=`pwd` +export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" +export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" -- cgit v1.2.3