ardupilot/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat

95 lines
1.8 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
# MCU class and specific type
MCU STM32G4xx STM32G491xx
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "io.mrobotics.mRo-M10095"
# bootloader starts firmware at 26k + 4k (STORAGE_FLASH)
FLASH_RESERVE_START_KB 30
# store parameters in pages 13 and 14
STORAGE_FLASH_PAGE 13
define HAL_STORAGE_SIZE 800
# setup build for a peripheral firmware
env AP_PERIPH 1
# enable watchdog
define HAL_WATCHDOG_ENABLED_DEFAULT true
# crystal frequency
OSCILLATOR_HZ 8000000
# assume the 512k flash part
FLASH_SIZE_KB 512
# board ID for firmware load
APJ_BOARD_ID 1041
define HAL_CAN_POOL_SIZE 6000
# LEDs
PA4 LED OUTPUT HIGH
# debugger support
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# Order of I2C buses
I2C_ORDER I2C1
# this board only has a single I2C bus so make it external
define HAL_I2C_INTERNAL_MASK 0
# Now the first I2C bus. The pin speeds are automatically setup
# correctly, but can be overridden here if needed.
PA15 I2C1_SCL I2C1
PB7 I2C1_SDA I2C1
# an I2C baro (DPS310)
BARO DPS280 I2C:0:0x77
define HAL_PERIPH_ENABLE_BARO
PA0 VSENSE50 ADC1 SCALE(3)
PA1 VSENSE3v3 ADC1 SCALE(2)
define DMA_RESERVE_SIZE 2048
define HAL_USE_ADC TRUE
define STM32_ADC_USE_ADC1 TRUE
# order of UARTs
SERIAL_ORDER USART1
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
# USART1, telemetry
PA9 USART1_TX USART1 SPEED_HIGH
PA10 USART1_RX USART1 SPEED_HIGH
# stack for fast interrupts
define PORT_INT_REQUIRED_STACK 64
define HAL_DISABLE_LOOP_DELAY
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
define HAL_NO_MONITOR_THREAD
define AP_PARAM_MAX_EMBEDDED_PARAM 512
# keep ROMFS uncompressed as we don't have enough RAM
# to uncompress the bootloader at runtime
env ROMFS_UNCOMPRESSED True
# don't share any DMA channels (there are enough for everyone)
DMA_NOSHARE *