summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xnuttx/arch/arm/src/stm32/Make.defs9
-rwxr-xr-xnuttx/arch/arm/src/stm32/chip.h4
-rwxr-xr-xnuttx/configs/stm3210e-eval/README.txt2
-rwxr-xr-xnuttx/configs/stm3210e-eval/ostest/defconfig11
-rwxr-xr-xnuttx/configs/stm3210e-eval/ostest/ld.script5
-rwxr-xr-xnuttx/configs/stm3210e-eval/src/up_boot.c2
-rwxr-xr-xnuttx/configs/stm3210e-eval/src/up_leds.c2
-rwxr-xr-xnuttx/configs/stm3210e-eval/src/up_spi.c2
8 files changed, 20 insertions, 17 deletions
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index ca6f54770..a62d050a2 100755
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -46,10 +46,5 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
CHIP_ASRCS =
CHIP_CSRCS = stm32_start.c
-# stm32_syscontrol.c stm32_irq.c \
-# stm32_gpio.c stm32_gpioirq.c stm32_timerisr.c stm32_lowputc.c \
-# stm32_serial.c stm32_ssi.c stm32_dumpgpio.c
-
-ifdef CONFIG_NET
-CHIP_CSRCS += stm32_ethernet.c
-endif
+# stm32_irq.c stm32_gpio.c stm32_timerisr.c stm32_lowputc.c \
+# stm32_serial.c stm32_spi.c stm32_dumpgpio.c
diff --git a/nuttx/arch/arm/src/stm32/chip.h b/nuttx/arch/arm/src/stm32/chip.h
index bedc96592..c80ea97c2 100755
--- a/nuttx/arch/arm/src/stm32/chip.h
+++ b/nuttx/arch/arm/src/stm32/chip.h
@@ -49,7 +49,7 @@
/* Get customizations for each supported chip (only the STM32F103Z right now) */
-#ifdef CONFIG_CHIP_STM32F103ZET6
+#ifdef CONFIG_ARCH_CHIP_STM32F103ZET6
# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
@@ -68,7 +68,7 @@
# define STM32_NCRC 0 /* No CRC */
# define STM32_NTHERNET 0 /* No ethernet */
#else
-# error "Unsupported STM32 chip */
+# error "Unsupported STM32 chip"
#endif
/* Include only the memory map. Other chip hardware files should then include this
diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt
index 175209b93..bb26a7440 100755
--- a/nuttx/configs/stm3210e-eval/README.txt
+++ b/nuttx/configs/stm3210e-eval/README.txt
@@ -141,7 +141,7 @@ STM3210E-EVAL-specific Configuration Options
CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
chip:
- CONFIG_ARCH_CHIP_STM32F103Z
+ CONFIG_ARCH_CHIP_STM32F103ZET6
CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
hence, the board that supports the particular chip or SoC.
diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig
index 496717411..c55c11329 100755
--- a/nuttx/configs/stm3210e-eval/ostest/defconfig
+++ b/nuttx/configs/stm3210e-eval/ostest/defconfig
@@ -71,8 +71,8 @@ CONFIG_ARCH=arm
CONFIG_ARCH_ARM=y
CONFIG_ARCH_CORTEXM3=y
CONFIG_ARCH_CHIP=stm32
-CONFIG_ARCH_CHIP_STM32F103Z=y
-CONFIG_ARCH_BOARD=stm3210e_eval
+CONFIG_ARCH_CHIP_STM32F103ZET6=y
+CONFIG_ARCH_BOARD=stm3210e-eval
CONFIG_ARCH_BOARD_STM3210E_EVAL=y
CONFIG_BOARD_LOOPSPERMSEC=4531
CONFIG_DRAM_SIZE=0x00010000
@@ -87,6 +87,13 @@ CONFIG_ARCH_LEDS=y
CONFIG_ARCH_CALIBRATION=n
#
+# Identify toolchain
+CONFIG_STM32_CODESOURCERY=n
+CONFIG_STM32_DEVKITARM=n
+CONFIG_STM32_RAISONANCE=n
+CONFIG_STM32_BUILDROOT=y
+
+#
# STM32F103Z specific serial device driver settings
#
# CONFIG_UARTn_DISABLE - select to disable all support for
diff --git a/nuttx/configs/stm3210e-eval/ostest/ld.script b/nuttx/configs/stm3210e-eval/ostest/ld.script
index 59a673c04..fd0014c20 100755
--- a/nuttx/configs/stm3210e-eval/ostest/ld.script
+++ b/nuttx/configs/stm3210e-eval/ostest/ld.script
@@ -33,11 +33,12 @@
*
****************************************************************************/
-/* The STM32F103Z has S56Kb of FLASH beginning at address 0x0000:0000 */
+/* The STM32F103ZET6 has 512Kb of FLASH beginning at address 0x0800:0000 and
+ * 64Kb of FLASH beginning at 0x2000:0000*/
MEMORY
{
- flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
+ flash (rx) : ORIGIN = 0x08000000, LENGTH = 256K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
}
diff --git a/nuttx/configs/stm3210e-eval/src/up_boot.c b/nuttx/configs/stm3210e-eval/src/up_boot.c
index 9807f5686..cfc02062d 100755
--- a/nuttx/configs/stm3210e-eval/src/up_boot.c
+++ b/nuttx/configs/stm3210e-eval/src/up_boot.c
@@ -46,7 +46,7 @@
#include <arch/board/board.h>
#include "up_arch.h"
-#include "stm3210e_internal.h"
+#include "stm3210e-internal.h"
/************************************************************************************
* Definitions
diff --git a/nuttx/configs/stm3210e-eval/src/up_leds.c b/nuttx/configs/stm3210e-eval/src/up_leds.c
index 175dfabff..c40953b41 100755
--- a/nuttx/configs/stm3210e-eval/src/up_leds.c
+++ b/nuttx/configs/stm3210e-eval/src/up_leds.c
@@ -49,7 +49,7 @@
#include "up_arch.h"
#include "up_internal.h"
#include "stm32_internal.h"
-#include "stm3210e_internal.h"
+#include "stm3210e-internal.h"
/****************************************************************************
* Definitions
diff --git a/nuttx/configs/stm3210e-eval/src/up_spi.c b/nuttx/configs/stm3210e-eval/src/up_spi.c
index 8599eff2b..852c4faec 100755
--- a/nuttx/configs/stm3210e-eval/src/up_spi.c
+++ b/nuttx/configs/stm3210e-eval/src/up_spi.c
@@ -49,7 +49,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32_internal.h"
-#include "stm3210e_internal.h"
+#include "stm3210e-internal.h"
#if !defined(CONFIG_SPI1_DISABLE) || !defined(CONFIG_SPI2_DISABLE)