mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: Flywoo H743 Pro
This commit is contained in:
parent
40e7118020
commit
08bf7c6163
Binary file not shown.
After Width: | Height: | Size: 681 KiB |
|
@ -0,0 +1,112 @@
|
|||
# Flywoo H743 Pro Flight Controller
|
||||
|
||||
The Flywoo H743 Pro is a flight controller produced by [Flywoo](https://www.flywoo.net/).
|
||||
|
||||
## Features
|
||||
|
||||
- MCU - STM32H743 32-bit processor running at 480 MHz
|
||||
- IMU - Dual ICM42688
|
||||
- Barometer - SPL06
|
||||
- OSD - AT7456E
|
||||
- Onboard Flash: 500MByte
|
||||
- 7x UARTs
|
||||
- 13x PWM Outputs (12 Motor Output, 1 LED)
|
||||
- Battery input voltage: 2S-6S
|
||||
- BEC 3.3V 0.5A
|
||||
- BEC 5V 3A
|
||||
- BEC 10V 3A for video, gpio controlled
|
||||
- Dual switchable camera inputs
|
||||
|
||||
## Pinout
|
||||
|
||||
![Flywoo H743 Pro Board Top](Top.png "Flywoo H743 Pro Top")
|
||||
![Flywoo H743 Pro Board Bottom](Bottom.png "Flywoo H743 Pro Bottom")
|
||||
|
||||
## 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.
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> UART1 (User, DMA-enabled)
|
||||
- SERIAL2 -> UART2 (RX, DMA-enabled)
|
||||
- SERIAL3 -> UART3 (User)
|
||||
- SERIAL4 -> UART4 (GPS, DMA-enabled)
|
||||
- SERIAL6 -> UART6 (ESC Telemetry)
|
||||
- SERIAL7 -> UART7 (User)
|
||||
- SERIAL8 -> UART8 (DisplayPort, DMA-enabled)
|
||||
|
||||
## RC Input
|
||||
|
||||
RC input is configured by default via the USART2 RX input. It supports all serial RC protocols except PPM.
|
||||
|
||||
Note: If the receiver is FPort the receiver must be tied to the USART2 TX pin , RSSI_TYPE set to 3,
|
||||
and SERIAL2_OPTIONS must be set to 7 (invert TX/RX, half duplex). For full duplex like CRSF/ELRS use both
|
||||
RX1 and TX1 and set RSSI_TYPE also to 3.
|
||||
|
||||
## FrSky Telemetry
|
||||
|
||||
FrSky Telemetry is supported using an unused UART, such as the T3 pin (UART3 transmit).
|
||||
You need to set the following parameters to enable support for FrSky S.PORT:
|
||||
|
||||
- SERIAL3_PROTOCOL 10
|
||||
- SERIAL3_OPTIONS 7
|
||||
|
||||
## OSD Support
|
||||
|
||||
The Flywoo H743 Pro supports OSD using OSD_TYPE 1 (MAX7456 driver) and simultaneously DisplayPort using TX8/RX8 on the HD VTX connector.
|
||||
|
||||
## PWM Output
|
||||
|
||||
The Flywoo H743 Pro supports up to 13 PWM or DShot outputs. The pads for motor output
|
||||
M1 to M8 are provided on both the motor connectors and on separate pads, plus
|
||||
M9-13 on a separate pads for LED strip and other PWM outputs.
|
||||
|
||||
The PWM is in 4 groups:
|
||||
|
||||
- PWM 1-2 in group1
|
||||
- PWM 3-6 in group2
|
||||
- PWM 7-10 in group3
|
||||
- PWM 11-12 in group4
|
||||
- PWM 13 in group5
|
||||
|
||||
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. Channels 1-10 support bi-directional dshot.
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has a built-in voltage sensor and external current sensor input. The current
|
||||
sensor can read up to 130 Amps. The voltage sensor can handle up to 6S
|
||||
LiPo batteries.
|
||||
|
||||
The correct battery setting parameters are:
|
||||
|
||||
- BATT_MONITOR 4
|
||||
- BATT_VOLT_PIN 11
|
||||
- BATT_CURR_PIN 13
|
||||
- BATT_VOLT_MULT 11.1
|
||||
- BATT_AMP_PERVLT 40
|
||||
|
||||
## Compass
|
||||
|
||||
The Flywoo H743 Pro does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads.
|
||||
|
||||
## VTX power control
|
||||
|
||||
GPIO 81 controls the VTX BEC output to pins marked "10V". Setting this GPIO low removes voltage supply to pins.
|
||||
By default RELAY2 is configured to control this pin and sets the GPIO high.
|
||||
|
||||
## Camera control
|
||||
|
||||
GPIO 82 controls the camera output to the connectors marked "CAM1" and "CAM2". Setting this GPIO low switches the video output from CAM1 to CAM2. By default RELAY3 is configured to control this pin and sets the GPIO high.
|
||||
|
||||
## Loading Firmware
|
||||
|
||||
Initial firmware load can be done with DFU by plugging in USB with the
|
||||
bootloader button pressed. Then you should load the "with_bl.hex"
|
||||
firmware, using your favourite DFU loading tool.
|
||||
|
||||
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.
|
Binary file not shown.
After Width: | Height: | Size: 635 KiB |
|
@ -0,0 +1,2 @@
|
|||
SERVO13_FUNCTION 120
|
||||
OSD_TYPE2 5
|
|
@ -0,0 +1,42 @@
|
|||
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for FLYWOOH743 hardware.
|
||||
# thanks to betaflight for pin information
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID AP_HW_FlywooH743Pro
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader starts at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 384
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# Chip select pins
|
||||
PB12 OSD1_CS CS
|
||||
PC15 GYRO1_CS CS
|
||||
PE11 GYRO2_CS CS
|
||||
|
||||
PD10 VTX_PWR OUTPUT HIGH
|
||||
PD11 CAM_CTRL OUTPUT HIGH
|
||||
|
||||
PE3 LED_BOOTLOADER OUTPUT LOW
|
||||
define HAL_LED_ON 1
|
|
@ -0,0 +1,195 @@
|
|||
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for FLYWOOH743 hardware.
|
||||
# thanks to betaflight for pin information
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID AP_HW_FlywooH743Pro
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
MCU_CLOCKRATE_MHZ 480
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 384
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define STORAGE_FLASH_PAGE 1
|
||||
|
||||
STM32_ST_USE_TIMER 12
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
# SPI devices
|
||||
|
||||
# SPI1 (IMU1)
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI2 (OSD)
|
||||
PB13 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB15 SPI2_MOSI SPI2
|
||||
|
||||
# SPI3 (External)
|
||||
PB3 SPI3_SCK SPI3
|
||||
PB4 SPI3_MISO SPI3
|
||||
PB5 SPI3_MOSI SPI3
|
||||
|
||||
# SPI4 (IMU2)
|
||||
PE12 SPI4_SCK SPI4
|
||||
PE13 SPI4_MISO SPI4
|
||||
PE14 SPI4_MOSI SPI4
|
||||
|
||||
# Chip select pins
|
||||
PB12 OSD1_CS CS
|
||||
PC15 GYRO1_CS CS
|
||||
PE11 GYRO2_CS CS
|
||||
|
||||
# Beeper
|
||||
PA15 TIM2_CH1 TIM2 GPIO(32) ALARM
|
||||
|
||||
# SERIAL ports
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7 UART8
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# USART1
|
||||
PA10 USART1_RX USART1
|
||||
PA9 USART1_TX USART1
|
||||
|
||||
# USART2 (RX)
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2
|
||||
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART3
|
||||
PD8 USART3_TX USART3 NODMA
|
||||
PD9 USART3_RX USART3 NODMA
|
||||
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None
|
||||
|
||||
# UART4 (GPS1)
|
||||
PB8 UART4_RX UART4
|
||||
PB9 UART4_TX UART4
|
||||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS
|
||||
|
||||
# USART6
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
PC7 USART6_RX USART6 NODMA
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
|
||||
# UART7
|
||||
PE7 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
# UART8 (DJI/MSP)
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_MSP_DisplayPort
|
||||
|
||||
# I2C ports
|
||||
I2C_ORDER I2C1 I2C2
|
||||
# I2C1
|
||||
PB6 I2C1_SCL I2C1
|
||||
PB7 I2C1_SDA I2C1
|
||||
|
||||
# I2C2
|
||||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
BARO SPL06 I2C:1:0x76
|
||||
define AP_BARO_BACKEND_DEFAULT_ENABLED 0
|
||||
define AP_BARO_SPL06_ENABLED 1
|
||||
|
||||
# ADC ports
|
||||
|
||||
# ADC1
|
||||
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
define HAL_BATT_VOLT_PIN 10
|
||||
define HAL_BATT_VOLT_SCALE 11.0
|
||||
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
define HAL_BATT_CURR_PIN 11
|
||||
define HAL_BATT_CURR_SCALE 40.0
|
||||
PC5 RSSI_ADC ADC1
|
||||
define BOARD_RSSI_ANA_PIN 8
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
PC4 PRESSURE_SENS ADC1 SCALE(2)
|
||||
define HAL_DEFAULT_AIRSPEED_PIN 4
|
||||
|
||||
# MOTORS
|
||||
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR # M1
|
||||
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) # M2
|
||||
PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52) BIDIR # M3
|
||||
PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53) # M4
|
||||
PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) BIDIR # M5
|
||||
PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) # M6
|
||||
PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR # M7
|
||||
PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) # M8
|
||||
PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) BIDIR # S9
|
||||
PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) # S10
|
||||
PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) NODMA # S11
|
||||
PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) NODMA # S12
|
||||
|
||||
# LEDs
|
||||
PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # S13
|
||||
|
||||
# VTX Power control - should be high at startup to ensure power
|
||||
PD10 VTX_PWR OUTPUT HIGH GPIO(81)
|
||||
define RELAY2_PIN_DEFAULT 81
|
||||
|
||||
# Camera switch control - should be high at startup to ensure Camera 1 selected
|
||||
PD11 CAM_CTRL OUTPUT HIGH GPIO(82)
|
||||
define RELAY3_PIN_DEFAULT 82
|
||||
|
||||
PE3 LED0 OUTPUT LOW GPIO(90)
|
||||
define HAL_GPIO_A_LED_PIN 90
|
||||
|
||||
PE4 LED1 OUTPUT LOW GPIO(91)
|
||||
define HAL_GPIO_B_LED_PIN 91
|
||||
|
||||
define AP_NOTIFY_GPIO_LED_2_ENABLED 1
|
||||
|
||||
# OSD setup
|
||||
SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ
|
||||
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
# IMU setup
|
||||
|
||||
# IMU setup
|
||||
SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 16*MHZ
|
||||
SPIDEV imu2 SPI4 DEVID1 GYRO2_CS MODE3 1*MHZ 16*MHZ
|
||||
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
IMU Invensensev3 SPI:imu1 ROTATION_PITCH_180_YAW_90
|
||||
IMU Invensensev3 SPI:imu2 ROTATION_PITCH_180_YAW_90
|
||||
|
||||
DMA_NOSHARE TIM3_UP TIM5_UP TIM4_UP SPI1* SPI4*
|
||||
DMA_PRIORITY TIM3_UP TIM5_UP TIM4_UP SPI1* SPI4*
|
||||
|
||||
# no built-in compass, but probe the i2c bus for all possible
|
||||
# external compass types
|
||||
define ALLOW_ARM_NO_COMPASS
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
||||
# Motor order implies Betaflight/X for standard ESCs
|
||||
define HAL_FRAME_TYPE_DEFAULT 12
|
Loading…
Reference in New Issue