-
Notifications
You must be signed in to change notification settings - Fork 17.6k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
AP_HAL_ChibiOS: hwdef: ARK_FPV board support
- Loading branch information
Showing
2 changed files
with
323 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,75 @@ | ||
# hw definition file for processing by chibios_hwdef.py | ||
# for the ARKV6X hardware | ||
|
||
# MCU class and specific type | ||
MCU STM32H7xx STM32H743xx | ||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 16000000 | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID 59 | ||
|
||
# bootloader is installed at zero offset | ||
FLASH_RESERVE_START_KB 0 | ||
|
||
# the location where the bootloader will put the firmware | ||
FLASH_BOOTLOADER_LOAD_KB 128 | ||
|
||
# flash size | ||
FLASH_SIZE_KB 2048 | ||
|
||
env OPTIMIZE -Os | ||
|
||
# order of UARTs (and USB) | ||
SERIAL_ORDER OTG1 UART7 UART5 USART3 | ||
|
||
# USB | ||
PA11 OTG_FS_DM OTG1 | ||
PA12 OTG_FS_DP OTG1 | ||
PA9 VBUS INPUT OPENDRAIN | ||
|
||
# pins for SWD debugging | ||
PA13 JTMS-SWDIO SWD | ||
PA14 JTCK-SWCLK SWD | ||
|
||
# CS pins | ||
|
||
# ICM20602 | ||
PI9 IMU1_CS CS | ||
# BMMI088 Accel | ||
PI4 BMI088_A_CS CS | ||
# BMMI088 Gyro | ||
PI8 BMI088_G_CS CS | ||
# Unused | ||
# PG7 FRAM_CS CS | ||
PI10 EXT1_CS CS | ||
|
||
# telem1 | ||
PE8 UART7_TX UART7 | ||
PF6 UART7_RX UART7 | ||
|
||
# telem2 | ||
PC12 UART5_TX UART5 | ||
PD2 UART5_RX UART5 | ||
|
||
# debug uart | ||
PD8 USART3_TX USART3 | ||
PD9 USART3_RX USART3 | ||
|
||
# armed indication | ||
PE6 nARMED OUTPUT HIGH | ||
|
||
# 12V peripheral enable | ||
PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH | ||
|
||
# LEDs | ||
PE3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red | ||
PE5 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # blue | ||
define HAL_LED_ON 0 | ||
|
||
define HAL_USE_EMPTY_STORAGE 1 | ||
define HAL_STORAGE_SIZE 16384 | ||
|
||
# enable DFU by default | ||
ENABLE_DFU_BOOT 1 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,248 @@ | ||
# hw definition file for processing by chibios_hwdef.py | ||
# for the ARKV6X hardware | ||
|
||
# MCU class and specific type | ||
MCU STM32H7xx STM32H743xx | ||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 16000000 | ||
|
||
# TODO: changing clockrate causes the build to fail | ||
# MCU_CLOCKRATE_MHZ 320 | ||
|
||
# ChibiOS system timer | ||
STM32_ST_USE_TIMER 2 | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID 59 | ||
|
||
FLASH_RESERVE_START_KB 128 | ||
|
||
# to be compatible with the px4 bootloader we need | ||
# to use a different RAM_MAP | ||
env USE_ALT_RAM_MAP 1 | ||
|
||
# flash size | ||
FLASH_SIZE_KB 2048 | ||
|
||
env OPTIMIZE -O2 | ||
|
||
SERIAL_ORDER OTG1 UART7 UART5 USART1 USART2 UART4 USART6 OTG2 | ||
|
||
# debug console | ||
STDOUT_SERIAL SD3 | ||
STDOUT_BAUDRATE 57600 | ||
|
||
# default to all pins low to avoid ESD issues | ||
DEFAULTGPIO OUTPUT LOW PULLDOWN | ||
|
||
# USB | ||
PA11 OTG_FS_DM OTG1 | ||
PA12 OTG_FS_DP OTG1 | ||
PA9 VBUS INPUT OPENDRAIN | ||
|
||
# pins for SWD debugging | ||
PA13 JTMS-SWDIO SWD | ||
PA14 JTCK-SWCLK SWD | ||
|
||
# telem1 | ||
PE8 UART7_TX UART7 | ||
PF6 UART7_RX UART7 | ||
PF8 UART7_RTS UART7 | ||
PE10 UART7_CTS UART7 | ||
|
||
# telem2 | ||
PC8 UART5_RTS UART5 | ||
PC9 UART5_CTS UART5 | ||
PC12 UART5_TX UART5 | ||
PD2 UART5_RX UART5 | ||
|
||
# telem3 | ||
PA3 USART2_RX USART2 | ||
PD5 USART2_TX USART2 | ||
PD3 USART2_CTS USART2 | ||
PD4 USART2_RTS USART2 | ||
|
||
# GPS1 | ||
PB6 USART1_TX USART1 | ||
PB7 USART1_RX USART1 | ||
|
||
# uart4 | ||
PH13 UART4_TX UART4 | ||
PH14 UART4_RX UART4 | ||
|
||
# debug uart | ||
PD8 USART3_TX USART3 | ||
PD9 USART3_RX USART3 | ||
|
||
# used for RC SBUS | ||
PC6 USART6_TX USART6 | ||
PC7 USART6_RX USART6 | ||
|
||
# ADC | ||
PA0 SCALED1_V3V3 ADC1 SCALE(2) | ||
PA4 SCALED2_V3V3 ADC1 SCALE(2) | ||
PB0 SCALED3_V3V3 ADC1 SCALE(2) | ||
|
||
PB1 VDD_5V_SENS ADC1 SCALE(2) | ||
|
||
# ESC Telem on UART4 | ||
define HAL_SERIAL_ESC_COMM_ENABLED 1 | ||
define HAL_WITH_ESC_TELEM 1 | ||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_ESCTelemetry | ||
|
||
# TODO: ESC analog current (CURR_IN) | ||
# PC2 ADC1_6V6 ADC1 SCALE(2) | ||
|
||
# SPI1 - IIM42653 | ||
PA5 SPI1_SCK SPI1 | ||
PB5 SPI1_MOSI SPI1 | ||
PG9 SPI1_MISO SPI1 | ||
PI9 IMU1_CS CS | ||
PF2 IMU1_DRDY INPUT | ||
|
||
# SPI6 - external1 | ||
PB3 SPI6_SCK SPI6 | ||
PA6 SPI6_MISO SPI6 | ||
PG14 SPI6_MOSI SPI6 | ||
PI10 EXT1_CS CS | ||
PD11 DRDY_ADIS16507 INPUT GPIO(93) | ||
|
||
# use GPIO(93) for data ready on ADIS16507 | ||
#define ADIS_DRDY_PIN 93 | ||
|
||
# PWM output pins | ||
PI0 TIM5_CH4 TIM5 PWM(1) GPIO(50) | ||
PH12 TIM5_CH3 TIM5 PWM(2) GPIO(51) | ||
PH11 TIM5_CH2 TIM5 PWM(3) GPIO(52) | ||
PH10 TIM5_CH1 TIM5 PWM(4) GPIO(53) | ||
PI5 TIM8_CH1 TIM8 PWM(5) GPIO(54) | ||
PI6 TIM8_CH2 TIM8 PWM(6) GPIO(55) | ||
PI7 TIM8_CH3 TIM8 PWM(7) GPIO(56) | ||
PI2 TIM8_CH4 TIM8 PWM(8) GPIO(57) | ||
PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58) | ||
|
||
# CAN bus | ||
PD0 CAN1_RX CAN1 | ||
PD1 CAN1_TX CAN1 | ||
|
||
# I2C buses | ||
|
||
# I2C1 (GPS1 compass, external) | ||
PB9 I2C1_SDA I2C1 | ||
PB8 I2C1_SCL I2C1 | ||
|
||
# I2C2 (BMP390 baro, internal) | ||
PF1 I2C2_SCL I2C2 | ||
PF0 I2C2_SDA I2C2 | ||
|
||
# I2C4 (IIS2MDC compass, internal) | ||
PF14 I2C4_SCL I2C4 | ||
PF15 I2C4_SDA I2C4 | ||
|
||
# order of I2C buses | ||
I2C_ORDER I2C1 I2C2 I2C4 | ||
define HAL_I2C_INTERNAL_MASK 6 | ||
|
||
# TODO: where does these GPIO numbers come from? ie, GPIO(80) | ||
PB10 HEATER_EN OUTPUT LOW GPIO(80) | ||
define HAL_HEATER_GPIO_PIN 80 | ||
|
||
# Setup the IMU heater | ||
define HAL_HAVE_IMU_HEATER 1 | ||
define HAL_IMU_TEMP_DEFAULT 45 | ||
define HAL_IMUHEAT_P_DEFAULT 50 | ||
define HAL_IMUHEAT_I_DEFAULT 0.07 | ||
# TODO: should we use this? | ||
# define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5 | ||
|
||
# armed indication | ||
PE6 nARMED OUTPUT HIGH | ||
|
||
# power enable pins | ||
PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH | ||
PI11 VDD_3V3_SENSORS1_EN OUTPUT HIGH | ||
|
||
# start peripheral power off, then enable after init | ||
# this prevents a problem with radios that use RTS for | ||
# bootloader hold | ||
PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH | ||
|
||
# power sensing | ||
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP | ||
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP | ||
|
||
PG1 VDD_BRICK_nVALID INPUT PULLUP | ||
|
||
# microSD support | ||
PD6 SDMMC2_CK SDMMC2 | ||
PD7 SDMMC2_CMD SDMMC2 | ||
PB14 SDMMC2_D0 SDMMC2 | ||
PB15 SDMMC2_D1 SDMMC2 | ||
PG11 SDMMC2_D2 SDMMC2 | ||
PB4 SDMMC2_D3 SDMMC2 | ||
define FATFS_HAL_DEVICE SDCD2 | ||
|
||
# LEDs | ||
PE3 LED_RED OUTPUT OPENDRAIN GPIO(90) HIGH | ||
PE4 LED_GREEN OUTPUT OPENDRAIN GPIO(91) HIGH | ||
PE5 LED_BLUE OUTPUT OPENDRAIN GPIO(92) HIGH | ||
|
||
# setup for "pixracer" RGB LEDs | ||
define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90 | ||
define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91 | ||
define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92 | ||
|
||
define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 | ||
|
||
# ID pins | ||
PG0 HW_VER_REV_DRIVE OUTPUT LOW | ||
# PH3 HW_VER_SENS ADC3 SCALE(1) | ||
# PH4 HW_REV_SENS ADC3 SCALE(1) | ||
|
||
# PWM output for buzzer | ||
PF9 TIM14_CH1 TIM14 GPIO(77) ALARM | ||
|
||
# barometer on i2c_2 | ||
BARO BMP388 I2C:1:0x76 | ||
|
||
# compass | ||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES | ||
|
||
# builtin compass | ||
COMPASS IIS2MDC I2C:2:0x1E false ROTATION_NONE | ||
|
||
# IIM42653 on SPI1 | ||
SPIDEV iim42653 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ | ||
#SPIDEV adis16507 SPI6 DEVID1 EXT1_CS MODE3 1*MHZ 2*MHZ | ||
|
||
# ARKV6X 1 IIM42653 IMU | ||
IMU Invensensev3 SPI:iim42653 ROTATION_YAW_270 | ||
|
||
# IMU Invensensev3 SPI:iim42652 ROTATION_YAW_270 | ||
#IMU ADIS1647x SPI:adis16507 ROTATION_NONE ADIS_DRDY_PIN | ||
|
||
define HAL_DEFAULT_INS_FAST_SAMPLE 1 | ||
|
||
# enable RAMTROM parameter storage | ||
define HAL_STORAGE_SIZE 32768 | ||
|
||
# INA226 battery monitor | ||
define HAL_BATTMON_INA2XX_BUS 2 | ||
define HAL_BATTMON_INA2XX_ADDR 0 | ||
define HAL_BATT_MONITOR_DEFAULT 21 | ||
|
||
DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM* | ||
|
||
# enable FAT filesystem support (needs a microSD defined via SDMMC) | ||
define HAL_OS_FATFS_IO 1 | ||
|
||
# ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin | ||
|
||
# enable DFU reboot for installing bootloader | ||
# note that if firmware is build with --secure-bl then DFU is | ||
# disabled | ||
ENABLE_DFU_BOOT 1 | ||
|
||
# bootloader embedding / bootloader flashing not available | ||
define AP_BOOTLOADER_FLASHING_ENABLED 0 |