1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 21:05:35 +03:00

Rename FLASH_SIZE to TARGET_FLASH_SIZE

This commit is contained in:
jflyper 2020-01-19 02:01:26 +09:00
parent a2aeb0cef4
commit be923434b8
15 changed files with 48 additions and 48 deletions

View file

@ -162,15 +162,15 @@ include $(ROOT)/make/mcu/$(TARGET_MCU).mk
include $(ROOT)/make/openocd.mk include $(ROOT)/make/openocd.mk
# Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already. # Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
ifeq ($(FLASH_SIZE),) ifeq ($(TARGET_FLASH_SIZE),)
ifneq ($(TARGET_FLASH),) ifneq ($(MCU_FLASH_SIZE),)
FLASH_SIZE := $(TARGET_FLASH) TARGET_FLASH_SIZE := $(MCU_FLASH_SIZE)
else else
$(error FLASH_SIZE not configured for target $(TARGET)) $(error MCU_FLASH_SIZE not configured for target $(TARGET))
endif endif
endif endif
DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) DEVICE_FLAGS := $(DEVICE_FLAGS) -DTARGET_FLASH_SIZE=$(TARGET_FLASH_SIZE)
ifneq ($(HSE_VALUE),) ifneq ($(HSE_VALUE),)
DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE) DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE)

View file

@ -11,7 +11,7 @@ LD_SCRIPT = src/main/target/SITL/pg.ld
STARTUP_SRC = STARTUP_SRC =
TARGET_FLAGS = -D$(TARGET) TARGET_FLAGS = -D$(TARGET)
TARGET_FLASH := 2048 MCU_FLASH_SIZE := 2048
ARM_SDK_PREFIX = ARM_SDK_PREFIX =

View file

@ -3,10 +3,10 @@
# #
ifeq ($(OPBL),yes) ifeq ($(OPBL),yes)
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(TARGET_FLASH_SIZE)k_opbl.ld
endif endif
TARGET_FLASH := 128 MCU_FLASH_SIZE := 128
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F1/Drivers/STM32F10x_StdPeriph_Driver STDPERIPH_DIR = $(ROOT)/lib/main/STM32F1/Drivers/STM32F10x_StdPeriph_Driver
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
EXCLUDES = stm32f10x_crc.c \ EXCLUDES = stm32f10x_crc.c \
@ -39,7 +39,7 @@ DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \
endif endif
ifeq ($(LD_SCRIPT),) ifeq ($(LD_SCRIPT),)
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(TARGET_FLASH_SIZE)k.ld
endif endif
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 ARCH_FLAGS = -mthumb -mcpu=cortex-m3

View file

@ -3,10 +3,10 @@
# #
ifeq ($(OPBL),yes) ifeq ($(OPBL),yes)
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(TARGET_FLASH_SIZE)k_opbl.ld
endif endif
TARGET_FLASH := 256 MCU_FLASH_SIZE := 256
# note that there is no hardfault debugging startup file assembly handler for other platforms # note that there is no hardfault debugging startup file assembly handler for other platforms
ifeq ($(DEBUG_HARDFAULTS),F3) ifeq ($(DEBUG_HARDFAULTS),F3)
CFLAGS += -DDEBUG_HARDFAULTS CFLAGS += -DDEBUG_HARDFAULTS
@ -58,7 +58,7 @@ VPATH := $(VPATH):$(FATFS_DIR)
endif endif
ifeq ($(LD_SCRIPT),) ifeq ($(LD_SCRIPT),)
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(TARGET_FLASH_SIZE)k.ld
endif endif
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion

View file

@ -45,12 +45,12 @@ endif
ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS))) ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
EXCLUDES += stm32f4xx_fsmc.c EXCLUDES += stm32f4xx_fsmc.c
TARGET_FLASH := 512 MCU_FLASH_SIZE := 512
else ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS))) else ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS)))
EXCLUDES += stm32f4xx_fsmc.c EXCLUDES += stm32f4xx_fsmc.c
TARGET_FLASH := 512 MCU_FLASH_SIZE := 512
else else
TARGET_FLASH := 1024 MCU_FLASH_SIZE := 1024
endif endif
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))

