hwdef: disable HAL_USE_CAN on all boards except f103-periph

setting HAL_USE_CAN uses the ChibiOS CAN driver instead of the AP_HAL
CAN driver. This is only used on the f103-periph as it significantly
reduces the size of the bootloader, which allows for f103 builds to
fit in the limited flash

on all other builds we are much better off using the HAL CAN driver as
it is much faster
This commit is contained in:
Andrew Tridgell 2023-09-02 08:43:13 +10:00
parent fbd44dddd0
commit fb5dba9d86
13 changed files with 0 additions and 33 deletions

View File

@ -63,9 +63,6 @@ PA12 CAN1_TX CAN1
PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.ARK_GPS" define CAN_APP_NODE_NAME "org.ardupilot.ARK_GPS"
# make bl baudrate match debug baudrate for easier debugging # make bl baudrate match debug baudrate for easier debugging

View File

@ -63,9 +63,6 @@ PA12 CAN1_TX CAN1
PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.ARK_RTK_GPS" define CAN_APP_NODE_NAME "org.ardupilot.ARK_RTK_GPS"
# make bl baudrate match debug baudrate for easier debugging # make bl baudrate match debug baudrate for easier debugging

View File

@ -66,8 +66,6 @@ define HAL_DISABLE_LOOP_DELAY
PB8 CAN1_RX CAN1 PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1 PB9 CAN1_TX CAN1
PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.birdcandy" define CAN_APP_NODE_NAME "org.ardupilot.birdcandy"

View File

@ -66,8 +66,6 @@ define HAL_DISABLE_LOOP_DELAY
# enable CAN support # enable CAN support
PB8 CAN1_RX CAN1 PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1 PB9 CAN1_TX CAN1
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.C-RTK2-HP" define CAN_APP_NODE_NAME "org.ardupilot.C-RTK2-HP"

View File

@ -68,8 +68,6 @@ define HAL_DISABLE_LOOP_DELAY
PB8 CAN1_RX CAN1 PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1 PB9 CAN1_TX CAN1
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps" define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"

View File

@ -63,9 +63,6 @@ define HAL_DISABLE_LOOP_DELAY
PB8 CAN1_RX CAN1 PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1 PB9 CAN1_TX CAN1
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK" define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
# make bl baudrate match debug baudrate for easier debugging # make bl baudrate match debug baudrate for easier debugging

View File

@ -73,9 +73,6 @@ PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL LOW GPIO(72)
# reset for GPS # reset for GPS
PB6 nGNSS_RESET OUTPUT HIGH GPIO(73) PB6 nGNSS_RESET OUTPUT HIGH GPIO(73)
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# make bl baudrate match debug baudrate for easier debugging # make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600 define BOOTLOADER_BAUDRATE 57600

View File

@ -50,9 +50,6 @@ PA14 JTCK-SWCLK SWD
PA11 CAN1_RX CAN1 PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1 PA12 CAN1_TX CAN1
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F405" define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F405"
# use DNA # use DNA

View File

@ -47,9 +47,6 @@ PA14 JTCK-SWCLK SWD
PA11 CAN1_RX CAN1 PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1 PA12 CAN1_TX CAN1
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F412" define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F412"
# use DNA # use DNA

View File

@ -59,8 +59,6 @@ define HAL_DISABLE_LOOP_DELAY
PB8 CAN1_RX CAN1 PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1 PB9 CAN1_TX CAN1
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P" define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P"

View File

@ -69,8 +69,6 @@ define HAL_DISABLE_LOOP_DELAY
# enable CAN support # enable CAN support
PA11 CAN_RX CAN PA11 CAN_RX CAN
PA12 CAN_TX CAN PA12 CAN_TX CAN
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# make bl baudrate match debug baudrate for easier debugging # make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600 define BOOTLOADER_BAUDRATE 57600

View File

@ -64,8 +64,6 @@ define HAL_DISABLE_LOOP_DELAY
# enable CAN support # enable CAN support
PA11 CAN_RX CAN PA11 CAN_RX CAN
PA12 CAN_TX CAN PA12 CAN_TX CAN
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# debugger support # debugger support
PA13 JTMS-SWDIO SWD PA13 JTMS-SWDIO SWD

View File

@ -45,9 +45,6 @@ PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1 PB9 CAN1_TX CAN1
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.f405_MatekGPS" define CAN_APP_NODE_NAME "org.ardupilot.f405_MatekGPS"