ardupilot/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef-bl.dat

87 lines
1.6 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
# MCU class and specific type
MCU STM32G4xx STM32G474xx
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 32
# reserve some space for params
APP_START_OFFSET_KB 4
# assume 512k flash part
FLASH_SIZE_KB 512
# board ID for firmware load
APJ_BOARD_ID 1053
# setup build for a peripheral firmware
env AP_PERIPH 1
# debug on USART2
STDOUT_SERIAL SD2
STDOUT_BAUDRATE 57600
# crystal frequency
OSCILLATOR_HZ 16000000
define CH_CFG_ST_FREQUENCY 1000000
# order of UARTs
SERIAL_ORDER USART2
# blue LED
PC10 LED_BOOTLOADER OUTPUT HIGH
define HAL_LED_ON 0
PB15 LED_RED OUTPUT HIGH
PC6 LED_GREEN OUTPUT HIGH
# 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 FALSE
define STM32_SERIAL_USE_USART2 TRUE
define STM32_SERIAL_USE_USART3 FALSE
define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
# avoid timer and RCIN threads to save memory
define HAL_NO_TIMER_THREAD
define HAL_NO_RCIN_THREAD
define DMA_RESERVE_SIZE 0
define HAL_DISABLE_LOOP_DELAY
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB12 CAN2_RX CAN2
PB13 CAN2_TX CAN2
PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_GPS"
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
# use a smaller bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 2500
# Add CS pins to ensure they are high in bootloader
PB1 BARO_CS CS
PC4 GYRO_CS CS
PC14 ICM_CS CS