mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
hwdef: ARKV6X
This commit is contained in:
parent
71fdf37055
commit
e5cd25ff98
@ -43,6 +43,7 @@ TARGET_HW_ARK_CAN_GPS 81
|
||||
TARGET_HW_ARK_CAN_RTK_GPS 82
|
||||
TARGET_HW_FF_RTK_CAN_GPS 85
|
||||
TARGET_HW_ATL_MANTIS_EDU 97
|
||||
TARGET_HW_ARK_FMU_V6X 57
|
||||
|
||||
|
||||
Reserved PX4 [BL] FMU v5X.x 51
|
||||
|
76
libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef-bl.dat
Normal file
76
libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef-bl.dat
Normal file
@ -0,0 +1,76 @@
|
||||
# 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 57
|
||||
|
||||
# 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
|
||||
|
||||
# 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
|
||||
|
||||
# CS pins
|
||||
PI9 IMU1_CS CS
|
||||
PH5 ICM42688_CS CS
|
||||
PI4 BMI088_A_CS CS
|
||||
PI8 BMI088_G_CS CS
|
||||
PH15 BMM150_CS CS
|
||||
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
|
||||
|
||||
# start peripheral power off
|
||||
PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH
|
||||
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
|
331
libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat
Normal file
331
libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat
Normal file
@ -0,0 +1,331 @@
|
||||
# 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
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 2
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 57
|
||||
|
||||
# Enable all IMUs to be used and therefore three active EKF Lanes
|
||||
define HAL_EKF_IMU_MASK_DEFAULT 7
|
||||
|
||||
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
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
||||
# 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
|
||||
|
||||
# GPS2
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
# uart4
|
||||
PH13 UART4_TX UART4
|
||||
PH14 UART4_RX UART4
|
||||
|
||||
# debug uart
|
||||
PD8 USART3_TX USART3
|
||||
PD9 USART3_RX USART3
|
||||
|
||||
# USART6 is for IOMCU
|
||||
PC6 USART6_TX USART6
|
||||
PC7 USART6_RX USART6
|
||||
IOMCU_UART USART6
|
||||
|
||||
# uart6, RX only, RC input, if no IOMCU
|
||||
# PC7 USART6_RX USART6
|
||||
|
||||
# ethernet (not implemented yet)
|
||||
#PA1 ETH_REF_CLK
|
||||
#PA2 ETH_MDIO
|
||||
#PA7 ETH_CRS_DV
|
||||
#PB11 ETH_TX_EN
|
||||
#PC1 ETH_MDC
|
||||
#PC4 ETH_RXD0
|
||||
#PC5 ETH_RXD1
|
||||
#PG12 ETH_TXD1
|
||||
#PG13 ETH_TXD0
|
||||
#PG15 ETH_POWER_EN
|
||||
|
||||
# ADC
|
||||
PA0 SCALED1_V3V3 ADC1 SCALE(2)
|
||||
PA4 SCALED2_V3V3 ADC1 SCALE(2)
|
||||
PB0 SCALED3_V3V3 ADC1 SCALE(2)
|
||||
PF12 SCALED4_V3V3 ADC1 SCALE(2)
|
||||
|
||||
PB1 VDD_5V_SENS ADC1 SCALE(2)
|
||||
|
||||
# pin7 on AD&IO, analog 12
|
||||
PC2 ADC1_6V6 ADC1 SCALE(2)
|
||||
|
||||
# pin6 on AD&IO, analog 13
|
||||
PC3 ADC1_3V3 ADC1 SCALE(1)
|
||||
|
||||
# SPI1 - IIM42652
|
||||
PA5 SPI1_SCK SPI1
|
||||
PB5 SPI1_MOSI SPI1
|
||||
PG9 SPI1_MISO SPI1
|
||||
PI9 IMU1_CS CS
|
||||
PF2 IMU1_DRDY INPUT
|
||||
|
||||
# SPI2 - ICM42688
|
||||
PI1 SPI2_SCK SPI2
|
||||
PI2 SPI2_MISO SPI2
|
||||
PI3 SPI2_MOSI SPI2
|
||||
PH5 IMU2_CS CS
|
||||
PA10 IMU2_DRDY INPUT
|
||||
|
||||
# SPI3 - ICM42688
|
||||
PB2 SPI3_MOSI SPI3
|
||||
PC10 SPI3_SCK SPI3
|
||||
PC11 SPI3_MISO SPI3
|
||||
PI4 IMU3_CS CS
|
||||
PI6 IMU3_DRDY INPUT
|
||||
|
||||
# SPI5 - FRAM
|
||||
PF7 SPI5_SCK SPI5
|
||||
PH7 SPI5_MISO SPI5
|
||||
PF11 SPI5_MOSI SPI5
|
||||
PG7 FRAM_CS CS
|
||||
|
||||
# SPI6 - external1 (disabled to save DMA channels)
|
||||
# PB3 SPI6_SCK SPI6
|
||||
# PA6 SPI6_MISO SPI6
|
||||
# PG14 SPI6_MOSI SPI6
|
||||
# PI10 EXT1_CS CS
|
||||
|
||||
# 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)
|
||||
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
||||
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
|
||||
|
||||
# we need to disable DMA on the last 2 FMU channels
|
||||
# as timer 12 doesn't have a TIMn_UP DMA option
|
||||
PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56) NODMA
|
||||
PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57) NODMA
|
||||
|
||||
# GPIOs
|
||||
PE11 FMU_CAP1 INPUT GPIO(58)
|
||||
PC0 NFC_GPIO INPUT GPIO(60)
|
||||
|
||||
|
||||
# CAN bus
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
|
||||
PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
|
||||
|
||||
# I2C buses
|
||||
|
||||
# I2C1, GPS+MAG
|
||||
PB9 I2C1_SDA I2C1
|
||||
PB8 I2C1_SCL I2C1
|
||||
|
||||
# I2C2, GPS2+MAG
|
||||
PF1 I2C2_SCL I2C2
|
||||
PF0 I2C2_SDA I2C2
|
||||
PG5 DRDY1_BMP388 INPUT
|
||||
|
||||
# I2C3, MS5611, external
|
||||
PA8 I2C3_SCL I2C3
|
||||
PH8 I2C3_SDA I2C3
|
||||
|
||||
# I2C4 internal
|
||||
PF14 I2C4_SCL I2C4
|
||||
PF15 I2C4_SDA I2C4
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C4 I2C1 I2C2 I2C3
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
|
||||
# this board is very tight on DMA channels. To allow for more UART DMA
|
||||
# we disable DMA on I2C. This also prevents a problem with DMA on I2C
|
||||
# interfering with IMUs
|
||||
NODMA I2C*
|
||||
define STM32_I2C_USE_DMA FALSE
|
||||
|
||||
# heater - No heater on Rev 1
|
||||
# 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
|
||||
|
||||
# armed indication
|
||||
PE6 nARMED OUTPUT HIGH
|
||||
|
||||
# power enable pins
|
||||
PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH
|
||||
PI11 VDD_3V3_SENSORS1_EN OUTPUT HIGH
|
||||
PF4 VDD_3V3_SENSORS2_EN OUTPUT HIGH
|
||||
PE7 VDD_3V3_SENSORS3_EN OUTPUT HIGH
|
||||
PG8 VDD_3V3_SENSORS4_EN OUTPUT HIGH
|
||||
PG15 ETH_PWR_EN OUTPUT LOW # disable power on ethernet
|
||||
|
||||
# start peripheral power off, then enable after init
|
||||
# this prevents a problem with radios that use RTS for
|
||||
# bootloader hold
|
||||
PG10 nVDD_5V_HIPOWER_EN OUTPUT HIGH
|
||||
PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
# Control of Spektrum power pin
|
||||
PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73)
|
||||
define HAL_GPIO_SPEKTRUM_PWR 73
|
||||
|
||||
# Spektrum Power is Active High
|
||||
define HAL_SPEKTRUM_PWR_ENABLED 1
|
||||
|
||||
# power sensing
|
||||
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
|
||||
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP
|
||||
|
||||
PG1 VDD_BRICK_nVALID INPUT PULLUP
|
||||
PG2 VDD_BRICK2_nVALID INPUT PULLUP
|
||||
PG3 VDD_BRICK3_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
|
||||
|
||||
# safety
|
||||
PD10 LED_SAFETY OUTPUT
|
||||
PF5 SAFETY_IN INPUT PULLDOWN
|
||||
|
||||
# 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 HAL_GPIO_A_LED_PIN 90
|
||||
define HAL_GPIO_B_LED_PIN 91
|
||||
define HAL_GPIO_C_LED_PIN 92
|
||||
define HAL_GPIO_LED_ON 0
|
||||
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
|
||||
# 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
|
||||
|
||||
# RC input
|
||||
PI5 TIM8_CH1 TIM8 RCININT PULLDOWN LOW
|
||||
|
||||
# barometers
|
||||
BARO BMP388 I2C:0:0x76
|
||||
|
||||
# compass
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
|
||||
# builtin compass
|
||||
COMPASS BMM150 I2C:0:0x10 false ROTATION_NONE
|
||||
|
||||
# IMU devices for ARKV6X
|
||||
SPIDEV iim42652 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV icm42688 SPI2 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV icm42688_ext SPI3 DEVID1 IMU3_CS MODE3 2*MHZ 8*MHZ
|
||||
|
||||
SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
|
||||
# ARKV6X 3 IMUs
|
||||
IMU Invensensev3 SPI:iim42652 ROTATION_ROLL_180_YAW_135
|
||||
IMU Invensensev3 SPI:icm42688 ROTATION_YAW_45
|
||||
IMU Invensensev3 SPI:icm42688_ext ROTATION_ROLL_180_YAW_270
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 7
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
# INA226 battery monitor
|
||||
define HAL_BATTMON_INA2XX_BUS 1
|
||||
define HAL_BATTMON_INA2XX_ADDR 0x41
|
||||
define HAL_BATT_MONITOR_DEFAULT 21
|
||||
|
||||
# allow to have have a dedicated safety switch pin
|
||||
define HAL_HAVE_SAFETY_SWITCH 1
|
||||
|
||||
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
|
||||
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
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
|
Loading…
Reference in New Issue
Block a user