hwdef: don't use DEFAULTGPIO in bootloaders

setting up a DEFAULTGPIO pulldown in bootloaders is a bad idea as it
overrides any hardware pullups that have been put in place as part of
a "hold in bootloader" mechanism. See discussion in #27360 for ELRS

note that this only impacts one board that I can see, the
BlitzF745AIO, due to the MCU vs DEFAULTGPIO interaction
This commit is contained in:
Andrew Tridgell 2024-06-23 12:15:26 +10:00 committed by Peter Barker
parent 9bb343938f
commit ed58758ce6
36 changed files with 31 additions and 71 deletions

View File

@ -24,8 +24,7 @@ env OPTIMIZE -Os
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 UART5 USART3
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# USB
PA11 OTG_FS_DM OTG1

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
PA10 USART1_RX USART1 HIGH PULLUP
PB11 USART3_RX USART3 HIGH PULLUP

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -3,8 +3,7 @@
# for IFLIGHT_BLITZ_F7_AIO hardware.
# thanks to betaflight for pin information
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# MCU class and specific type
MCU STM32F7xx STM32F745xx

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -1,8 +1,7 @@
# hw definition file for processing by chibios_hwdef.py
# for the BotBloxSwitch hardware
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# MCU class and specific type
MCU STM32H7xx STM32H723xx

View File

@ -1,9 +1,6 @@
# hw definition file for processing by chibios_hwdef.py
# for the CBUnmanned H743 Stamp hardware
# default to all pins low to avoid ESD issues
#DEFAULTGPIO OUTPUT LOW PULLDOWN
# MCU class and specific type
MCU STM32H7xx STM32H743xx

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -27,8 +27,7 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -42,8 +42,7 @@ SERIAL_ORDER OTG1 UART7 UART5 USART3
STDOUT_SERIAL SD3
STDOUT_BAUDRATE 921600
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# USB OTG1 SERIAL0
PA11 OTG_FS_DM OTG1

View File

@ -32,8 +32,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -34,8 +34,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -35,8 +35,7 @@ PC13 BUZZER OUTPUT LOW PULLDOWN
PC2 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 1
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Add CS pins to ensure they are high in bootloader
PE4 IMU_CS CS

View File

@ -35,8 +35,7 @@ PC13 BUZZER OUTPUT LOW PULLDOWN
PC2 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 1
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Add CS pins to ensure they are high in bootloader
PE4 IMU_CS CS

View File

@ -33,8 +33,7 @@ PE3 BUZZER OUTPUT LOW PULLDOWN
PE5 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 1
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
PC5 VTX_PWR OUTPUT HIGH

View File

@ -27,8 +27,7 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
#CS pin
PB12 AT7456E_CS CS

View File

@ -31,8 +31,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
#CS pin
PB12 AT7456E_CS CS

View File

@ -19,8 +19,7 @@ FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 128
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART1

View File

@ -19,8 +19,7 @@ FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 128
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# order of UARTs (and USB)
SERIAL_ORDER OTG1

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -29,8 +29,7 @@ env OPTIMIZE -Os
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 UART5 USART2 USART3
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# USB
PA11 OTG_FS_DM OTG1

View File

@ -29,8 +29,7 @@ env OPTIMIZE -Os
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 UART5 USART3
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# USB
PA11 OTG_FS_DM OTG1

View File

@ -24,8 +24,7 @@ env OPTIMIZE -Os
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 UART5 USART3
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# USB
PA11 OTG_FS_DM OTG1

View File

@ -53,7 +53,6 @@ QSPIDEV w25q-dtr QUADSPI1 MODE3 100*MHZ 24 1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Add CS pins to ensure they are high in bootloader
PB12 ICM20602_2_CS CS

View File

@ -56,7 +56,6 @@ OSPIDEV w25q OCTOSPI1 MODE3 130*MHZ 21 1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Add CS pins to ensure they are high in bootloader
PA15 ICM42688_CS CS

View File

@ -38,8 +38,7 @@ PE4 LED_ACTIVITY OUTPUT HIGH
define HAL_LED_ON 0
define HAL_LED_OFF 1
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Add CS pins to ensure they are high in bootloader
PC15 BMI270_CS1 CS

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -29,8 +29,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Add CS pins to ensure they are high in bootloader
PA4 MPU_CS CS
PB12 OSD_CS CS

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -10,8 +10,7 @@ OSCILLATOR_HZ 16000000
# board ID for firmware load
APJ_BOARD_ID 41775
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
FLASH_SIZE_KB 2048

View File

@ -31,8 +31,6 @@ SERIAL_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Add CS pins to ensure they are high in bootloader
PA4 MPU6000_CS CS
PB12 MAX7456_CS CS

View File

@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins

View File

@ -77,5 +77,4 @@ PC15 ICM20602_CS CS
PD7 MS5611_CS CS
PD10 FRAM_CS CS SPEED_VERYLOW
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN

View File

@ -77,5 +77,4 @@ PC15 ICM20602_CS CS
PD7 MS5611_CS CS
PD10 FRAM_CS CS SPEED_VERYLOW
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN