ardupilot/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef.dat

47 lines
1.2 KiB
Plaintext
Raw Normal View History

# hw definition file for processing by chibios_pins.py
# for SkystarsH7HD
include ../SkystarsH7HD/hwdef.dat
undef PB0 PB1 PD12 PA0 PA2 PC7 PC6 PD8 PD9 PB5 PB6 PE0 PE1
undef DMA_PRIORITY DMA_NOSHARE HAL_I2C_INTERNAL_MASK
undef DEFAULT_SERIAL6_PROTOCOL DEFAULT_SERIAL6_BAUD
MCU_CLOCKRATE_MHZ 480
DMA_PRIORITY TIM3* TIM4* TIM2* SPI1* SPI3* SPI4* TIM1*
DMA_NOSHARE TIM3* TIM4* TIM2* SPI1* SPI3*
define HAL_I2C_INTERNAL_MASK 1
define RELAY2_PIN_DEFAULT 81 # Pit-1
define RELAY3_PIN_DEFAULT 82 # PIN-EN
# Motor order Betaflight/X
define HAL_FRAME_TYPE_DEFAULT 12
# USART1 (RX)
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
define DEFAULT_SERIAL1_BAUD 115
# USART3 (ESC Telem)
PD8 USART3_TX USART3 NODMA
PD9 USART3_RX USART3 NODMA
# UART4 (GPS)
# UART5 (VTX)
PB5 UART5_RX UART5 NODMA
PB6 UART5_TX UART5 NODMA
# USART6 (DJI FPV)
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_DJI_FPV
define DEFAULT_SERIAL6_BAUD 115
# UART7
# UART8
PE0 UART8_RX UART8 NODMA
PE1 UART8_TX UART8 NODMA
# Motors
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51)
PD12 TIM4_CH1 TIM4 PWM(3) GPIO(52) BIDIR
PA0 TIM2_CH1 TIM2 PWM(5) GPIO(54) BIDIR
PA2 TIM2_CH3 TIM2 PWM(7) GPIO(56) BIDIR