Skip to content

Commit

Permalink
added common.inc, added README
Browse files Browse the repository at this point in the history
  • Loading branch information
dakejahl committed Dec 12, 2024
1 parent f83ba71 commit 6eb6081
Show file tree
Hide file tree
Showing 4 changed files with 175 additions and 128 deletions.
87 changes: 87 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
# ARK FPV Flight Controller

https://arkelectron.com/product/ark-fpv-flight-controller/


## Features
#### Processor
- STM32H743 32-bit processor
- 480MHz
- 2MB Flash
- 1MB RAM
#### Sensors
- Invensense IIM-42653 Industrial IMU with heater resistor
- Bosch BMP390 Barometer
- ST IIS2MDC Magnetometer
#### Power
- 5.5V - 54V (2S - 12S) input
- 12V, 2A output
- 5V, 2A output. 300ma for main system, 200ma for heater
#### Interfaces
- **Micro SD**
- **USB-C**
- VBUS In, USB
- **PWM**
- VBAT In, Analog Current Input, Telem RX, 4x PWM and Bidirectional-DSHOT capable
- JST-GH 8 Pin
- **PWM EXTRA**
- 5x PWM and Bidirectional-DSHOT capable
- JST-SH 6 Pin
- **RC Input**
- 5V Out, UART
- JST-GH 4 Pin
- **POWER AUX**
- 12V Out, VBAT In/Out
- JST-GH 3 Pin
- **TELEM**
- 5V Out, UART with flow control
- JST-GH 6 Pin
- **GPS**
- 5V Out, UART, I2C
- JST-GH 6 Pin
- **CAN**
- 5V Out, CAN
- JST-GH 4 Pin
- **VTX**
- 12V Out, UART TX/RX, UART RX
- JST-GH 6 Pin
- **SPI** (OSD or External IMU)
- 5V Out, SPI
- JST-SH 8 Pin
- **DEBUG**
- 3.3V Out, UART, SWD
- JST-SH 6 Pin

##### Dimensions
- Size: 3.6 × 3.6 × 0.8 cm
- Weight: 7.5g with MicroSD card

## Pinout
TODO

## UART Mapping

|Name|Function|
|:-|:-|
|SERIAL0|USB|
|SERIAL1|UART7 (Telem)|
|SERIAL2|UART5 (VTX - DJI Air Unit, RX/TXT)|
|SERIAL3|USART1 (GPS1)|
|SERIAL4|USART2 (VTX - DJI Air Unit, RX only)|
|SERIAL5|UART4 (ESC Telem, RX only)|
|SERIAL6|USART6 (RC Input)|
|SERIAL7|OTG2 (SLCAN)|

All UARTS support DMA.

## OSD Support

This flight controller has an MSP-DisplayPort output on a 6-pin DJI-compatible JST SH.

## Motor Output

Motors 1-8 are capable of Bidirectional-DSHOT and PWM.

All outputs in the motor groups below must be either PWM or DShot:
Motors 1-4 Group1 (TIM5)
Motors 5-8 Group2 (TIM8)
32 changes: 32 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/common.inc
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
# MCU class and specific type
MCU STM32H7xx STM32H743xx

# board ID for firmware load
APJ_BOARD_ID 59

# crystal frequency
OSCILLATOR_HZ 16000000

# 480Hz is only value support on H7
# MCU_CLOCKRATE_MHZ 320

# flash size
FLASH_SIZE_KB 2048

# enable DFU reboot for installing bootloader
# note that if firmware is build with --secure-bl then DFU is
# disabled
ENABLE_DFU_BOOT 1

# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA9 VBUS INPUT OPENDRAIN

# SWD
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

# debug uart
PD8 USART3_TX USART3
PD9 USART3_RX USART3
49 changes: 9 additions & 40 deletions libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -1,61 +1,33 @@
# hw definition file for processing by chibios_hwdef.py
# for the ARKV6X hardware
# processed by chibios_hwdef.py

# MCU class and specific type
MCU STM32H7xx STM32H743xx

# crystal frequency
OSCILLATOR_HZ 16000000

# board ID for firmware load
APJ_BOARD_ID 59
include common.inc

# 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
# SPI1 - IIM42653
PI9 IMU1_CS CS
# BMMI088 Accel
PI4 BMI088_A_CS CS
# BMMI088 Gyro
PI8 BMI088_G_CS CS
# Unused
# PG7 FRAM_CS CS
# SPI6 - external
PI10 EXT1_CS CS

# telem1
PE8 UART7_TX UART7
PF6 UART7_RX UART7
PE8 UART7_TX UART7
PF6 UART7_RX UART7
PF8 UART7_RTS UART7
PE10 UART7_CTS UART7

# telem2
PC12 UART5_TX UART5
PD2 UART5_RX UART5

# debug uart
PD8 USART3_TX USART3
PD9 USART3_RX USART3
PD2 UART5_RX UART5

# armed indication
PE6 nARMED OUTPUT HIGH
Expand All @@ -70,6 +42,3 @@ define HAL_LED_ON 0

define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384

# enable DFU by default
ENABLE_DFU_BOOT 1
Loading

0 comments on commit 6eb6081

Please sign in to comment.