mirror of https://github.com/ArduPilot/ardupilot
120 lines
2.6 KiB
Plaintext
120 lines
2.6 KiB
Plaintext
# HW definition file for Sierra-TrueNavIC
|
|
|
|
# MCU class and specific type
|
|
MCU STM32L431 STM32L431xx
|
|
|
|
# bootloader starts firmware at 36k + 4k (STORAGE_FLASH)
|
|
FLASH_RESERVE_START_KB 40
|
|
FLASH_SIZE_KB 256
|
|
|
|
# store parameters in pages 18 and 19
|
|
STORAGE_FLASH_PAGE 18
|
|
define HAL_STORAGE_SIZE 800
|
|
|
|
# ChibiOS system timer
|
|
STM32_ST_USE_TIMER 15
|
|
define CH_CFG_ST_RESOLUTION 16
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 5302
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
env AP_PERIPH 1
|
|
|
|
define HAL_NO_GPIO_IRQ
|
|
define SERIAL_BUFFERS_SIZE 512
|
|
define PORT_INT_REQUIRED_STACK 64
|
|
|
|
define DMA_RESERVE_SIZE 0
|
|
|
|
# MAIN_STACK is stack for ISR handlers
|
|
MAIN_STACK 0x300
|
|
|
|
# PROCESS_STACK controls stack for main thread
|
|
PROCESS_STACK 0xA00
|
|
|
|
# save memory
|
|
define HAL_GCS_ENABLED 0
|
|
define HAL_NO_LOGGING
|
|
define HAL_USE_ADC FALSE
|
|
|
|
# we setup a small defaults.parm
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
|
|
|
# debugger support
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# --------------------- SPI1 RM3100+DPS310 -----------------------
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
PA8 BARO_CS CS
|
|
|
|
# Baro probe
|
|
SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ
|
|
BARO DPS310 SPI:dps310
|
|
|
|
# QMC5883L on I2C2
|
|
I2C_ORDER I2C2
|
|
|
|
PB13 I2C2_SCL I2C2
|
|
PB11 I2C2_SDA I2C2
|
|
|
|
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
|
define HAL_I2C_INTERNAL_MASK 1
|
|
COMPASS QMC5883L I2C:0:0xd false ROTATION_YAW_180
|
|
|
|
# ---------------------- CAN bus -------------------------
|
|
PA11 CAN1_RX CAN1
|
|
PA12 CAN1_TX CAN1
|
|
PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
|
PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
|
|
|
|
define HAL_CAN_POOL_SIZE 8000
|
|
|
|
# ---------------------- UARTs ---------------------------
|
|
SERIAL_ORDER EMPTY USART1
|
|
|
|
# USART1 for GPS
|
|
PA9 USART1_TX USART1 SPEED_HIGH
|
|
PA10 USART1_RX USART1 SPEED_HIGH
|
|
|
|
# keep ROMFS uncompressed as we don't have enough RAM
|
|
# to uncompress the bootloader at runtime
|
|
env ROMFS_UNCOMPRESSED True
|
|
|
|
# enable GPS and compass
|
|
define HAL_PERIPH_ENABLE_GPS
|
|
define GPS_MAX_RATE_MS 200
|
|
define HAL_PERIPH_ENABLE_MAG
|
|
define HAL_PERIPH_ENABLE_BARO
|
|
|
|
# disable dual GPS and GPS blending to save flash space
|
|
define GPS_MAX_RECEIVERS 1
|
|
define GPS_MAX_INSTANCES 1
|
|
define HAL_COMPASS_MAX_SENSORS 1
|
|
define BARO_MAX_INSTANCES 1
|
|
define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
|
|
|
# GPS PPS
|
|
PA15 GPS_PPS_IN INPUT
|
|
|
|
# PWM, WS2812 LED
|
|
PB10 TIM2_CH3 TIM2 PWM(1)
|
|
|
|
define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavIC"
|
|
|
|
# Enable GPS LDO
|
|
PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
|
|
|
# do direct neopixel LED output to enable the 'rainbow' effect on startup
|
|
define HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY 0
|
|
define HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY 8
|
|
define DEFAULT_NTF_LED_TYPES 455
|
|
# PA1 LED OUTPUT LOW GPIO(1)
|
|
|
|
define HAL_SERIAL_ESC_COMM_ENABLED 1
|