mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 10:23:59 -04:00
AP_HAL_ChibiOS: ARK_FPV board support
This commit is contained in:
parent
d8c232d452
commit
b722ea8f2f
232
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/README.md
Normal file
232
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/README.md
Normal file
@ -0,0 +1,232 @@
|
||||
# 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 AUX**
|
||||
- 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
|
||||
![top](ark_fpv_top.png)
|
||||
![bottom](ark_fpv_bottom.png)
|
||||
|
||||
#### PWM UART4 - 8 Pin JST-GH
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|-----------------|--------------|
|
||||
| 1 | VBAT IN | 5.5V-54V |
|
||||
| 2 | CURR_IN_EXT | 3.3V |
|
||||
| 3 | UART4_RX_EXT | 3.3V |
|
||||
| 4 | FMU_CH1_EXT | 3.3V |
|
||||
| 5 | FMU_CH2_EXT | 3.3V |
|
||||
| 6 | FMU_CH3_EXT | 3.3V |
|
||||
| 7 | FMU_CH4_EXT | 3.3V |
|
||||
| 8 | GND | GND |
|
||||
|
||||
#### RC - 4 Pin JST-GH
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|---------------------|---------|
|
||||
| 1 | 5.0V | 5.0V |
|
||||
| 2 | USART6_RX_IN_EXT | 3.3V |
|
||||
| 3 | USART6_TX_OUTPUT_EXT| 3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
#### PWM AUX - 6 Pin JST-SH
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|-----------------|---------|
|
||||
| 1 | FMU_CH5_EXT | 3.3V |
|
||||
| 2 | FMU_CH6_EXT | 3.3V |
|
||||
| 3 | FMU_CH7_EXT | 3.3V |
|
||||
| 4 | FMU_CH8_EXT | 3.3V |
|
||||
| 5 | FMU_CH9_EXT | 3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
#### POWER AUX - 3 Pin JST-GH
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|-------------|--------------|
|
||||
| 1 | 12.0V | 12.0V |
|
||||
| 2 | GND | GND |
|
||||
| 3 | VBAT IN/OUT | 5.5V-54V |
|
||||
|
||||
#### CAN - 4 Pin JST-GH
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|-------------|---------|
|
||||
| 1 | 5.0V | 5.0V |
|
||||
| 2 | CAN1_P | 5.0V |
|
||||
| 3 | CAN1_N | 5.0V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
#### GPS - 6 Pin JST-GH
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|---------------------|---------|
|
||||
| 1 | 5.0V | 5.0V |
|
||||
| 2 | USART1_TX_GPS1_EXT | 3.3V |
|
||||
| 3 | USART1_RX_GPS1_EXT | 3.3V |
|
||||
| 4 | I2C1_SCL_GPS1_EXT | 3.3V |
|
||||
| 5 | I2C1_SDA_GPS1_EXT | 3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
#### TELEM - 6 Pin JST-GH
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|-----------------------|---------|
|
||||
| 1 | 5.0V | 5.0V |
|
||||
| 2 | UART7_TX_TELEM1_EXT | 3.3V |
|
||||
| 3 | UART7_RX_TELEM1_EXT | 3.3V |
|
||||
| 4 | UART7_CTS_TELEM1_EXT | 3.3V |
|
||||
| 5 | UART7_RTS_TELEM1_EXT | 3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
#### VTX - 6 Pin JST-GH
|
||||
Note: connector pinout not in same order as standard HD VTX cabling
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|-----------------------|---------|
|
||||
| 1 | 12.0V | 12.0V |
|
||||
| 2 | GND | GND |
|
||||
| 3 | UART5_TX_TELEM2_EXT | 3.3V |
|
||||
| 4 | UART5_RX_TELEM2_EXT | 3.3V |
|
||||
| 5 | USART2_RX_TELEM3_EXT | 3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
#### SPI (OSD or IMU) - 8 Pin JST-SH
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|---------------------|---------|
|
||||
| 1 | 5.0V | 5.0V |
|
||||
| 2 | SPI6_SCK_EXT | 3.3V |
|
||||
| 3 | SPI6_MISO_EXT | 3.3V |
|
||||
| 4 | SPI6_MOSI_EXT | 3.3V |
|
||||
| 5 | SPI6_nCS1_EXT | 3.3V |
|
||||
| 6 | SPI6_DRDY1_EXT | 3.3V |
|
||||
| 7 | SPI6_nRESET_EXT | 3.3V |
|
||||
| 8 | GND | GND |
|
||||
|
||||
#### Flight Controller Debug - 6 Pin JST-SH
|
||||
| Pin | Signal Name | Voltage |
|
||||
|-----|-----------------|---------|
|
||||
| 1 | 3V3_FMU | 3.3V |
|
||||
| 2 | USART4_TX_DEBUG | 3.3V |
|
||||
| 3 | USART4_RX_DEBUG | 3.3V |
|
||||
| 4 | FMU_SWDIO | 3.3V |
|
||||
| 5 | FMU_SWCLK | 3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
|
||||
## UART Mapping
|
||||
|
||||
|Name|Function|
|
||||
|:-|:-|
|
||||
|SERIAL0|USB|
|
||||
|SERIAL1|UART7 (Telem)|
|
||||
|SERIAL2|UART5 (DisplayPort HD VTX)|
|
||||
|SERIAL3|USART1 (GPS1)|
|
||||
|SERIAL4|USART2 (User, SBUS pin on HD VTX, RX only)|
|
||||
|SERIAL5|UART4 (ESC Telem, RX only)|
|
||||
|SERIAL6|USART6 (RC Input)|
|
||||
|SERIAL7|OTG2 (SLCAN)|
|
||||
|
||||
All UARTS support DMA. Any UART may be re-tasked by changing its protocol parameter.
|
||||
|
||||
## RC Input
|
||||
|
||||
RC input is configured on the RX6 (UART6_RX) pin. It supports all RC protocols except PPM. See :ref:`Radio Control Systems <common-rc-systems>` for details for a specific RC system. :ref:`SERIAL6_PROTOCOL<SERIAL6_PROTOCOL>` is set to “23”, by default, to enable this.
|
||||
|
||||
- SBUS/DSM/SRXL connects to the RX6 pin.
|
||||
- FPort requires connection to TX6 and :ref:`SERIAL6_OPTIONS<SERIAL2_OPTIONS>` be set to “7”.
|
||||
- CRSF also requires a TX6 connection, in addition to RX6, and automatically provides telemetry. Set :ref:`SERIAL6_OPTIONS<SERIAL6_OPTIONS>`
|
||||
- SRXL2 requires a connecton to TX6 and automatically provides telemetry. Set :ref:`SERIAL6_OPTIONS<SERIAL6_OPTIONS>` to “4”. =3.
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input. The board supports up to 12S LiPo batteries.
|
||||
|
||||
The default battery parameters are:
|
||||
|
||||
- BATT_MONITOR 4
|
||||
- BATT_VOLT_PIN 9
|
||||
- BATT_CURR_PIN 12
|
||||
- BATT_VOLT_SCALE 21
|
||||
- BATT_CURR_SCALE 120
|
||||
|
||||
## Compass
|
||||
This autopilot has a built-in compass. The compass is the IIS2MDC
|
||||
|
||||
## OSD Support
|
||||
|
||||
This flight controller has an MSP-DisplayPort output on a 6-pin DJI-compatible JST SH.
|
||||
|
||||
## Motor Output
|
||||
|
||||
All outputs are capable of PWM and DShot. Motors 1-4 are capable of Bidirectional-DSHOT. All outputs in the motor groups below must be either PWM or DShot:
|
||||
- Motors 1-4 Group1 (TIM5)
|
||||
- Motors 5-8 Group2 (TIM8)
|
||||
- Motor 9 Group3 (TIM4)
|
||||
|
||||
## Loading Firmware
|
||||
|
||||
Initial firmware load can be done with DFU by plugging in USB with the
|
||||
BOOT button pressed. You can then load the bootloader using your favorite DFU tool.
|
||||
The bootloader can be found at https://firmware.ardupilot.org/Tools/Bootloaders/
|
||||
|
||||
Once the initial firmware is loaded you can update the firmware using
|
||||
any ArduPilot ground station software. Updates should be done with the
|
||||
*.apj firmware files*.
|
||||
|
||||
Alternatively you can build the firmware from source
|
||||
```
|
||||
./waf configure --board ARK_FPV --bootloader
|
||||
./waf bootloader
|
||||
```
|
||||
And flash the bootloader with your st-link to 0x08000000.
|
||||
Then build the firmware and upload it via USB-C
|
||||
```
|
||||
./waf configure --board ARK_FPV
|
||||
./waf copter --upload
|
||||
```
|
BIN
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/ark_fpv_bottom.png
Normal file
BIN
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/ark_fpv_bottom.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 219 KiB |
BIN
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/ark_fpv_top.png
Normal file
BIN
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/ark_fpv_top.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 279 KiB |
41
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/common.inc
Normal file
41
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/common.inc
Normal file
@ -0,0 +1,41 @@
|
||||
# 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
|
||||
|
||||
# SD card
|
||||
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
|
5
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/defaults.parm
Normal file
5
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/defaults.parm
Normal file
@ -0,0 +1,5 @@
|
||||
# CAN
|
||||
CAN_P1_DRIVER 1 # Enables the use of CAN
|
||||
|
||||
# Onboard OSD
|
||||
OSD_TYPE 5 # MSP
|
32
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef-bl.dat
Normal file
32
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef-bl.dat
Normal file
@ -0,0 +1,32 @@
|
||||
# Processed by chibios_hwdef.py
|
||||
|
||||
include common.inc
|
||||
|
||||
# Bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# Location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
SERIAL_ORDER OTG1 UART7 USART1 USART3
|
||||
|
||||
PI9 IMU1_CS CS # SPI1 CS - IIM42653
|
||||
PI10 EXT1_CS CS # SPI6 CS - external
|
||||
|
||||
# Telem1 - Telem
|
||||
PE8 UART7_TX UART7
|
||||
PF6 UART7_RX UART7
|
||||
PF8 UART7_RTS UART7
|
||||
PE10 UART7_CTS UART7
|
||||
|
||||
# GPS
|
||||
PB6 USART1_TX USART1
|
||||
PB7 USART1_RX USART1
|
||||
|
||||
# Armed indication
|
||||
PE6 nARMED OUTPUT HIGH
|
||||
|
||||
# LEDs
|
||||
PE3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red
|
||||
PE5 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # blue
|
||||
define HAL_LED_ON 0
|
201
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef.dat
Normal file
201
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef.dat
Normal file
@ -0,0 +1,201 @@
|
||||
# Processed by chibios_hwdef.py
|
||||
|
||||
include common.inc
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 2
|
||||
|
||||
# Bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# Use last 2 pages for flash storage
|
||||
# H743 has 16 pages of 128k each
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
STORAGE_FLASH_PAGE 14
|
||||
|
||||
# To be compatible with the px4 bootloader we need
|
||||
# to use a different RAM_MAP
|
||||
env USE_ALT_RAM_MAP 1
|
||||
|
||||
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
|
||||
|
||||
# Telem
|
||||
PE8 UART7_TX UART7
|
||||
PF6 UART7_RX UART7
|
||||
PF8 UART7_RTS UART7
|
||||
PE10 UART7_CTS UART7
|
||||
|
||||
# VTX (DJI Air Unit)
|
||||
PC12 UART5_TX UART5
|
||||
PD2 UART5_RX UART5
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_MSP_DisplayPort
|
||||
|
||||
# GPS
|
||||
PB6 USART1_TX USART1
|
||||
PB7 USART1_RX USART1
|
||||
|
||||
# VTX (DJI Air Unit, RX only)
|
||||
PA3 USART2_RX USART2
|
||||
PD5 USART2_TX USART2 NODMA
|
||||
# TODO: DJI HDL?
|
||||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None
|
||||
|
||||
# ESC Telem (RX only)
|
||||
PH13 UART4_TX UART4 NODMA
|
||||
PH14 UART4_RX UART4
|
||||
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define DEFAULT_SERIAL5_BAUD 115
|
||||
define HAL_SERIAL_ESC_COMM_ENABLED 1
|
||||
define HAL_WITH_ESC_TELEM 1
|
||||
|
||||
# RC Input
|
||||
PC6 USART6_TX USART6
|
||||
PC7 USART6_RX USART6
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# ADCs
|
||||
PA0 SCALED1_V3V3 ADC1 SCALE(2)
|
||||
PB1 VDD_5V_SENS ADC1 SCALE(2)
|
||||
# 12V monitor
|
||||
PA4 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(7.66)
|
||||
|
||||
PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
# Analog battery input scaling
|
||||
# See STM32H743xx.py
|
||||
define HAL_BATT_VOLT_PIN 9
|
||||
define HAL_BATT_CURR_PIN 12
|
||||
define HAL_BATT_VOLT_SCALE 21
|
||||
define HAL_BATT_CURR_SCALE 120
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
|
||||
# SPI1 - IIM42653 IMU
|
||||
PA5 SPI1_SCK SPI1
|
||||
PB5 SPI1_MOSI SPI1
|
||||
PG9 SPI1_MISO SPI1
|
||||
PI9 IMU1_CS CS
|
||||
PF2 IMU1_DRDY INPUT
|
||||
|
||||
# SPI6 - external (SPI OSD or IMU)
|
||||
PB3 SPI6_SCK SPI6
|
||||
PA6 SPI6_MISO SPI6
|
||||
PG14 SPI6_MOSI SPI6
|
||||
PI10 EXT1_CS CS
|
||||
PD11 DRDY_ADIS16507 INPUT GPIO(93)
|
||||
|
||||
# GPIO(93) for data ready on ADIS16507
|
||||
# define ADIS_DRDY_PIN 93
|
||||
|
||||
# Motors, see STM32H743xx.py
|
||||
PI0 TIM5_CH4 TIM5 PWM(1) GPIO(50) BIDIR
|
||||
PH12 TIM5_CH3 TIM5 PWM(2) GPIO(51) BIDIR
|
||||
PH11 TIM5_CH2 TIM5 PWM(3) GPIO(52) BIDIR
|
||||
PH10 TIM5_CH1 TIM5 PWM(4) GPIO(53) BIDIR
|
||||
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)
|
||||
|
||||
# PWM output for buzzer
|
||||
PF9 TIM14_CH1 TIM14 GPIO(77) ALARM
|
||||
|
||||
# CAN bus
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
|
||||
# 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
|
||||
|
||||
# IMU heater
|
||||
PB10 HEATER_EN OUTPUT LOW GPIO(80)
|
||||
define HAL_HEATER_GPIO_PIN 80
|
||||
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
|
||||
|
||||
# 12V enable, start with it ON
|
||||
PG4 VDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
# Power sensing
|
||||
# 12V PGOOD
|
||||
PE15 VDD_5V_PERIPH_nOC INPUT FLOATING
|
||||
# 5V PGOOD
|
||||
PF13 VDD_5V_HIPOWER_nOC INPUT FLOATING
|
||||
# 5V_ON_BATn
|
||||
PG1 VDD_BRICK_nVALID INPUT FLOATING
|
||||
|
||||
# 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
|
||||
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
|
||||
PH4 HW_REV_SENS ADC3 SCALE(1)
|
||||
|
||||
# Barometer on i2c_2
|
||||
BARO BMP388 I2C:1:0x76
|
||||
|
||||
# Compass
|
||||
COMPASS IIS2MDC I2C:2:0x1E false ROTATION_NONE
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define AP_COMPASS_IIS2MDC_ENABLED 1
|
||||
|
||||
# IIM42653 IMU on SPI1
|
||||
SPIDEV iim42653 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ
|
||||
IMU Invensensev3 SPI:iim42653 ROTATION_YAW_270
|
||||
|
||||
# SPI6 external bus
|
||||
# SPIDEV adis16507 SPI6 DEVID1 EXT1_CS MODE3 1*MHZ 2*MHZ
|
||||
# IMU ADIS1647x SPI:adis16507 ROTATION_NONE ADIS_DRDY_PIN
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
||||
|
||||
# Prioritze SD logging and IMU
|
||||
DMA_PRIORITY SDMMC* SPI*
|
||||
|
||||
# Bidir DShot timers cannot share DMA
|
||||
DMA_NOSHARE SPI* TIM5* TIM8*
|
||||
|
||||
# Enable FAT filesystem support (needs a microSD defined via SDMMC)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
# Setup for OSD
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 5 # MSP Displayport
|
Loading…
Reference in New Issue
Block a user