mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: put RX on UART1 on Skystars H7HD bdshot
make sure VTX has power on Skystars H7HD at boot
This commit is contained in:
parent
05b88ba475
commit
661a03365c
|
@ -32,11 +32,10 @@ receive pin for UARTn. The TX pin is the transmit pin for UARTn.
|
|||
|
||||
## RC Input
|
||||
|
||||
RC input is configured on the R6 (UART6_RX) pin. It supports all serial RC
|
||||
protocols. For protocols requiring half-duplex serial to transmit
|
||||
telemetry (such as FPort) you should setup
|
||||
SERIAL6 as an RC input serial port, with half-duplex, pin-swap
|
||||
and inversion enabled.
|
||||
RC input is configured on the R1 (UART1_RX) pin in the DJI connector or via the R1/T1 (UART1) pads.
|
||||
It supports all serial RC protocols. For protocols requiring half-duplex serial to transmit
|
||||
telemetry (such as FPort) you should setup SERIAL1 with half-duplex and connect to T1 or use
|
||||
R1 with pin-swap. You also need to set inversion enabled if using FPort.
|
||||
|
||||
## OSD Support
|
||||
|
||||
|
@ -76,6 +75,7 @@ The correct battery setting parameters are:
|
|||
## Compass
|
||||
|
||||
The Skystars H7 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
|
||||
|
|
|
@ -5,6 +5,7 @@ include ../SkystarsH7HD/hwdef.dat
|
|||
|
||||
undef PB0 PB1 PD12 PA0 PA2 PC7 PC6 PD8 PD9 PB5 PB6 PE0 PE1
|
||||
undef HAL_I2C_INTERNAL_MASK DMA_PRIORITY DMA_NOSHARE
|
||||
undef HAL_SERIAL6_PROTOCOL HAL_SERIAL6_BAUD
|
||||
|
||||
MCU_CLOCKRATE_MHZ 480
|
||||
|
||||
|
@ -23,6 +24,8 @@ define RELAY4_PIN_DEFAULT 83 # CAM-C
|
|||
define HAL_FRAME_TYPE_DEFAULT 12
|
||||
|
||||
# USART1 (RX)
|
||||
define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
define HAL_SERIAL1_BAUD 115
|
||||
# USART3 (ESC Telem)
|
||||
PD8 USART3_TX USART3 NODMA
|
||||
PD9 USART3_RX USART3 NODMA
|
||||
|
@ -31,6 +34,8 @@ PD9 USART3_RX USART3 NODMA
|
|||
PB5 UART5_RX UART5 NODMA
|
||||
PB6 UART5_TX UART5 NODMA
|
||||
# USART6 (DJI FPV)
|
||||
define HAL_SERIAL6_PROTOCOL SerialProtocol_DJI_FPV
|
||||
define HAL_SERIAL6_BAUD 115
|
||||
# UART7
|
||||
# UART8
|
||||
PE0 UART8_RX UART8 NODMA
|
||||
|
|
|
@ -49,6 +49,7 @@ PB12 AT7456E_CS CS
|
|||
PA15 FLASH_CS CS
|
||||
PE11 BMI270_CS2 CS
|
||||
|
||||
PC5 VTX_PWR OUTPUT LOW # labelled as "Pit-1"
|
||||
## pull up VTX power so that it is enabled in bootloader
|
||||
PC5 VTX_PWR OUTPUT HIGH # labelled as "Pit-1"
|
||||
PC2 VID_SELECT OUTPUT LOW # labelled as "PIN-EN"
|
||||
PD2 CAM_C OUTPUT LOW # labelled as "CAM-C"
|
||||
|
|
Loading…
Reference in New Issue