2022-03-08 04:08:38 -04:00
|
|
|
# hw definition file for processing by chibios_pins.py
|
|
|
|
|
|
|
|
# Sierra-F9P Firmware
|
|
|
|
|
|
|
|
# MCU class and specific type
|
|
|
|
MCU STM32F4xx STM32F412Rx
|
|
|
|
|
|
|
|
# bootloader starts firmware at 64k
|
|
|
|
FLASH_RESERVE_START_KB 64
|
|
|
|
|
|
|
|
# store parameters in pages 2 and 3
|
|
|
|
STORAGE_FLASH_PAGE 2
|
|
|
|
define HAL_STORAGE_SIZE 8192
|
|
|
|
|
|
|
|
# board ID for firmware load
|
|
|
|
APJ_BOARD_ID 1034
|
|
|
|
|
|
|
|
# setup build for a peripheral firmware
|
|
|
|
env AP_PERIPH 1
|
|
|
|
|
|
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
|
|
|
|
# enable watchdog
|
|
|
|
define HAL_WATCHDOG_ENABLED_DEFAULT true
|
|
|
|
|
|
|
|
# crystal frequency
|
|
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
|
|
|
|
define CH_CFG_ST_FREQUENCY 1000000
|
|
|
|
|
|
|
|
# Available Flash
|
|
|
|
FLASH_SIZE_KB 1024
|
|
|
|
|
|
|
|
STDOUT_SERIAL SD1
|
|
|
|
STDOUT_BAUDRATE 57600
|
|
|
|
|
|
|
|
# order of UARTs
|
|
|
|
SERIAL_ORDER USART1 EMPTY EMPTY USART2
|
|
|
|
|
|
|
|
# USART1 for debug
|
|
|
|
PA9 USART1_TX USART1 NODMA
|
|
|
|
PA10 USART1_RX USART1 NODMA
|
2023-05-03 21:30:51 -03:00
|
|
|
define DEFAULT_SERIAL0_BAUD 57600
|
2022-03-08 04:08:38 -04:00
|
|
|
|
|
|
|
# USART2 for GPS
|
|
|
|
PA2 USART2_TX USART2 SPEED_HIGH
|
|
|
|
PA3 USART2_RX USART2 SPEED_HIGH
|
|
|
|
|
|
|
|
# SWD debugging
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
|
|
|
|
# only one I2C bus in normal config
|
|
|
|
PB7 I2C1_SDA I2C1
|
|
|
|
PB6 I2C1_SCL I2C1
|
|
|
|
|
|
|
|
define HAL_USE_I2C TRUE
|
|
|
|
define STM32_I2C_USE_I2C1 TRUE
|
|
|
|
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
|
|
|
define HAL_I2C_INTERNAL_MASK 0
|
|
|
|
|
|
|
|
# only one I2C bus
|
|
|
|
I2C_ORDER I2C1
|
|
|
|
|
|
|
|
# only one SPI bus in normal config
|
|
|
|
PA5 SPI1_SCK SPI1
|
|
|
|
PA6 SPI1_MISO SPI1
|
|
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
|
|
|
|
# SPI CS
|
|
|
|
#PC6 ICM_CS CS
|
|
|
|
PC12 BARO_CS CS
|
|
|
|
|
|
|
|
# SPI devices
|
|
|
|
# ToDo SPI devices
|
|
|
|
#SPIDEV icm20948 SPI1 DEVID1 MPU_CS MODE3 4*MHZ 8*MHZ
|
|
|
|
SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ
|
|
|
|
|
|
|
|
# Compass
|
|
|
|
COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90
|
|
|
|
|
|
|
|
# Baro
|
|
|
|
BARO DPS310 SPI:dps310
|
|
|
|
|
|
|
|
# PWM output for buzzer
|
|
|
|
PB5 TIM3_CH2 TIM3 GPIO(77) LOW ALARM
|
|
|
|
|
|
|
|
# WS2812 LEDs
|
|
|
|
PA15 TIM2_CH1 TIM2 PWM(1)
|
|
|
|
|
|
|
|
define HAL_USE_ADC TRUE
|
|
|
|
define STM32_ADC_USE_ADC1 TRUE
|
|
|
|
#define HAL_DISABLE_ADC_DRIVER TRUE
|
|
|
|
PA0 VSENSE ADC1 SCALE(2)
|
|
|
|
|
|
|
|
define HAL_NO_GPIO_IRQ
|
|
|
|
|
|
|
|
# avoid RCIN thread to save memory
|
|
|
|
define HAL_USE_RTC TRUE
|
|
|
|
define DMA_RESERVE_SIZE 0
|
|
|
|
|
|
|
|
# enable CAN support
|
|
|
|
PB8 CAN1_RX CAN1
|
|
|
|
PB9 CAN1_TX CAN1
|
|
|
|
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
|
|
|
|
|
|
|
define HAL_DEVICE_THREAD_STACK 768
|
|
|
|
|
|
|
|
# we setup a small defaults.parm
|
|
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
|
|
|
|
|
|
|
# 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
|
|
|
|
|
|
|
|
# GPS+MAG+BARO+Buzzer+NeoPixels
|
|
|
|
define HAL_PERIPH_ENABLE_GPS
|
|
|
|
define HAL_PERIPH_ENABLE_MAG
|
|
|
|
define HAL_PERIPH_ENABLE_BARO
|
|
|
|
define HAL_PERIPH_ENABLE_RC_OUT
|
|
|
|
define HAL_PERIPH_ENABLE_NOTIFY
|
|
|
|
define CONFIGURE_PPS_PIN TRUE
|
|
|
|
define GPS_MOVING_BASELINE 1
|
|
|
|
|
|
|
|
# Logging
|
|
|
|
define HAL_LOGGING_ENABLED 1
|
2023-10-08 00:27:07 -03:00
|
|
|
define HAL_PERIPH_ENABLE_RTC 1
|
2022-03-08 04:08:38 -04:00
|
|
|
define HAL_OS_FATFS_IO 1
|
|
|
|
|
|
|
|
# SD Card pins
|
|
|
|
PC8 SDIO_D0 SDIO
|
|
|
|
PC9 SDIO_D1 SDIO
|
|
|
|
PC10 SDIO_D2 SDIO
|
|
|
|
PC11 SDIO_D3 SDIO
|
|
|
|
PB15 SDIO_CK SDIO
|
|
|
|
PD2 SDIO_CMD SDIO
|
|
|
|
|
|
|
|
# reserve 256 bytes for comms between app and bootloader
|
|
|
|
RAM_RESERVE_START 256
|
|
|
|
|
|
|
|
# allow for reboot command for faster development
|
|
|
|
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
|
|
|
|
|
|
|
#Sensors Enable & ESP Enable
|
|
|
|
PB0 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
|
|
|
PC2 ESP_PWR_EN OUTPUT LOW
|
2023-08-10 05:56:59 -03:00
|
|
|
|
|
|
|
# bootloader embedding / bootloader flashing not available
|
|
|
|
define AP_BOOTLOADER_FLASHING_ENABLED 0
|