mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: FoxeerH743 GA release
This commit is contained in:
parent
b2aed56431
commit
f6408f9d9b
Binary file not shown.
After Width: | Height: | Size: 132 KiB |
|
@ -0,0 +1,100 @@
|
|||
# FoxeerH743 Flight Controller
|
||||
|
||||
The FoxeerH743 is a flight controller produced by [Foxeer](https://www.foxeer.com/).
|
||||
|
||||
## Features
|
||||
|
||||
- MCU - STM32H743 32-bit processor running at 480 MHz
|
||||
- IMU - MPU6000
|
||||
- Barometer - DPS310
|
||||
- OSD - AT7456E
|
||||
- Onboard Flash: 128Mbit
|
||||
- 7x UARTs
|
||||
- 9x PWM Outputs (8 Motor Output, 1 LED)
|
||||
- Battery input voltage: 2S-8S
|
||||
- BEC 3.3V 0.5A
|
||||
- BEC 5V 2A
|
||||
- BEC 10V 2A
|
||||
- DJI Connector
|
||||
|
||||
## Pinout
|
||||
|
||||
![FoxeerH743 Board](FoxeerH743_Board.JPG "FoxeerH743")
|
||||
|
||||
## 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 (RX/SBUS, DMA-enabled)
|
||||
- SERIAL2 -> UART2 (VTX)
|
||||
- SERIAL3 -> UART3 (DMA-enabled)
|
||||
- SERIAL4 -> UART4 (DJI RX/SBUS, DMA-enabled)
|
||||
- SERIAL6 -> UART6 (GPS, DMA-enabled)
|
||||
- SERIAL7 -> UART7 (DJI OSD, DMA-enabled)
|
||||
- SERIAL8 -> UART8 (ESC Telemetry)
|
||||
|
||||
## RC Input
|
||||
|
||||
RC input is configured by default on the R4 (UART4_RX) pin in the DJI connector. It supports all serial RC
|
||||
protocols. For protocols requiring separate half-duplex serial to transmit
|
||||
telemetry (such as FPort) you should setup SERIAL1 as an RC input serial port,
|
||||
with half-duplex, pin-swap and inversion enabled. You can also use the soldered pads on UART1 by setting SERIAL4_PROTOCOL to -1 and SERIAL1_PROTOCOL to 23. For PPM support on UART1_RX set BRD_ALT_CONFIG to 1.
|
||||
|
||||
## FrSky Telemetry
|
||||
|
||||
FrSky Telemetry can be supported using the T1 pin (UART1 transmit). You need to set the following parameters to enable support for FrSky S.PORT
|
||||
|
||||
- SERIAL1_PROTOCOL 10
|
||||
- SERIAL1_OPTIONS 7
|
||||
|
||||
## OSD Support
|
||||
|
||||
The FoxeerH743 supports OSD using OSD_TYPE 1 (MAX7456 driver) or OSD_TYPE 3 if using DJI OSD
|
||||
|
||||
## PWM Output
|
||||
|
||||
The FoxeerH743 supports up to 9 PWM outputs. The pads for motor output
|
||||
M1 to M8 are provided on both the motor connectors and on separate pads, plus
|
||||
M9 on a separate pad for LED strip or another PWM output.
|
||||
|
||||
The PWM is in 4 groups:
|
||||
|
||||
- PWM 1-4 in group1
|
||||
- PWM 5,6 in group2
|
||||
- PWM 7,8 in group3
|
||||
- PWM 9 in group4
|
||||
|
||||
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-8 support bi-directional dshot.
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has a builting voltage and current sensor. The current
|
||||
sensor can read up to 130 Amps. The voltage sensor can handle up to 8S
|
||||
LiPo batteries.
|
||||
|
||||
The correct battery setting parameters are:
|
||||
|
||||
- BATT_MONITOR 4
|
||||
- BATT_VOLT_PIN 13
|
||||
- BATT_CURR_PIN 12
|
||||
- BATT_VOLT_MULT 11
|
||||
- BATT_AMP_PERVLT 35.4
|
||||
|
||||
## Compass
|
||||
|
||||
The FoxeerH743 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads.
|
||||
|
||||
## 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.
|
||||
|
|
@ -11,6 +11,7 @@ APJ_BOARD_ID 1089
|
|||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
MCU_CLOCKRATE_MHZ 480
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
|
@ -48,35 +49,45 @@ define HAL_BUZZER_PIN 80
|
|||
define HAL_BUZZER_ON 1
|
||||
define HAL_BUZZER_OFF 0
|
||||
|
||||
# USART4 can also support PPM
|
||||
PA1 TIM2_CH2 TIM2 RCININT PULLDOWN LOW ALT(1)
|
||||
|
||||
# SERIAL ports
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY EMPTY UART7 UART8
|
||||
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
|
||||
# USART1 (RX/SBUS)
|
||||
PA10 USART1_RX USART1
|
||||
PA9 USART1_TX USART1
|
||||
define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART2 (VTX)
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
PA3 USART2_RX USART2 NODMA
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_SmartAudio
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_Tramp
|
||||
|
||||
# USART3 (GPS)
|
||||
# USART3
|
||||
PB10 USART3_TX USART3
|
||||
PB11 USART3_RX USART3
|
||||
define HAL_SERIAL3_PROTOCOL SerialProtocol_GPS
|
||||
define HAL_SERIAL3_PROTOCOL SerialProtocol_None
|
||||
|
||||
# UART4 (DJI)
|
||||
PA0 UART4_TX UART4
|
||||
# UART4 (DJI RX/SBUS)
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4
|
||||
define HAL_SERIAL4_PROTOCOL SerialProtocol_DJI_FPV
|
||||
define HAL_SERIAL4_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# UART7 (DJI)
|
||||
# USART6 (GPS)
|
||||
PC6 USART6_TX USART6
|
||||
PC7 USART6_RX USART6
|
||||
define HAL_SERIAL6_PROTOCOL SerialProtocol_GPS
|
||||
define HAL_SERIAL6_BAUD 115
|
||||
|
||||
# UART7 (DJI OSD)
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
define HAL_SERIAL7_PROTOCOL SerialProtocol_DJI_FPV
|
||||
define HAL_SERIAL7_BAUD 115
|
||||
|
||||
# UART8 (ESC)
|
||||
PE0 UART8_RX UART8 NODMA
|
||||
|
@ -107,8 +118,6 @@ define HAL_BATT_CURR_SCALE 35.4
|
|||
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
define HAL_BATT_VOLT_PIN 13
|
||||
define HAL_BATT_VOLT_SCALE 11.0
|
||||
PC5 RSSI_ADC ADC1
|
||||
define BOARD_RSSI_ANA_PIN 8
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
|
||||
# MOTORS
|
||||
|
@ -141,7 +150,7 @@ define HAL_OSD_TYPE_DEFAULT 1
|
|||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
# Barometer setup
|
||||
BARO DPS280 I2C:0:0x76
|
||||
BARO DPS310 I2C:0:0x76
|
||||
|
||||
# IMU setup
|
||||
|
||||
|
@ -157,6 +166,6 @@ 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
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
||||
# Motor order implies Betaflight/X for standard ESCs
|
||||
define HAL_FRAME_TYPE_DEFAULT 12
|
||||
|
|
Loading…
Reference in New Issue