View file

@ -132,24 +132,24 @@ ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XI_TARGETS)))
DEVICE_FLAGS += -DSTM32F765xx DEVICE_FLAGS += -DSTM32F765xx
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f765.ld LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f765.ld
STARTUP_SRC = startup_stm32f765xx.s STARTUP_SRC = startup_stm32f765xx.s
TARGET_FLASH = 2048 MCU_FLASH_SIZE := 2048
else ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS))) else ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS)))
DEVICE_FLAGS += -DSTM32F745xx DEVICE_FLAGS += -DSTM32F745xx
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f74x.ld LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f74x.ld
STARTUP_SRC = startup_stm32f745xx.s STARTUP_SRC = startup_stm32f745xx.s
TARGET_FLASH := 1024 MCU_FLASH_SIZE := 1024
else ifeq ($(TARGET),$(filter $(TARGET),$(F7X6XG_TARGETS))) else ifeq ($(TARGET),$(filter $(TARGET),$(F7X6XG_TARGETS)))
DEVICE_FLAGS += -DSTM32F746xx DEVICE_FLAGS += -DSTM32F746xx
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f74x.ld LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f74x.ld
STARTUP_SRC = startup_stm32f746xx.s STARTUP_SRC = startup_stm32f746xx.s
TARGET_FLASH := 1024 MCU_FLASH_SIZE := 1024
else ifeq ($(TARGET),$(filter $(TARGET),$(F7X2RE_TARGETS))) else ifeq ($(TARGET),$(filter $(TARGET),$(F7X2RE_TARGETS)))
DEVICE_FLAGS += -DSTM32F722xx DEVICE_FLAGS += -DSTM32F722xx
ifndef LD_SCRIPT ifndef LD_SCRIPT
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f722.ld LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f722.ld
endif endif
STARTUP_SRC = startup_stm32f722xx.s STARTUP_SRC = startup_stm32f722xx.s
TARGET_FLASH := 512 MCU_FLASH_SIZE := 512
else else
$(error Unknown MCU for F7 target) $(error Unknown MCU for F7 target)
endif endif

View file

@ -161,14 +161,14 @@ ifeq ($(TARGET),$(filter $(TARGET),$(H743xI_TARGETS)))
DEVICE_FLAGS += -DSTM32H743xx DEVICE_FLAGS += -DSTM32H743xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_2m.ld DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_2m.ld
STARTUP_SRC = startup_stm32h743xx.s STARTUP_SRC = startup_stm32h743xx.s
TARGET_FLASH := 2048 MCU_FLASH_SIZE := 2048
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
ifeq ($(RAM_BASED),yes) ifeq ($(RAM_BASED),yes)
FIRMWARE_SIZE := 448 FIRMWARE_SIZE := 448
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware # TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
# and the maximum size of the data stored on the external storage device. # and the maximum size of the data stored on the external storage device.
TARGET_FLASH := FIRMWARE_SIZE MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_ram_based.ld DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_ram_based.ld
endif endif
@ -179,14 +179,14 @@ STARTUP_SRC = startup_stm32h743xx.s
DEFAULT_TARGET_FLASH := 128 DEFAULT_TARGET_FLASH := 128
ifeq ($(TARGET_FLASH),) ifeq ($(TARGET_FLASH),)
TARGET_FLASH := $(DEFAULT_TARGET_FLASH) MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH)
endif endif
ifeq ($(EXST),yes) ifeq ($(EXST),yes)
FIRMWARE_SIZE := 448 FIRMWARE_SIZE := 448
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware # TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
# and the maximum size of the data stored on the external storage device. # and the maximum size of the data stored on the external storage device.
TARGET_FLASH := FIRMWARE_SIZE MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_exst.ld DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_exst.ld
endif endif

View file

@ -82,7 +82,7 @@
#include "sensors/gyro.h" #include "sensors/gyro.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#if ((FLASH_SIZE > 128) && (defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6500))) #if ((TARGET_FLASH_SIZE > 128) && (defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6500)))
#define USE_GYRO_SLEW_LIMITER #define USE_GYRO_SLEW_LIMITER
#endif #endif

