|
|
|
@ -23,7 +23,7 @@ FLASH_SIZE_KB 1024
@@ -23,7 +23,7 @@ FLASH_SIZE_KB 1024
|
|
|
|
|
I2C_ORDER I2C1 I2C2 |
|
|
|
|
|
|
|
|
|
# order of UARTs (and USB) |
|
|
|
|
SERIAL_ORDER OTG1 USART1 EMPTY USART6 |
|
|
|
|
SERIAL_ORDER OTG1 USART1 USART3 USART6 USART2 UART4 |
|
|
|
|
|
|
|
|
|
# rcinput is PB14, which is the 1st "PWM IN" pin (the white wire on a |
|
|
|
|
# revolution board) |
|
|
|
@ -53,14 +53,34 @@ PB4 LED_RED OUTPUT LOW GPIO(2)
@@ -53,14 +53,34 @@ PB4 LED_RED OUTPUT LOW GPIO(2)
|
|
|
|
|
PC6 USART6_TX USART6 |
|
|
|
|
PC7 USART6_RX USART6 |
|
|
|
|
|
|
|
|
|
# flexi port for USART3, alternative config |
|
|
|
|
#PB10 USART3_TX USART3 |
|
|
|
|
#PB11 USART3_RX USART3 |
|
|
|
|
# USART3 (SERIAL2) on flexi port in BRD_ALT_CONFIG = 3 & 4 & 5 |
|
|
|
|
PB10 USART3_TX USART3 ALT(3) |
|
|
|
|
PB11 USART3_RX USART3 ALT(3) |
|
|
|
|
PB10 USART3_TX USART3 ALT(4) |
|
|
|
|
PB11 USART3_RX USART3 ALT(4) |
|
|
|
|
PB10 USART3_TX USART3 ALT(5) |
|
|
|
|
PB11 USART3_RX USART3 ALT(5) |
|
|
|
|
|
|
|
|
|
# main port, for telem1 |
|
|
|
|
PA9 USART1_TX USART1 |
|
|
|
|
PA10 USART1_RX USART1 |
|
|
|
|
|
|
|
|
|
# USART2 = SERIAL4 Rx & Tx on PWMOutput pins 3 & 4 in BRD_ALT_CONFIG = 1 & 2 & 4 & 5 |
|
|
|
|
PA2 USART2_TX USART2 ALT(1) |
|
|
|
|
PA3 USART2_RX USART2 ALT(1) |
|
|
|
|
PA2 USART2_TX USART2 ALT(2) |
|
|
|
|
PA3 USART2_RX USART2 ALT(2) |
|
|
|
|
PA2 USART2_TX USART2 ALT(4) |
|
|
|
|
PA3 USART2_RX USART2 ALT(4) |
|
|
|
|
PA2 USART2_TX USART2 ALT(5) |
|
|
|
|
PA3 USART2_RX USART2 ALT(5) |
|
|
|
|
|
|
|
|
|
# UART4 = SERIAL5 Rx & Tx on PWMOutput pins 5 & 6 in BRD_ALT_CONFIG = 2 & 5 |
|
|
|
|
PA0 UART4_TX UART4 ALT(2) |
|
|
|
|
PA1 UART4_RX UART4 ALT(2) |
|
|
|
|
PA0 UART4_TX UART4 ALT(5) |
|
|
|
|
PA1 UART4_RX UART4 ALT(5) |
|
|
|
|
|
|
|
|
|
# flexi port, for external I2C |
|
|
|
|
PB10 I2C2_SCL I2C2 |
|
|
|
|
PB11 I2C2_SDA I2C2 |
|
|
|
@ -100,9 +120,8 @@ PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
@@ -100,9 +120,8 @@ PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
|
|
|
|
|
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) |
|
|
|
|
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(54) |
|
|
|
|
PA0 TIM2_CH1 TIM2 PWM(6) GPIO(55) |
|
|
|
|
# disable last two channels as conflicts with TIM8 for RCIN |
|
|
|
|
#PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) |
|
|
|
|
#PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) |
|
|
|
|
PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) |
|
|
|
|
PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) |
|
|
|
|
|
|
|
|
|
PB7 DRDY_HMC5883 INPUT PULLUP |
|
|
|
|
|
|
|
|
@ -132,6 +151,5 @@ SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
@@ -132,6 +151,5 @@ SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
|
|
|
|
|
define HAL_LOGGING_DATAFLASH |
|
|
|
|
|
|
|
|
|
# 6 PWM available by default |
|
|
|
|
define BOARD_PWM_COUNT_DEFAULT 6 |
|
|
|
|
define BOARD_PWM_COUNT_DEFAULT 8 |
|
|
|
|
define HAL_WITH_DSP FALSE |
|
|
|
|
|
|
|
|
|