|
|
|
@ -117,8 +117,8 @@ PD15 DRDY7_EXTERNAL1 INPUT
@@ -117,8 +117,8 @@ PD15 DRDY7_EXTERNAL1 INPUT
|
|
|
|
|
# UARTs |
|
|
|
|
|
|
|
|
|
# USART2 is telem1 |
|
|
|
|
PD6 USART2_RX USART2 NODMA |
|
|
|
|
PD5 USART2_TX USART2 NODMA |
|
|
|
|
PD6 USART2_RX USART2 |
|
|
|
|
PD5 USART2_TX USART2 |
|
|
|
|
PD3 USART2_CTS USART2 |
|
|
|
|
PD4 USART2_RTS USART2 |
|
|
|
|
|
|
|
|
@ -127,8 +127,8 @@ PB7 USART1_RX USART1 NODMA
@@ -127,8 +127,8 @@ PB7 USART1_RX USART1 NODMA
|
|
|
|
|
PB6 USART1_TX USART1 NODMA |
|
|
|
|
|
|
|
|
|
# USART3 is telem2 |
|
|
|
|
PD9 USART3_RX USART3 NODMA |
|
|
|
|
PD8 USART3_TX USART3 NODMA |
|
|
|
|
PD9 USART3_RX USART3 |
|
|
|
|
PD8 USART3_TX USART3 |
|
|
|
|
PD11 USART3_CTS USART3 |
|
|
|
|
PD12 USART3_RTS USART3 |
|
|
|
|
|
|
|
|
@ -137,10 +137,10 @@ PD0 UART4_RX UART4 NODMA
@@ -137,10 +137,10 @@ PD0 UART4_RX UART4 NODMA
|
|
|
|
|
PD1 UART4_TX UART4 NODMA |
|
|
|
|
|
|
|
|
|
# USART6 is telem3 |
|
|
|
|
PG9 USART6_RX USART6 NODMA |
|
|
|
|
PG9 USART6_RX USART6 |
|
|
|
|
# we leave PG14 as an input to prevent it acting as a pullup |
|
|
|
|
# on the IOMCU SBUS input |
|
|
|
|
# PG14 USART6_TX USART6 NODMA |
|
|
|
|
# PG14 USART6_TX USART6 |
|
|
|
|
PG15 USART6_CTS USART6 |
|
|
|
|
PG8 USART6_RTS USART6 |
|
|
|
|
|
|
|
|
@ -162,16 +162,16 @@ define AP_FEATURE_RTSCTS 1
@@ -162,16 +162,16 @@ define AP_FEATURE_RTSCTS 1
|
|
|
|
|
define AP_FEATURE_SBUS_OUT 1 |
|
|
|
|
|
|
|
|
|
# PWM AUX channels |
|
|
|
|
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) NODMA |
|
|
|
|
PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51) NODMA |
|
|
|
|
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) NODMA |
|
|
|
|
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) NODMA |
|
|
|
|
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) NODMA |
|
|
|
|
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) NODMA |
|
|
|
|
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) |
|
|
|
|
PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51) |
|
|
|
|
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) |
|
|
|
|
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) |
|
|
|
|
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) |
|
|
|
|
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) |
|
|
|
|
# we need to disable DMA on the last 2 FMU channels |
|
|
|
|
# as timer 12 doesn't have a TIMn_UP DMA option |
|
|
|
|
PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56) NODMA |
|
|
|
|
PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57) NODMA |
|
|
|
|
PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56) |
|
|
|
|
PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57) |
|
|
|
|
|
|
|
|
|
define BOARD_PWM_COUNT_DEFAULT 8 |
|
|
|
|
|
|
|
|
@ -281,3 +281,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
@@ -281,3 +281,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
|
|
|
|
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" |
|
|
|
|
|
|
|
|
|
ROMFS io_firmware.bin Tools/IO_Firmware/fmuv2_IO.bin |
|
|
|
|
|
|
|
|
|
# don't share IOMCU DMA |
|
|
|
|
DMA_NOSHARE UART8* |
|
|
|
|