mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: Add hwdef for TrueNavPro-G4
This commit is contained in:
parent
101bc7c3a7
commit
f71fc58767
|
@ -0,0 +1,56 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32G4xx STM32G491xx
|
||||
|
||||
FLASH_RESERVE_START_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 32
|
||||
|
||||
# reserve some space for params
|
||||
APP_START_OFFSET_KB 4
|
||||
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 5301
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
define CH_CFG_ST_FREQUENCY 1000000
|
||||
|
||||
# blue LED
|
||||
PA4 LED_BOOTLOADER OUTPUT HIGH
|
||||
define HAL_LED_ON 1
|
||||
|
||||
# SWD debugging
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define HAL_USE_EMPTY_IO TRUE
|
||||
define HAL_NO_TIMER_THREAD
|
||||
define HAL_NO_RCIN_THREAD
|
||||
define DMA_RESERVE_SIZE 0
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_USE_SERIAL FALSE
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
# use a smaller bootloader timeout
|
||||
define HAL_BOOTLOADER_TIMEOUT 2500
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PA9 RM3100_CS CS
|
||||
PA10 DPS310_CS CS
|
||||
|
||||
define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavPro-G4"
|
|
@ -0,0 +1,111 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
|
||||
# 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 5301
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 15
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
define CH_CFG_ST_FREQUENCY 1000000
|
||||
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
# order of UARTs
|
||||
SERIAL_ORDER EMPTY USART2
|
||||
|
||||
# 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
|
||||
|
||||
# one SPI bus
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI CS
|
||||
PA9 RM3100_CS CS
|
||||
PA10 DPS310_CS CS
|
||||
|
||||
# GPS PPS
|
||||
PA15 GPS_PPS_IN INPUT
|
||||
|
||||
# Baro probe
|
||||
SPIDEV dps310 SPI1 DEVID3 DPS310_CS MODE3 5*MHZ 5*MHZ
|
||||
BARO DPS310 SPI:dps310
|
||||
|
||||
# Mag probe
|
||||
SPIDEV rm3100 SPI1 DEVID1 RM3100_CS MODE0 1*MHZ 1*MHZ
|
||||
COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180
|
||||
define AP_RM3100_REVERSAL_MASK 7
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define STM32_ADC_USE_ADC1 FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
define HAL_NO_GPIO_IRQ
|
||||
|
||||
# avoid RCIN thread to save memory
|
||||
define HAL_NO_RCIN_THREAD
|
||||
|
||||
define HAL_USE_RTC FALSE
|
||||
define DMA_RESERVE_SIZE 0
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DEVICE_THREAD_STACK 768
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
PA2 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
# 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
|
||||
|
||||
# GPS+MAG+BARO+LEDs
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_BARO
|
||||
define HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY 0
|
||||
define HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY 8
|
||||
define DEFAULT_NTF_LED_TYPES 455
|
||||
|
||||
# single baro
|
||||
define BARO_MAX_INSTANCES 1
|
||||
|
||||
# GPS on 1st 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
|
||||
|
||||
# PWM, WS2812 LED
|
||||
PA3 TIM2_CH4 TIM2 PWM(1)
|
||||
|
||||
DMA_NOSHARE USART2*
|
Loading…
Reference in New Issue