mirror of https://github.com/ArduPilot/ardupilot
157 lines
3.1 KiB
Plaintext
157 lines
3.1 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# MCU class and specific type
|
|
|
|
# MCU class and specific type
|
|
MCU STM32G4xx STM32G474xx
|
|
|
|
FLASH_RESERVE_START_KB 36
|
|
|
|
STORAGE_FLASH_PAGE 16
|
|
define HAL_STORAGE_SIZE 800
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1053
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
define CH_CFG_ST_FREQUENCY 1000000
|
|
|
|
# assume 512k flash part
|
|
FLASH_SIZE_KB 512
|
|
|
|
# ensure NRST_MODE is set to "Reset input only". This fixes
|
|
# an issue with resetting the CAN node and firmware update
|
|
define HAL_FLASH_SET_NRST_MODE 0x01
|
|
|
|
# debug on USART2
|
|
STDOUT_SERIAL SD2
|
|
STDOUT_BAUDRATE 57600
|
|
|
|
# order of UARTs
|
|
SERIAL_ORDER USART2 USART3
|
|
|
|
# sensor power control
|
|
PC11 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
|
|
|
# LEDs
|
|
PC10 LED OUTPUT HIGH GPIO(2) # blue
|
|
PB15 LED_R OUTPUT HIGH GPIO(0)
|
|
PC6 LED_G OUTPUT HIGH GPIO(1)
|
|
|
|
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 AP_NOTIFY_GPIO_LED_RGB_ENABLED 1
|
|
|
|
# USART3, GPS
|
|
PB10 USART3_TX USART3
|
|
PB11 USART3_RX USART3
|
|
|
|
# USART2, debug
|
|
PA2 USART2_TX USART2 NODMA
|
|
PA3 USART2_RX USART2 NODMA
|
|
|
|
# SWD debugging
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# I2C1 bus
|
|
PB7 I2C1_SDA I2C1
|
|
PB8 I2C1_SCL I2C1
|
|
|
|
# I2C2 bus (LED Driver)
|
|
PA8 I2C2_SDA I2C2
|
|
PA9 I2C2_SCL I2C2
|
|
|
|
define HAL_I2C_INTERNAL_MASK 3
|
|
|
|
# I2C buses
|
|
I2C_ORDER I2C1 I2C2
|
|
|
|
# one SPI bus (for IMU, unused)
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
# SPI CS
|
|
PC4 GYR_CS CS
|
|
PB1 ACC_CS CS
|
|
PC14 ICM_CS CS
|
|
|
|
# GPS PPS
|
|
PA15 GPS_PPS_IN INPUT
|
|
|
|
# compass bmm150 on can-M8N and can-F9P-v1
|
|
COMPASS BMM150 I2C:0:0x10 false ROTATION_YAW_90
|
|
|
|
# compass ist8310 on can-M9N
|
|
COMPASS IST8310 I2C:0:0x0E false ROTATION_NONE
|
|
|
|
# compass RM3100 on can-F9P-v2
|
|
COMPASS RM3100 I2C:0:0x20 false ROTATION_NONE
|
|
|
|
# baro, disabled by default
|
|
BARO ICP201XX I2C:0:0x64
|
|
define AP_PERIPH_BARO_ENABLE_DEFAULT 0
|
|
|
|
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
|
|
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
|
|
|
PB12 CAN2_RX CAN2
|
|
PB13 CAN2_TX CAN2
|
|
PB14 GPIO_CAN2_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
|
|
|
|
DMA_NOSHARE USART3*
|
|
|
|
# add support for moving baseline yaw
|
|
define GPS_MOVING_BASELINE 1
|
|
|
|
SPIDEV icm42688 SPI1 DEVID1 ICM_CS MODE0 24*MHZ 24*MHZ
|
|
|
|
IMU Invensensev3 SPI:icm42688 ROTATION_YAW_180
|
|
|
|
define HAL_PERIPH_ENABLE_IMU
|
|
|
|
# GPS+MAG+LEDs
|
|
define HAL_PERIPH_ENABLE_GPS
|
|
define HAL_PERIPH_ENABLE_MAG
|
|
define HAL_PERIPH_ENABLE_BARO
|
|
define HAL_PERIPH_ENABLE_IMU
|
|
define HAL_PERIPH_ENABLE_NOTIFY
|
|
define HAL_PERIPH_ENABLE_RC_OUT
|
|
|
|
# GPS on 2nd port
|
|
define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
|
|
|
# keep ROMFS uncompressed as we don't have enough RAM
|
|
# to uncompress the bootloader at runtime
|
|
env ROMFS_UNCOMPRESSED True
|