mirror of https://github.com/ArduPilot/ardupilot
74 lines
1.4 KiB
Plaintext
74 lines
1.4 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
|
|
# Sierra RM3100 & Airspeed common hwdef
|
|
|
|
# MCU class and specific type
|
|
MCU STM32L431 STM32L431xx
|
|
|
|
FLASH_RESERVE_START_KB 0
|
|
FLASH_BOOTLOADER_LOAD_KB 36
|
|
|
|
# reserve some space for params
|
|
APP_START_OFFSET_KB 4
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1050
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
# Flash available
|
|
FLASH_SIZE_KB 256
|
|
|
|
# a fault LED
|
|
PA15 LED_BOOTLOADER OUTPUT LOW # amber
|
|
define HAL_LED_ON 1
|
|
|
|
STDOUT_SERIAL SD1
|
|
STDOUT_BAUDRATE 57600
|
|
|
|
# order of UARTs
|
|
SERIAL_ORDER USART1
|
|
|
|
# USART1
|
|
PA9 USART1_TX USART1 SPEED_HIGH NODMA
|
|
PA10 USART1_RX USART1 SPEED_HIGH NODMA
|
|
|
|
define HAL_USE_SERIAL TRUE
|
|
define STM32_SERIAL_USE_USART1 TRUE
|
|
define SERIAL_BUFFERS_SIZE 32
|
|
|
|
define HAL_NO_GPIO_IRQ
|
|
define HAL_USE_EMPTY_IO TRUE
|
|
define PORT_INT_REQUIRED_STACK 64
|
|
|
|
define DMA_RESERVE_SIZE 0
|
|
|
|
MAIN_STACK 0x800
|
|
PROCESS_STACK 0x800
|
|
|
|
define HAL_DISABLE_LOOP_DELAY
|
|
|
|
# enable CAN support
|
|
PA11 CAN1_RX CAN1
|
|
PA12 CAN1_TX CAN1
|
|
CAN_ORDER 1
|
|
|
|
# debugger support
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# make bl baudrate match debug baudrate for easier debugging
|
|
define BOOTLOADER_BAUDRATE 57600
|
|
|
|
# use a small bootloader timeout
|
|
define HAL_BOOTLOADER_TIMEOUT 1000
|
|
|
|
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431"
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PB12 MAG_CS CS
|