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

77 lines
1.5 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
# Sierra-M9N 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 1055
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 16000000
define CH_CFG_ST_FREQUENCY 1000000
# Flash available
FLASH_SIZE_KB 1024
define HAL_STORAGE_SIZE 16384
# Enable the sensor voltage pin
PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH
# 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
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# Add CS pins to ensure they are high in bootloader
PB12 MAG_CS CS
PA8 BARO_CS CS
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
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
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000