Browse Source

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
master
Andrew Tridgell 5 years ago
parent
commit
e820219202
  1. 2
      libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat
  2. 2
      libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat
  3. 2
      libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat
  4. 3
      libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat
  5. 2
      libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat
  6. 2
      libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat
  7. 2
      libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat
  8. 2
      libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat
  9. 2
      libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat
  10. 2
      libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat
  11. 2
      libraries/AP_HAL_ChibiOS/hwdef/mRoX21/hwdef.dat

2
libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat

@ -6,7 +6,7 @@ include ../fmuv3/hwdef.dat
define HAL_CHIBIOS_ARCH_CUBEBLACK 1 define HAL_CHIBIOS_ARCH_CUBEBLACK 1
env OPTIMIZE -O3 env OPTIMIZE -O2
# USB setup # USB setup
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE

2
libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat

@ -19,7 +19,7 @@ APJ_BOARD_ID 140
FLASH_SIZE_KB 2048 FLASH_SIZE_KB 2048
# with 2M flash we can afford to optimize for speed # with 2M flash we can afford to optimize for speed
env OPTIMIZE -O3 env OPTIMIZE -O2
FLASH_RESERVE_START_KB 128 FLASH_RESERVE_START_KB 128

2
libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat

@ -5,7 +5,7 @@
include ../fmuv3/hwdef.dat include ../fmuv3/hwdef.dat
env OPTIMIZE -O3 env OPTIMIZE -O2
SPIDEV icm20948_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ 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 SPIDEV icm20602_ext SPI4 DEVID3 GYRO_EXT_CS MODE3 4*MHZ 8*MHZ

3
libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat

@ -33,7 +33,8 @@ define STM32_PLLQ_VALUE 9
APJ_BOARD_ID 120 APJ_BOARD_ID 120
# with 2M flash we can afford to optimize for speed # 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 # 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 # the defaults in common/mcuconf.h, and use the define mechanism
# explained later in this file to override values suitable for your # explained later in this file to override values suitable for your

2
libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat

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

2
libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat

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

2
libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat

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

2
libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat

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

2
libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat

@ -23,7 +23,7 @@ STM32_VDD 330U
FLASH_SIZE_KB 2048 FLASH_SIZE_KB 2048
# with 2M flash we can afford to optimize for speed # 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) # start on 4th sector (1st sector for bootloader, 2 for extra storage)
FLASH_RESERVE_START_KB 96 FLASH_RESERVE_START_KB 96

2
libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat

@ -62,7 +62,7 @@ STM32_ST_USE_TIMER 5
# flash size # flash size
FLASH_SIZE_KB 2048 FLASH_SIZE_KB 2048
env OPTIMIZE -O3 env OPTIMIZE -O2
# now define which UART is used for printf(). We rarely use printf() # 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 ChibiOS, so this is really only for debugging very early startup

2
libraries/AP_HAL_ChibiOS/hwdef/mRoX21/hwdef.dat

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

Loading…
Cancel
Save