mirror of https://github.com/ArduPilot/ardupilot
134 lines
2.4 KiB
Plaintext
134 lines
2.4 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# MCU class and specific type
|
|
|
|
AUTOBUILD_TARGETS None
|
|
|
|
# MCU class and specific type
|
|
MCU STM32G4xx STM32G491xx
|
|
|
|
FLASH_RESERVE_START_KB 36
|
|
|
|
STORAGE_FLASH_PAGE 16
|
|
define HAL_STORAGE_SIZE 800
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1103
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
define CH_CFG_ST_FREQUENCY 1000000
|
|
|
|
FLASH_SIZE_KB 512
|
|
|
|
# order of UARTs
|
|
SERIAL_ORDER USART2
|
|
|
|
# sensor power control
|
|
PA4 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
|
|
|
# LEDs
|
|
PA0 LED_RED OUTPUT LOW GPIO(0)
|
|
PA2 LED_GREEN OUTPUT LOW GPIO(1)
|
|
PA1 LED_BLUE OUTPUT LOW GPIO(2)
|
|
PA3 LED_SAFETY OUTPUT LOW
|
|
|
|
define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0
|
|
define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1
|
|
define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2
|
|
|
|
define HAL_GPIO_LED_ON 1
|
|
|
|
define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1
|
|
|
|
# USART2, GPS
|
|
PB3 USART2_TX USART2
|
|
PB4 USART2_RX USART2
|
|
|
|
# USART1, debug, disabled to save flash
|
|
#PB6 USART1_TX USART1
|
|
#PB7 USART1_RX USART1
|
|
|
|
# SWD debugging
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# I2C2 bus
|
|
PA8 I2C2_SDA I2C2
|
|
PA9 I2C2_SCL I2C2
|
|
|
|
define HAL_I2C_INTERNAL_MASK 1
|
|
|
|
# I2C buses
|
|
I2C_ORDER I2C2
|
|
|
|
# one SPI bus
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
# SPI CS
|
|
PB0 MAG_CS CS
|
|
|
|
# GPS PPS
|
|
PA10 GPS_PPS_IN INPUT
|
|
|
|
# SPI devices
|
|
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE3 1*MHZ 1*MHZ
|
|
|
|
# compass
|
|
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
|
|
|
|
# baro
|
|
BARO BMP388 I2C:0:0x77
|
|
|
|
define HAL_USE_ADC FALSE
|
|
define STM32_ADC_USE_ADC1 FALSE
|
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
|
|
|
define HAL_NO_GPIO_IRQ
|
|
|
|
define HAL_USE_RTC FALSE
|
|
|
|
define DMA_RESERVE_SIZE 0
|
|
|
|
# enable CAN support
|
|
PA11 CAN1_RX CAN1
|
|
PA12 CAN1_TX CAN1
|
|
PA15 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
|
|
|
define HAL_NO_MONITOR_THREAD
|
|
|
|
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
|
|
|
|
# add support for moving baseline yaw
|
|
define GPS_MOVING_BASELINE 1
|
|
|
|
# GPS+MAG+BARO+LEDs
|
|
define HAL_PERIPH_ENABLE_GPS
|
|
define HAL_PERIPH_ENABLE_MAG
|
|
define HAL_PERIPH_ENABLE_BARO
|
|
define HAL_PERIPH_ENABLE_NOTIFY
|
|
define HAL_PERIPH_ENABLE_RC_OUT
|
|
|
|
# single baro
|
|
define BARO_MAX_INSTANCES 1
|
|
|
|
# GPS on 1st port
|
|
define HAL_PERIPH_GPS_PORT_DEFAULT 0
|
|
|
|
# keep ROMFS uncompressed as we don't have enough RAM
|
|
# to uncompress the bootloader at runtime
|
|
env ROMFS_UNCOMPRESSED True
|