-
Notifications
You must be signed in to change notification settings - Fork 17.9k
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: Added support for ZeroOne_Air flight controller
- Loading branch information
Your Name
committed
Dec 30, 2024
1 parent
21e4d13
commit 871412f
Showing
9 changed files
with
3,066 additions
and
0 deletions.
There are no files selected for viewing
Binary file not shown.
Large diffs are not rendered by default.
Oops, something went wrong.
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,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 |
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added
BIN
+1.83 MB
libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6_Air/ZeroOneX6_AirSeriesPinout.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
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,5 @@ | ||
CAN_P1_DRIVER 1 | ||
CAN_P2_DRIVER 1 | ||
|
||
BATT_MONITOR 8 | ||
|
103 changes: 103 additions & 0 deletions
103
libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6_Air/hwdef-bl.dat
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,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 | ||
|
Oops, something went wrong.