HAL_ChibiOS: optimize for speed on more boards

This commit is contained in:
Andrew Tridgell 2019-02-14 23:13:01 +11:00
parent 34a7812416
commit dd835f5fce
4 changed files with 8 additions and 0 deletions

View File

@ -4,6 +4,8 @@
include ../fmuv3/hwdef.dat
env OPTIMIZE -O3
# USB setup
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
USB_PRODUCT 0x1011

View File

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

View File

@ -62,6 +62,8 @@ STM32_ST_USE_TIMER 5
# flash size
FLASH_SIZE_KB 2048
env OPTIMIZE -O3
# now define which UART is used for printf(). We rarely use printf()
# in ChibiOS, so this is really only for debugging very early startup
# in drivers.

View File

@ -3,4 +3,6 @@
include ../fmuv3/hwdef.dat
env OPTIMIZE -O3
define BOARD_TYPE_DEFAULT 20