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

90 lines
1.7 KiB
Plaintext
Raw Normal View History

2020-05-20 18:59:29 -03:00
# Hitec Mosaic GPS
# MCU class and specific type
MCU STM32F303 STM32F303xC
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 26
# board ID for firmware load
APJ_BOARD_ID 1016
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 24000000
define CH_CFG_ST_FREQUENCY 1000
# assume 256k flash part
FLASH_SIZE_KB 256
# order of UARTs
SERIAL_ORDER
define HAL_USE_UART FALSE
PA6 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 1
STDOUT_SERIAL SD2
STDOUT_BAUDRATE 57600
# USART2, debug
PA2 USART2_TX USART2 SPEED_HIGH NODMA
PA3 USART2_RX USART2 SPEED_HIGH NODMA
# USART3, GPS
PB10 USART3_TX USART3 SPEED_HIGH NODMA
PB11 USART3_RX USART3 SPEED_HIGH NODMA
define HAL_USE_SERIAL TRUE
define STM32_SERIAL_USE_USART1 FALSE
define STM32_SERIAL_USE_USART2 TRUE
define STM32_SERIAL_USE_USART3 TRUE
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
2020-05-20 18:59:29 -03:00
define HAL_NO_GPIO_IRQ
define CH_CFG_ST_TIMEDELTA 0
#define CH_CFG_USE_DYNAMIC FALSE
define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
# avoid timer and RCIN threads to save memory
define HAL_NO_TIMER_THREAD
define HAL_NO_RCIN_THREAD
define DMA_RESERVE_SIZE 0
MAIN_STACK 0x800
PROCESS_STACK 0x800
define HAL_DISABLE_LOOP_DELAY
# enable CAN support
PB8 CAN_RX CAN
PB9 CAN_TX CAN
PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL LOW GPIO(72)
# reset for GPS
PB6 nGNSS_RESET OUTPUT HIGH GPIO(73)
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000
# use LOG_BTN as stay in bootloader, it is active low
PA5 STAY_IN_BOOTLOADER INPUT PULLUP
define HAL_STAY_IN_BOOTLOADER_VALUE 0
# Add CS pins to ensure they are high in bootloader
PB1 MAG_CS CS