HAL_ChibiOS: use -O3 on boards with 2M flash

This commit is contained in:
Andrew Tridgell 2019-02-14 23:11:08 +11:00
parent b07ba37359
commit 34a7812416
4 changed files with 10 additions and 0 deletions

View File

@ -12,6 +12,9 @@ APJ_BOARD_ID 139
FLASH_SIZE_KB 2048
# with 2M flash we can afford to optimize for speed
env OPTIMIZE -O3
FLASH_RESERVE_START_KB 128
# board voltage

View File

@ -12,6 +12,9 @@ APJ_BOARD_ID 139
FLASH_SIZE_KB 2048
# with 2M flash we can afford to optimize for speed
env OPTIMIZE -O3
# bootloader takes first sector
FLASH_RESERVE_START_KB 128

View File

@ -21,6 +21,8 @@ STM32_ST_USE_TIMER 5
# flash size
FLASH_SIZE_KB 2048
env OPTIMIZE -O3
# serial port for stdout disabled, use USB console
# STDOUT_SERIAL SD7
# STDOUT_BAUDRATE 57600

View File

@ -30,6 +30,8 @@ STM32_VDD 330U
# flash size
FLASH_SIZE_KB 2048
env OPTIMIZE -O3
# order of UARTs (and USB)
UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7