ardupilot/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef-bl.dat

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

76 lines
1.5 KiB
Plaintext
Raw Normal View History

2022-03-08 04:08:38 -04:00
# hw definition file for processing by chibios_pins.py
# Sierra-F9P bootloader
# MCU class and specific type
MCU STM32F4xx STM32F412Rx
FLASH_RESERVE_START_KB 0
# two sectors for bootloader, two for storage
FLASH_BOOTLOADER_LOAD_KB 64
# board ID for firmware load
APJ_BOARD_ID 1034
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 16000000
define CH_CFG_ST_FREQUENCY 1000000
# Available Flash
FLASH_SIZE_KB 1024
define HAL_STORAGE_SIZE 16384
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
# order of UARTs
SERIAL_ORDER
# USART1
PA9 USART1_TX USART1
PA10 USART1_RX USART1
# USART2
PA2 USART2_TX USART2
PA3 USART2_RX USART2
# SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_SERIAL TRUE
define STM32_SERIAL_USE_USART1 TRUE
define STM32_SERIAL_USE_USART2 TRUE
define STM32_SERIAL_USE_USART3 FALSE
define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
define DMA_RESERVE_SIZE 0
define HAL_DISABLE_LOOP_DELAY
# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000
# Add CS pins to ensure they are high in bootloader
#PC6 ICM_CS CS
PC12 BARO_CS CS
#Sensors Enable & ESP Enable
PB0 VDD_3V3_SENSORS_EN OUTPUT HIGH
PC2 ESP_PWR_EN OUTPUT LOW