mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: changed optimisation of higher end boards to -O2
-O3 does not seem to be a win, and takes up a lot more flash
This commit is contained in:
parent
0e3a27f74f
commit
e820219202
|
@ -6,7 +6,7 @@ include ../fmuv3/hwdef.dat
|
|||
|
||||
define HAL_CHIBIOS_ARCH_CUBEBLACK 1
|
||||
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
|
||||
|
|
|
@ -19,7 +19,7 @@ APJ_BOARD_ID 140
|
|||
FLASH_SIZE_KB 2048
|
||||
|
||||
# with 2M flash we can afford to optimize for speed
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
|
||||
include ../fmuv3/hwdef.dat
|
||||
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
SPIDEV icm20948_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ
|
||||
SPIDEV icm20602_ext SPI4 DEVID3 GYRO_EXT_CS MODE3 4*MHZ 8*MHZ
|
||||
|
|
|
@ -33,7 +33,8 @@ define STM32_PLLQ_VALUE 9
|
|||
APJ_BOARD_ID 120
|
||||
|
||||
# with 2M flash we can afford to optimize for speed
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# on some boards you will need to also set the various PLL values. See
|
||||
# the defaults in common/mcuconf.h, and use the define mechanism
|
||||
# explained later in this file to override values suitable for your
|
||||
|
|
|
@ -23,7 +23,7 @@ STM32_ST_USE_TIMER 5
|
|||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# serial port for stdout, disabled so console is on USB
|
||||
#STDOUT_SERIAL SD7
|
||||
|
|
|
@ -19,7 +19,7 @@ APJ_BOARD_ID 139
|
|||
FLASH_SIZE_KB 2048
|
||||
|
||||
# with 2M flash we can afford to optimize for speed
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
|
|
@ -21,7 +21,7 @@ STM32_ST_USE_TIMER 5
|
|||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# serial port for stdout disabled, use USB console
|
||||
# STDOUT_SERIAL SD7
|
||||
|
|
|
@ -30,7 +30,7 @@ STM32_VDD 330U
|
|||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 OTG2
|
||||
|
|
|
@ -23,7 +23,7 @@ STM32_VDD 330U
|
|||
FLASH_SIZE_KB 2048
|
||||
|
||||
# with 2M flash we can afford to optimize for speed
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# start on 4th sector (1st sector for bootloader, 2 for extra storage)
|
||||
FLASH_RESERVE_START_KB 96
|
||||
|
|
|
@ -62,7 +62,7 @@ STM32_ST_USE_TIMER 5
|
|||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# now define which UART is used for printf(). We rarely use printf()
|
||||
# in ChibiOS, so this is really only for debugging very early startup
|
||||
|
|
|
@ -3,6 +3,6 @@
|
|||
|
||||
include ../fmuv3/hwdef.dat
|
||||
|
||||
env OPTIMIZE -O3
|
||||
env OPTIMIZE -O2
|
||||
|
||||
define BOARD_TYPE_DEFAULT 20
|
||||
|
|
Loading…
Reference in New Issue