2021-10-11 04:32:57 -03:00
|
|
|
g# hw definition file for processing by chibios_pins.py
|
|
|
|
|
|
|
|
# MCU class and specific type
|
|
|
|
MCU STM32L431 STM32L431xx
|
|
|
|
|
|
|
|
# bootloader starts firmware at 36k + 4k (STORAGE_FLASH)
|
|
|
|
FLASH_RESERVE_START_KB 40
|
|
|
|
|
|
|
|
# store parameters in pages 18 and 19
|
2021-10-27 02:32:43 -03:00
|
|
|
STORAGE_FLASH_PAGE 18
|
2021-10-11 04:32:57 -03:00
|
|
|
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 1050
|
|
|
|
|
|
|
|
# setup build for a peripheral firmware
|
|
|
|
env AP_PERIPH 1
|
|
|
|
|
|
|
|
# enable watchdog
|
|
|
|
|
|
|
|
# crystal frequency
|
|
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
|
|
|
|
# assume the 256k flash part
|
|
|
|
FLASH_SIZE_KB 256
|
|
|
|
|
|
|
|
# order of UARTs
|
|
|
|
SERIAL_ORDER USART1 USART2
|
|
|
|
|
|
|
|
define HAL_CAN_POOL_SIZE 6000
|
|
|
|
|
|
|
|
#STDOUT_SERIAL SD1
|
|
|
|
#STDOUT_BAUDRATE 57600
|
|
|
|
|
|
|
|
# USART1 Debug
|
|
|
|
PA9 USART1_TX USART1 SPEED_HIGH
|
|
|
|
PA10 USART1_RX USART1 SPEED_HIGH
|
|
|
|
|
|
|
|
# USART2 M9N
|
|
|
|
PA2 USART2_TX USART2 SPEED_HIGH
|
|
|
|
PA3 USART2_RX USART2 SPEED_HIGH
|
|
|
|
|
|
|
|
# LEDs
|
|
|
|
PB0 LED OUTPUT LOW GPIO(1)
|
|
|
|
|
|
|
|
# a fault LED
|
|
|
|
# PB14 LED_FAULT OUTPUT LOW # red
|
|
|
|
|
|
|
|
# SPI1 bus for Baro
|
|
|
|
PA5 SPI1_SCK SPI1
|
|
|
|
PA6 SPI1_MISO SPI1
|
|
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
PA8 BARO_CS CS
|
|
|
|
|
|
|
|
SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ
|
|
|
|
BARO DPS280 SPI:dps310
|
|
|
|
|
|
|
|
#SPIDEV Invensensev2 SPI2 DEVID2 IMU_CS MODE3 2*MHZ 8*MHZ
|
|
|
|
|
|
|
|
# QMC5883L
|
|
|
|
PB6 I2C1_SCL I2C1
|
|
|
|
PB7 I2C1_SDA I2C1
|
|
|
|
|
|
|
|
I2C_ORDER I2C1
|
|
|
|
|
|
|
|
# compass
|
|
|
|
COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90
|
|
|
|
|
|
|
|
# allow for reboot command for faster development
|
|
|
|
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
|
|
|
|
|
|
|
# debugger support
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
|
|
|
|
define HAL_NO_GPIO_IRQ
|
|
|
|
define SERIAL_BUFFERS_SIZE 512
|
|
|
|
|
|
|
|
define DMA_RESERVE_SIZE 2048
|
|
|
|
|
|
|
|
|
|
|
|
# stack for fast interrupts
|
|
|
|
define PORT_INT_REQUIRED_STACK 64
|
|
|
|
|
|
|
|
# MAIN_STACK is stack for ISR handlers
|
|
|
|
MAIN_STACK 0x300
|
|
|
|
|
|
|
|
# PROCESS_STACK controls stack for main thread
|
2021-10-19 16:43:16 -03:00
|
|
|
PROCESS_STACK 0xA00
|
2021-10-11 04:32:57 -03:00
|
|
|
|
|
|
|
define HAL_DISABLE_LOOP_DELAY
|
|
|
|
|
|
|
|
# enable CAN support
|
|
|
|
PA11 CAN1_RX CAN1
|
|
|
|
PA12 CAN1_TX CAN1
|
|
|
|
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
|
|
|
|
|
|
|
CAN_ORDER 1
|
|
|
|
|
|
|
|
define HAL_USE_ADC TRUE
|
|
|
|
define STM32_ADC_USE_ADC1 TRUE
|
|
|
|
PA4 VSENSE ADC1 SCALE(2)
|
|
|
|
|
|
|
|
define HAL_GCS_ENABLED 0
|
|
|
|
define HAL_NO_MONITOR_THREAD
|
|
|
|
define HAL_NO_LOGGING
|
|
|
|
define HAL_MINIMIZE_FEATURES 0
|
|
|
|
|
|
|
|
|
|
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431"
|
|
|
|
|
|
|
|
define HAL_PERIPH_ENABLE_GPS
|
|
|
|
define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
|
|
|
|
|
|
|
define HAL_PERIPH_ENABLE_MAG
|
|
|
|
define HAL_PERIPH_ENABLE_BARO
|
|
|
|
define HAL_PERIPH_ENABLE_AIRSPEED
|
|
|
|
|
|
|
|
#BARO MS56XX SPI:ms5611
|
|
|
|
#BARO BMP388 I2C:0:0x76
|
|
|
|
|
|
|
|
# define HAL_SPI_CHECK_CLOCK_FREQ
|
|
|
|
|
|
|
|
# WS2812 LED
|
|
|
|
PA15 TIM2_CH1 TIM2 PWM(1)
|
|
|
|
PB11 TIM2_CH4 TIM2 PWM(2)
|
|
|
|
|