View file

@ -1,5 +1,5 @@
F1_TARGETS += $(TARGET) F1_TARGETS += $(TARGET)
FLASH_SIZE = 64 MCU_FLASH_SIZE = 64
TARGET_SRC = \ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu.c \

View file

@ -17,5 +17,5 @@ It is also easy to convert exisiting F1 targets to be built to run on the Nucleo
to target.h to avoid non-F1 compatible code from getting in. to target.h to avoid non-F1 compatible code from getting in.
- Add - Add
FLASH_SIZE = 1024 MCU_FLASH_SIZE = 1024
to target.mk to target.mk

View file

@ -1,6 +1,6 @@
F1_TARGETS += $(TARGET) F1_TARGETS += $(TARGET)
FEATURES = ONBOARDFLASH FEATURES = ONBOARDFLASH
FLASH_SIZE = 1024 MCU_FLASH_SIZE = 1024
TARGET_SRC = \ TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \ drivers/accgyro/accgyro_fake.c \

View file

@ -10,8 +10,8 @@ NUCLEOF303RE target for use with ST Nucleo-F303RE.
It is easy to build other targets to run on Nucleo-F303RE: It is easy to build other targets to run on Nucleo-F303RE:
1. Add FLASH_SIZE line to target.mk (This will select stm32_flash_f303_512k.ld as linker script) 1. Add MCU_FLASH_SIZE line to target.mk (This will select stm32_flash_f303_512k.ld as linker script)
FLASH_SIZE = 512 MCU_FLASH_SIZE = 512
2. Modify target.h to define extra pins used for UART5 if necessary. 2. Modify target.h to define extra pins used for UART5 if necessary.
#define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTC 0xffff

View file

@ -4,7 +4,7 @@ FEATURES = VCP SDCARD_SPI
FEATURE_CUT_LEVEL = 0 FEATURE_CUT_LEVEL = 0
FLASH_SIZE = 512 MCU_FLASH_SIZE = 512
TARGET_SRC = \ TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \ drivers/accgyro/accgyro_fake.c \

View file

@ -131,7 +131,7 @@
#undef USE_I2C #undef USE_I2C
#undef USE_SPI #undef USE_SPI
#define FLASH_SIZE 2048 #define TARGET_FLASH_SIZE 2048
#define LED_STRIP_TIMER 1 #define LED_STRIP_TIMER 1

View file

