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

151 lines
3.0 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
# MCU class and specific type
MCU STM32F303 STM32F303xC
# bootloader starts firmware at 26k
FLASH_RESERVE_START_KB 26
# store parameters in pages 11 and 12
STORAGE_FLASH_PAGE 11
define HAL_STORAGE_SIZE 800
# board ID for firmware load
APJ_BOARD_ID 1016
# setup build for a peripheral firmware
env AP_PERIPH 1
# enable watchdog
# crystal frequency
OSCILLATOR_HZ 24000000
define CH_CFG_ST_FREQUENCY 100000
define CH_CFG_ST_TIMEDELTA 0
# assume the 256k flash part for now
FLASH_SIZE_KB 256
# order of UARTs
SERIAL_ORDER USART2 EMPTY EMPTY USART3
define HAL_CAN_POOL_SIZE 6000
STDOUT_SERIAL SD2
STDOUT_BAUDRATE 57600
# USART2, debug
PA2 USART2_TX USART2 SPEED_HIGH NODMA
PA3 USART2_RX USART2 SPEED_HIGH NODMA
# USART3 for GPS
PB10 USART3_TX USART3 SPEED_HIGH NODMA
PB11 USART3_RX USART3 SPEED_HIGH NODMA
# only one I2C bus in normal config, no external pullup
PA15 I2C1_SCL I2C1 PULLUP
PB7 I2C1_SDA I2C1 PULLUP
# debugger support
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# spi bus, unused
PB3 SPI1_SCK SPI1
PB4 SPI1_MISO SPI1
PB5 SPI1_MOSI SPI1
# single rm3100 mag on I2C
COMPASS RM3100 I2C:0:0x20 false ROTATION_NONE
COMPASS RM3100 I2C:0:0x21 false ROTATION_NONE
COMPASS RM3100 I2C:0:0x22 false ROTATION_NONE
COMPASS RM3100 I2C:0:0x23 false ROTATION_NONE
# single MS5611 baro on I2C
BARO MS56XX I2C:0:0x77
# analog input
# PA5 VIN5 ADC1
define HAL_USE_ADC FALSE
define STM32_ADC_USE_ADC1 FALSE
define HAL_DISABLE_ADC_DRIVER TRUE
define HAL_NO_GPIO_IRQ
define SERIAL_BUFFERS_SIZE 512
define HAL_USE_RTC FALSE
define DMA_RESERVE_SIZE 0
# 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
PROCESS_STACK 0xA00
# enable CAN support
PB8 CAN_RX CAN
PB9 CAN_TX CAN
PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL LOW
define HAL_USE_I2C TRUE
define STM32_I2C_USE_I2C1 TRUE
define HAL_UART_MIN_TX_SIZE 256
define HAL_UART_MIN_RX_SIZE 128
define HAL_UART_STACK_SIZE 0x200
# only one I2C bus
I2C_ORDER I2C1
define HAL_I2C_CLEAR_ON_TIMEOUT 0
define HAL_DEVICE_THREAD_STACK 0x200
define STORAGE_THD_WA_SIZE 512
define IO_THD_WA_SIZE 512
define AP_PARAM_MAX_EMBEDDED_PARAM 512
define HAL_I2C_INTERNAL_MASK 1
# 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
# reset for GPS
PB6 nGNSS_RESET OUTPUT HIGH GPIO(73)
# use LOG_BTN to start Mosaic logging
PA5 LOG_BTN INPUT FLOATING GPIO(74)
# a LED to flash for CAN activity
PA6 LED OUTPUT LOW
# I2C activity LED
PA7 LED_BUS_I2C OUTPUT LOW
# keep ROMFS uncompressed as we don't have enough RAM
# to uncompress the bootloader at runtime
env ROMFS_UNCOMPRESSED True
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
# septentrio on com 3
define HAL_GPS1_TYPE_DEFAULT 10
define HAL_GPS_COM_PORT_DEFAULT 3
define GPS_SBF_STREAM_NUMBER 3
define GPS_SBF_EXTRA_CONFIG "sdfa, DSK1, DeleteOldest", "sfn, DSK1, Incremental, Mosaic", "sfno, off"