mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_HAL_ChibiOS: Add a new target HolybroG4 DroneCAN Airspeed
This commit is contained in:
parent
e037b0b985
commit
a3c930be7b
@ -0,0 +1,84 @@
|
|||||||
|
# hw definition file for processing by chibios_pins.py
|
||||||
|
|
||||||
|
# MCU class and specific type
|
||||||
|
MCU STM32G4xx STM32G474xx
|
||||||
|
|
||||||
|
FLASH_RESERVE_START_KB 0
|
||||||
|
FLASH_BOOTLOADER_LOAD_KB 32
|
||||||
|
|
||||||
|
# reserve some space for params
|
||||||
|
APP_START_OFFSET_KB 4
|
||||||
|
|
||||||
|
# 512k flash part
|
||||||
|
FLASH_SIZE_KB 512
|
||||||
|
|
||||||
|
# board ID for firmware load
|
||||||
|
APJ_BOARD_ID 5405
|
||||||
|
|
||||||
|
# setup build for a peripheral firmware
|
||||||
|
env AP_PERIPH 1
|
||||||
|
|
||||||
|
# debug on USART1
|
||||||
|
STDOUT_SERIAL SD1
|
||||||
|
STDOUT_BAUDRATE 57600
|
||||||
|
|
||||||
|
# crystal frequency
|
||||||
|
OSCILLATOR_HZ 16000000
|
||||||
|
|
||||||
|
define CH_CFG_ST_FREQUENCY 1000000
|
||||||
|
|
||||||
|
# order of UARTs
|
||||||
|
SERIAL_ORDER USART1
|
||||||
|
|
||||||
|
# I2C buses
|
||||||
|
I2C_ORDER I2C1
|
||||||
|
|
||||||
|
# blue LED
|
||||||
|
PB15 LED_BOOTLOADER OUTPUT HIGH
|
||||||
|
define HAL_LED_ON 0
|
||||||
|
|
||||||
|
#green LED, Power ON indicator, Low ON
|
||||||
|
PA4 LED_GREEN OUTPUT LOW
|
||||||
|
|
||||||
|
# I2C1 bus
|
||||||
|
PB7 I2C1_SDA I2C1
|
||||||
|
PA15 I2C1_SCL I2C1
|
||||||
|
|
||||||
|
# USART1
|
||||||
|
PA9 USART1_TX USART1
|
||||||
|
PA10 USART1_RX USART1
|
||||||
|
|
||||||
|
# SWD debugging
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
define HAL_USE_SERIAL TRUE
|
||||||
|
|
||||||
|
define STM32_SERIAL_USE_USART1 TRUE
|
||||||
|
define STM32_SERIAL_USE_USART2 FALSE
|
||||||
|
define STM32_SERIAL_USE_USART3 FALSE
|
||||||
|
|
||||||
|
define HAL_NO_GPIO_IRQ
|
||||||
|
define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
|
# avoid timer and RCIN threads to save memory
|
||||||
|
define HAL_NO_TIMER_THREAD
|
||||||
|
define HAL_NO_RCIN_THREAD
|
||||||
|
|
||||||
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
|
# enable CAN support
|
||||||
|
|
||||||
|
PB12 CAN2_RX CAN2
|
||||||
|
PB13 CAN2_TX CAN2
|
||||||
|
PB2 GPIO_CAN2_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
|
||||||
|
|
||||||
|
|
95
libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Airspeed/hwdef.dat
Normal file
95
libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Airspeed/hwdef.dat
Normal file
@ -0,0 +1,95 @@
|
|||||||
|
# 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 5405
|
||||||
|
|
||||||
|
# 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
|
||||||
|
|
||||||
|
# debug on USART1
|
||||||
|
STDOUT_SERIAL SD1
|
||||||
|
STDOUT_BAUDRATE 57600
|
||||||
|
|
||||||
|
# order of UARTs
|
||||||
|
SERIAL_ORDER USART1
|
||||||
|
|
||||||
|
# I2C buses
|
||||||
|
I2C_ORDER I2C1
|
||||||
|
|
||||||
|
# LEDs
|
||||||
|
# blue LED0 marked as ACT
|
||||||
|
PB15 LED OUTPUT HIGH
|
||||||
|
define HAL_LED_ON 0
|
||||||
|
|
||||||
|
#green LED, Power ON indicator, Low ON
|
||||||
|
PA4 LED_GREEN OUTPUT LOW
|
||||||
|
|
||||||
|
# USART1, debug
|
||||||
|
PA9 USART1_TX USART1
|
||||||
|
PA10 USART1_RX USART1
|
||||||
|
|
||||||
|
# I2C1 bus
|
||||||
|
PB7 I2C1_SDA I2C1
|
||||||
|
PA15 I2C1_SCL I2C1
|
||||||
|
|
||||||
|
define HAL_I2C_INTERNAL_MASK 1
|
||||||
|
|
||||||
|
# SWD debugging
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
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 DISABLE_SERIAL_ESC_COMM TRUE
|
||||||
|
|
||||||
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
|
# enable CAN support
|
||||||
|
PB12 CAN2_RX CAN2
|
||||||
|
PB13 CAN2_TX CAN2
|
||||||
|
PB2 GPIO_CAN2_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
|
||||||
|
|
||||||
|
# Airspeed
|
||||||
|
define HAL_PERIPH_ENABLE_AIRSPEED
|
||||||
|
|
||||||
|
# 10" DLVR sensor by default
|
||||||
|
define HAL_AIRSPEED_TYPE_DEFAULT 10
|
||||||
|
define AIRSPEED_MAX_SENSORS 1
|
||||||
|
|
||||||
|
# keep ROMFS uncompressed as we don't have enough RAM
|
||||||
|
# to uncompress the bootloader at runtime
|
||||||
|
env ROMFS_UNCOMPRESSED True
|
Loading…
Reference in New Issue
Block a user