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

79 lines
1.6 KiB
Plaintext
Raw Normal View History

2022-01-24 03:32:23 -04:00
# hw definition file for processing by chibios_pins.py
# 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 81
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 8000000
# assume 512k flash part
FLASH_SIZE_KB 512
STDOUT_SERIAL SD2
STDOUT_BAUDRATE 57600
# order of UARTs
SERIAL_ORDER
# use safety button to stay in bootloader
PB15 STAY_IN_BOOTLOADER INPUT PULLDOWN
define HAL_STAY_IN_BOOTLOADER_VALUE 1
PA10 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
# 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
PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.ARK_GPS"
# 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
PB0 IMU_CS CS