@ -199,7 +199,7 @@
#define USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol #define USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
#define USE_SERIALRX_SUMD // Graupner Hott protocol #define USE_SERIALRX_SUMD // Graupner Hott protocol
#if (FLASH_SIZE > 128) #if (TARGET_FLASH_SIZE > 128)
#define PID_PROFILE_COUNT 3 #define PID_PROFILE_COUNT 3
#define CONTROL_RATE_PROFILE_COUNT 6 #define CONTROL_RATE_PROFILE_COUNT 6
#else #else
@ -207,7 +207,7 @@
#define CONTROL_RATE_PROFILE_COUNT 3 #define CONTROL_RATE_PROFILE_COUNT 3
#endif #endif
#if (FLASH_SIZE > 64) #if (TARGET_FLASH_SIZE > 64)
#define USE_ACRO_TRAINER #define USE_ACRO_TRAINER
#define USE_BLACKBOX #define USE_BLACKBOX
#define USE_CLI_BATCH #define USE_CLI_BATCH
@ -219,7 +219,7 @@
#define USE_TELEMETRY_SMARTPORT #define USE_TELEMETRY_SMARTPORT
#endif #endif
#if (FLASH_SIZE > 128) #if (TARGET_FLASH_SIZE > 128)
#define USE_GYRO_OVERFLOW_CHECK #define USE_GYRO_OVERFLOW_CHECK
#define USE_YAW_SPIN_RECOVERY #define USE_YAW_SPIN_RECOVERY
#define USE_DSHOT_DMAR #define USE_DSHOT_DMAR
@ -227,7 +227,7 @@
#define USE_TELEMETRY_CRSF #define USE_TELEMETRY_CRSF
#define USE_TELEMETRY_SRXL #define USE_TELEMETRY_SRXL
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 12)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 12))
#define USE_CMS #define USE_CMS
#define USE_MSP_DISPLAYPORT #define USE_MSP_DISPLAYPORT
#define USE_MSP_OVER_TELEMETRY #define USE_MSP_OVER_TELEMETRY
@ -235,14 +235,14 @@
#define USE_LED_STRIP #define USE_LED_STRIP
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 11)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 11))
#define USE_VTX_COMMON #define USE_VTX_COMMON
#define USE_VTX_CONTROL #define USE_VTX_CONTROL
#define USE_VTX_SMARTAUDIO #define USE_VTX_SMARTAUDIO
#define USE_VTX_TRAMP #define USE_VTX_TRAMP
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 10)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 10))
#define USE_VIRTUAL_CURRENT_METER #define USE_VIRTUAL_CURRENT_METER
#define USE_CAMERA_CONTROL #define USE_CAMERA_CONTROL
#define USE_ESC_SENSOR #define USE_ESC_SENSOR
@ -250,39 +250,39 @@
#define USE_RCDEVICE #define USE_RCDEVICE
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 9)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 9))
#define USE_GYRO_LPF2 #define USE_GYRO_LPF2
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 8)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 8))
#define USE_LAUNCH_CONTROL #define USE_LAUNCH_CONTROL
#define USE_DYN_LPF #define USE_DYN_LPF
#define USE_D_MIN #define USE_D_MIN
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 7)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 7))
#define USE_THROTTLE_BOOST #define USE_THROTTLE_BOOST
#define USE_INTEGRATED_YAW_CONTROL #define USE_INTEGRATED_YAW_CONTROL
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 6)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 6))
#define USE_ITERM_RELAX #define USE_ITERM_RELAX
#define USE_RC_SMOOTHING_FILTER #define USE_RC_SMOOTHING_FILTER
#define USE_THRUST_LINEARIZATION #define USE_THRUST_LINEARIZATION
#define USE_TPA_MODE #define USE_TPA_MODE
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 5)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 5))
#define USE_PWM #define USE_PWM
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 4)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 4))
#define USE_HUFFMAN #define USE_HUFFMAN
#define USE_PINIO #define USE_PINIO
#define USE_PINIOBOX #define USE_PINIOBOX
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 3)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 3))
#ifdef USE_SERIALRX_SPEKTRUM #ifdef USE_SERIALRX_SPEKTRUM
#define USE_SPEKTRUM_BIND #define USE_SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND_PLUG #define USE_SPEKTRUM_BIND_PLUG
@ -296,14 +296,14 @@
#endif #endif
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 2)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 2))
#define USE_TELEMETRY_HOTT #define USE_TELEMETRY_HOTT
#define USE_TELEMETRY_LTM #define USE_TELEMETRY_LTM
#define USE_SERIALRX_SUMH // Graupner legacy protocol #define USE_SERIALRX_SUMH // Graupner legacy protocol
#define USE_SERIALRX_XBUS // JR #define USE_SERIALRX_XBUS // JR
#endif #endif
#if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 1)) #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 1))
#define USE_BOARD_INFO #define USE_BOARD_INFO
#define USE_EXTENDED_CMS_MENUS #define USE_EXTENDED_CMS_MENUS
#define USE_RTC_TIME #define USE_RTC_TIME
@ -314,9 +314,9 @@
#define USE_RX_RSSI_DBM #define USE_RX_RSSI_DBM
#endif #endif
#endif // FLASH_SIZE > 128 #endif // TARGET_FLASH_SIZE > 128
#if (FLASH_SIZE > 256) #if (TARGET_FLASH_SIZE > 256)
#define USE_AIRMODE_LPF #define USE_AIRMODE_LPF
#define USE_CANVAS #define USE_CANVAS
#define USE_DASHBOARD #define USE_DASHBOARD