HAL_ChibiOS: added mRo-M10095 G491 peripheral

This commit is contained in:
Andrew Tridgell 2021-07-29 14:45:55 +10:00 committed by Peter Barker
parent adb8e1fc7e
commit 4df62ce719
2 changed files with 185 additions and 0 deletions

View File

@ -0,0 +1,76 @@
# hw definition file for processing by chibios_pins.py
# MCU class and specific type
MCU STM32G491 STM32G491xx
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 26
# reserve some space for params
APP_START_OFFSET_KB 4
# board ID for firmware load
APJ_BOARD_ID 1041
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 8000000
# assume 256k flash part
FLASH_SIZE_KB 256
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
# order of UARTs
SERIAL_ORDER USART1
# a fault LED
PA4 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 1
# USART1
PA9 USART1_TX USART1 SPEED_HIGH NODMA
PA10 USART1_RX USART1 SPEED_HIGH NODMA
define HAL_USE_SERIAL TRUE
define STM32_SERIAL_USE_USART1 TRUE
define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
define HAL_USE_RTC FALSE
define DISABLE_SERIAL_ESC_COMM TRUE
define NO_DATAFLASH TRUE
define DMA_RESERVE_SIZE 0
define PERIPH_FW TRUE
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
# debugger support
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.mRo-M10095"

View File

@ -0,0 +1,109 @@
# 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
define 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 NO_DATAFLASH TRUE
define DMA_RESERVE_SIZE 2048
define PERIPH_FW TRUE
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_GCS
define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0
define HAL_BUILD_AP_PERIPH
define AP_PARAM_MAX_EMBEDDED_PARAM 512
# use the app descriptor needed by MissionPlanner for CAN upload
env APP_DESCRIPTOR MissionPlanner
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# 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 *