mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: Added support for ZeroOne_Air flight controller
This commit is contained in:
parent
331b58dcb0
commit
7ad05f77b1
|
@ -0,0 +1,105 @@
|
|||
## ZeroOneX6 Air Flight Controller
|
||||
The ZeroOneX6_Air is a series of flight controllers manufactured by ZeroOne, which is based on the open-source FMU v6C architecture and Pixhawk Autopilot Bus open source specifications.
|
||||
|
||||
![Uploading ZeroOneX6_Air.jpg…](https://github.com/ZeroOne-Aero/ardupilot/blob/ZeroOneX6_Air/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6_Air/ZeroOneX6_Air.png?raw=true)
|
||||
|
||||
|
||||
## Features:
|
||||
- Separate flight control Inertial Measurement Unit design.
|
||||
- MCU
|
||||
STM32H743IIK6 32-bit processor running at 400MHz
|
||||
2MB Flash
|
||||
1MB RAM
|
||||
- IO MCU
|
||||
STM32F103
|
||||
- **Sensors of Air**
|
||||
- IMU:
|
||||
With Synced IMU, BalancedGyro technology, low noise and more shock-resistant:
|
||||
IMU- ICM45686 (No vibration isolation)
|
||||
- Baro:
|
||||
one barometer :ICP20100
|
||||
- Magnetometer:
|
||||
Builtin IST8310 magnetometer
|
||||
- **Sensors of Air+**
|
||||
- IMU:
|
||||
Internal Vibration Isolation for IMU
|
||||
IMU constant temperature heating (1W heating power).
|
||||
With Double Synced IMUs, BalancedGyro technology, low noise and more shock-resistant:
|
||||
IMU1- ICM45686 (With vibration isolation)
|
||||
IMU2- ICM45686 (No vibration isolation)
|
||||
- Baro:
|
||||
Two barometers :2 x ICP20100
|
||||
- Magnetometer:
|
||||
Builtin IST8310 magnetometer
|
||||
|
||||
## Pinout
|
||||
![ZeroOneX6_Air Pinout](https://github.com/ZeroOne-Aero/ardupilot/blob/ZeroOneX6_Air/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6_Air/ZeroOneX6_AirSeriesPinout.jpg "ZeroOneX6_Air")
|
||||
|
||||
## UART Mapping
|
||||
The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
|
||||
| Name | Function | MCU PINS | DMA |
|
||||
| :-----: | :------: | :------: | :------:|
|
||||
| SERIAL0 | OTG1 | USB |
|
||||
| SERIAL1 | Telem1 | UART7 |DMA Enabled |
|
||||
| SERIAL2 | Telem2 | UART5 |DMA Enabled |
|
||||
| SERIAL3 | GPS1 | USART1 |DMA Enabled |
|
||||
| SERIAL4 | GPS2 | UART8 |DMA Enabled |
|
||||
| SERIAL5 | Telem3 | USART2 |DMA Enabled |
|
||||
| SERIAL6 | UART4 | UART4 |DMA Enabled |
|
||||
| SERIAL7 | OTG-SLCAN| USB |
|
||||
|
||||
## RC Input
|
||||
The remote control signal should be connected to the SBUS RC IN port.It will support ALL unidirectional RC protocols.
|
||||
|
||||
## PWM Output
|
||||
The X6_Air flight controller supports up to 15 PWM outputs.
|
||||
First 8 outputs (labelled 1 to 8) are controlled by a dedicated STM32F103 IO controller.
|
||||
The remaining 7 outputs (labelled 9 to 15) are the "auxiliary" outputs. These are directly attached to the STM32H753 FMU controller .
|
||||
All 15 outputs support normal PWM output formats. All 15 outputs support DShot, except 15.
|
||||
|
||||
The 8 IO PWM outputs are in 4 groups:
|
||||
- Outputs 1 and 2 in group1
|
||||
- Outputs 3 and 4 in group2
|
||||
- Outputs 5, 6, 7 and 8 in group3
|
||||
|
||||
The 8 FMU PWM outputs are in 4 groups:
|
||||
- Outputs 1, 2, 3 and 4 in group1
|
||||
- Outputs 5 and 6 in group2
|
||||
- Outputs 7 in group3
|
||||
|
||||
Channels within the same group need to use the same output rate. If any channel in a group uses DShot then all channels in the group need to use DShot.
|
||||
|
||||
## GPIO
|
||||
All PWM outputs can be used as GPIOs (relays, camera, RPM etc). To use them you need to set the output’s SERVOx_FUNCTION to -1. The numbering of the GPIOs for PIN variables in ArduPilot is:
|
||||
|
||||
<table>
|
||||
<tr>
|
||||
<th colspan="3">IO Pins</th>
|
||||
<th colspan="1"> </th>
|
||||
<th colspan="3">FMU Pins</th>
|
||||
</tr>
|
||||
<tr><td> Name </td><td> Value </td><td> Option </td><td> </td><td> Name </td><td> Value </td><td> Option </td></tr>
|
||||
<tr><td> M1 </td><td> 101 </td> <td> MainOut1 </td><td> </td><td> A9 </td><td> 50 </td><td> AuxOut1 </td></tr>
|
||||
<tr><td> M2 </td><td> 102 </td> <td> MainOut2 </td><td> </td><td> A10 </td><td> 51 </td><td> AuxOut2 </td></tr>
|
||||
<tr><td> M3 </td><td> 103 </td> <td> MainOut3 </td><td> </td><td> A11 </td><td> 52 </td><td> AuxOut3 </td></tr>
|
||||
<tr><td> M4 </td><td> 104 </td> <td> MainOut4 </td><td> </td><td> A12 </td><td> 53 </td><td> AuxOut4 </td></tr>
|
||||
<tr><td> M5 </td><td> 105 </td> <td> MainOut5 </td><td> </td><td> A13 </td><td> 54 </td><td> AuxOut5 </td></tr>
|
||||
<tr><td> M6 </td><td> 106 </td> <td> MainOut6 </td><td> </td><td> A14 </td><td> 55 </td><td> AuxOut6 </td></tr>
|
||||
<tr><td> M7 </td><td> 107 </td> <td> MainOut7 </td><td> </td><td> A15 </td><td> 56 </td><td> </td></tr>
|
||||
<tr><td> M8 </td><td> 108 </td> <td> MainOut8 </td><td> </td><td> </td><td> </td><td> </td></tr>
|
||||
</table>
|
||||
|
||||
## Battery Monitoring
|
||||
The X6_Air flight controller has one six-pin power connectors, supporting CAN interface power supply.
|
||||
This is set by default in the firmware and shouldn't need to be adjusted.
|
||||
|
||||
## Compass
|
||||
The X6_Air flight controller built-in industrial-grade electronic compass chip IST8310.
|
||||
|
||||
## Analog inputs
|
||||
The X6_Air flight controller has 2 analog inputs.
|
||||
- ADC Pin12 -> ADC 6.6V Sense
|
||||
- ADC Pin13 -> ADC 3.3V Sense
|
||||
|
||||
## Where to Buy
|
||||
https://www.01aero.cn
|
Binary file not shown.
After Width: | Height: | Size: 266 KiB |
Binary file not shown.
After Width: | Height: | Size: 2.2 MiB |
Binary file not shown.
After Width: | Height: | Size: 1.8 MiB |
|
@ -0,0 +1,5 @@
|
|||
CAN_P1_DRIVER 1
|
||||
CAN_P2_DRIVER 1
|
||||
|
||||
BATT_MONITOR 8
|
||||
|
|
@ -0,0 +1,103 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for the ZeroOneX6_Air Series hardware
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 5600
|
||||
|
||||
# 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
|
||||
|
||||
# Pin for PWM Voltage Selection
|
||||
PG6 PWM_VOLT_SEL OUTPUT HIGH GPIO(3)
|
||||
|
||||
# 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 ICM45686_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
|
||||
|
||||
# support flashing from SD card:
|
||||
# power enable pins
|
||||
PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH
|
||||
|
||||
# FATFS support:
|
||||
define CH_CFG_USE_MEMCORE 1
|
||||
define CH_CFG_USE_HEAP 1
|
||||
define CH_CFG_USE_SEMAPHORES 0
|
||||
define CH_CFG_USE_MUTEXES 1
|
||||
define CH_CFG_USE_DYNAMIC 1
|
||||
define CH_CFG_USE_WAITEXIT 1
|
||||
define CH_CFG_USE_REGISTRY 1
|
||||
|
||||
# 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
|
||||
|
||||
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 AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1
|
||||
|
|
@ -0,0 +1,335 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for the ZeroOneX6_Air Series hardware
|
||||
|
||||
# default to all pins low to avoid ESD issues
|
||||
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
||||
|
||||
# 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 5600
|
||||
|
||||
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
|
||||
|
||||
# supports upto 8MBits/s
|
||||
CANFD_SUPPORTED 8
|
||||
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2
|
||||
|
||||
# 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
|
||||
# define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
||||
# 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
|
||||
|
||||
# Ethernet
|
||||
PC1 ETH_MDC ETH1
|
||||
PA2 ETH_MDIO ETH1
|
||||
PC4 ETH_RMII_RXD0 ETH1
|
||||
PC5 ETH_RMII_RXD1 ETH1
|
||||
PG13 ETH_RMII_TXD0 ETH1
|
||||
PG12 ETH_RMII_TXD1 ETH1
|
||||
PB11 ETH_RMII_TX_EN ETH1
|
||||
PA7 ETH_RMII_CRS_DV ETH1
|
||||
PA1 ETH_RMII_REF_CLK ETH1
|
||||
#PG15 ETH_POWER_EN ETH1
|
||||
|
||||
PG15 Ethernet_PWR_EN OUTPUT HIGH # disable power on ethernet
|
||||
|
||||
define BOARD_PHY_ID MII_LAN8742A_ID
|
||||
define BOARD_PHY_RMII
|
||||
|
||||
# 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 - IMU3 ICM45686
|
||||
PA5 SPI1_SCK SPI1
|
||||
PB5 SPI1_MOSI SPI1
|
||||
PG9 SPI1_MISO SPI1
|
||||
PI9 SP1_CS1 CS
|
||||
|
||||
# SPI2 -IMU1 ICM45686
|
||||
PI1 SPI2_SCK SPI2
|
||||
PI2 SPI2_MISO SPI2
|
||||
PI3 SPI2_MOSI SPI2
|
||||
PH5 SP2_CS1 CS
|
||||
PA10 SP2_DRDY2 INPUT
|
||||
|
||||
# SPI3 - unused
|
||||
PB2 SPI3_MOSI SPI3
|
||||
PC10 SPI3_SCK SPI3
|
||||
PC11 SPI3_MISO SPI3
|
||||
PI4 SP3_CS1 CS
|
||||
PI8 SP3_CS2 CS
|
||||
PI6 SP3_DRDY1 INPUT
|
||||
PI7 SP3_DRDY2 INPUT GPIO(93)
|
||||
define SP3_DRDY2 93
|
||||
|
||||
# SPI4 - unused
|
||||
#PE12 SPI4_SCK SPI4
|
||||
#PE13 SPI4_MISO SPI4
|
||||
#PE14 SPI4_MOSI SPI4
|
||||
#PF3 SP4_DRDY1 INPUT
|
||||
PH15 SP4_CS1 CS
|
||||
|
||||
# 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)
|
||||
|
||||
# Pin for PWM Voltage Selection, 0 means 3.3v, 1 means 5v
|
||||
PG6 PWM_VOLT_SEL OUTPUT HIGH GPIO(3)
|
||||
define HAL_GPIO_PWM_VOLT_PIN 3
|
||||
define HAL_GPIO_PWM_VOLT_3v3 0
|
||||
|
||||
# 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
|
||||
|
||||
# heater
|
||||
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
|
||||
|
||||
# start peripheral power on
|
||||
PG10 nVDD_5V_HIPOWER_EN OUTPUT LOW
|
||||
PG4 nVDD_5V_PERIPH_EN OUTPUT LOW
|
||||
|
||||
# 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
|
||||
|
||||
# GPIO 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
|
||||
# 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 ZeroOneX6_Air Series
|
||||
BARO ICP201XX I2C:0:0x64
|
||||
BARO ICP201XX I2C:2:0x63
|
||||
|
||||
# compass
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
|
||||
# builtin compass on ZeroOneX6_Air Series
|
||||
COMPASS IST8310 I2C:0:0x0E false ROTATION_NONE
|
||||
|
||||
# IMU devices for ZeroOneX6_Air Series
|
||||
SPIDEV icm45686_1 SPI2 DEVID1 SP2_CS1 MODE3 2*MHZ 16*MHZ
|
||||
SPIDEV icm45686_2 SPI1 DEVID1 SP1_CS1 MODE3 2*MHZ 16*MHZ
|
||||
|
||||
SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
|
||||
# ZeroOneX6_Air Series 2 IMUs
|
||||
IMU Invensensev3 SPI:icm45686_1 ROTATION_ROLL_180_YAW_270
|
||||
IMU Invensensev3 SPI:icm45686_2 ROTATION_NONE
|
||||
|
||||
define HAL_INS_HIGHRES_SAMPLE 7
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 7
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
# allow to have have a dedicated safety switch pin
|
||||
define HAL_HAVE_SAFETY_SWITCH 1
|
||||
|
||||
DMA_PRIORITY TIM5* TIM4* SPI1* SPI2* SPI3* SDMMC* USART6* ADC* UART* USART*
|
||||
|
||||
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_f103_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
|
||||
|
||||
# build ABIN for flash-from-bootloader support:
|
||||
env BUILD_ABIN True
|
||||
|
||||
# enable support for dshot on iomcu
|
||||
#github suggestion
|
||||
ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_dshot_highpolh.bin
|
||||
define HAL_WITH_IO_MCU_DSHOT 1
|
||||
#V6C
|
||||
#ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin
|
||||
#define HAL_WITH_IO_MCU_BIDIR_DSHOT 1
|
Loading…
Reference in New Issue