mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_ChibiOS: normalize SerialManagers ports defaults to allow inclusion in hwdefs
This commit is contained in:
parent
8ac9a7561c
commit
d0ac8f3016
@ -38,8 +38,10 @@
|
||||
|
||||
#include <hwdef.h>
|
||||
|
||||
#ifndef HAL_SERIAL0_BAUD_DEFAULT
|
||||
#define HAL_SERIAL0_BAUD_DEFAULT 115200
|
||||
#ifndef DEFAULT_SERIAL0_BAUD
|
||||
#define SERIAL0_BAUD 115200
|
||||
#else
|
||||
#define SERIAL0_BAUD DEFAULT_SERIAL0_BAUD
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
@ -223,7 +225,7 @@ static void main_loop()
|
||||
|
||||
peripheral_power_enable();
|
||||
|
||||
hal.serial(0)->begin(HAL_SERIAL0_BAUD_DEFAULT);
|
||||
hal.serial(0)->begin(SERIAL0_BAUD);
|
||||
|
||||
#ifdef HAL_SPI_CHECK_CLOCK_FREQ
|
||||
// optional test of SPI clock frequencies
|
||||
|
@ -86,12 +86,12 @@ PA3 USART2_RX USART2 NODMA ALT(1)
|
||||
# USART3
|
||||
PC10 USART3_TX USART3
|
||||
PC11 USART3_RX USART3
|
||||
define HAL_SERIAL3_PROTOCOL 0
|
||||
define DEFAULT_SERIAL3_PROTOCOL 0
|
||||
|
||||
# UART4 GPS
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
define HAL_SERIAL4_PROTOCOL 5
|
||||
define DEFAULT_SERIAL4_PROTOCOL 5
|
||||
|
||||
# UART5 for DJI OSD
|
||||
PD2 UART5_RX UART5 NODMA
|
||||
|
@ -81,7 +81,7 @@ PA3 USART2_RX USART2 NODMA
|
||||
|
||||
# USART3 (DJI RCIN)
|
||||
PB11 USART3_RX USART3
|
||||
define HAL_SERIAL3_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# UART4
|
||||
PA0 UART4_TX UART4
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
include ../BeastF7/hwdef.dat
|
||||
undef APJ_BOARD_ID
|
||||
undef HAL_SERIAL3_PROTOCOL
|
||||
undef DEFAULT_SERIAL3_PROTOCOL
|
||||
undef IMU
|
||||
undef BARO
|
||||
undef PD15
|
||||
@ -36,7 +36,7 @@ PA9 USART1_TX USART1 NODMA
|
||||
# USART2 (DJI RCIN)
|
||||
PA3 USART2_RX USART2
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART3 (RCIN)
|
||||
PB11 USART3_RX USART3
|
||||
|
@ -82,7 +82,7 @@ PA3 USART2_RX USART2
|
||||
|
||||
# USART3 (DJI RCIN)
|
||||
PB11 USART3_RX USART3
|
||||
define HAL_SERIAL3_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# UART4
|
||||
PA0 UART4_TX UART4
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
include ../BeastH7/hwdef.dat
|
||||
undef APJ_BOARD_ID
|
||||
undef HAL_SERIAL3_PROTOCOL
|
||||
undef DEFAULT_SERIAL3_PROTOCOL
|
||||
undef IMU
|
||||
undef BARO
|
||||
undef PD15
|
||||
@ -36,7 +36,7 @@ PA9 USART1_TX USART1 NODMA
|
||||
# USART2 (DJI RCIN)
|
||||
PA3 USART2_RX USART2
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART3 (RCIN)
|
||||
PB11 USART3_RX USART3
|
||||
|
@ -45,7 +45,7 @@ PB5 TIM3_CH2 TIM3 PWM(4) GPIO(53)
|
||||
# USART1 for debug
|
||||
# PA15 USART1_TX USART1
|
||||
# PB3 USART1_RX USART1
|
||||
# define HAL_SERIAL0_BAUD_DEFAULT 57600
|
||||
# define DEFAULT_SERIAL0_BAUD 57600
|
||||
|
||||
# ------ end RCOUT pins ------
|
||||
|
||||
|
@ -42,7 +42,7 @@ PB0 LED OUTPUT LOW
|
||||
# USART1 for debug
|
||||
PB6 USART1_TX USART1 NODMA
|
||||
PB7 USART1_RX USART1 NODMA
|
||||
define HAL_SERIAL0_BAUD_DEFAULT 57600
|
||||
define DEFAULT_SERIAL0_BAUD 57600
|
||||
|
||||
# USART2 for GPS
|
||||
PA2 USART2_TX USART2
|
||||
|
@ -41,7 +41,7 @@ PB12 LED OUTPUT LOW
|
||||
# USART1 for debug
|
||||
PB6 USART1_TX USART1 NODMA
|
||||
PB7 USART1_RX USART1 NODMA
|
||||
define HAL_SERIAL0_BAUD_DEFAULT 57600
|
||||
define DEFAULT_SERIAL0_BAUD 57600
|
||||
|
||||
# USART2 for GPS
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
|
@ -272,5 +272,5 @@ INT_FLASH_PRIMARY 1
|
||||
# forward Serial traffic from USB OTG2 to Serial7(UART7)
|
||||
define HAL_FORWARD_OTG2_SERIAL 7
|
||||
define HAL_HAVE_DUAL_USB_CDC 1
|
||||
define HAL_SERIAL7_PROTOCOL SerialProtocol_MAVLink2
|
||||
define HAL_SERIAL7_BAUD 2000000
|
||||
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_MAVLink2
|
||||
define DEFAULT_SERIAL7_BAUD 2000000
|
||||
|
@ -146,10 +146,10 @@ PD3 USART2_CTS USART2 SPEED_HIGH
|
||||
SERIAL_ORDER UART7 UART8 USART3 USART6 UART4 USART2
|
||||
|
||||
# use 2 MBaud when talking to primary controller
|
||||
define HAL_SERIAL0_BAUD_DEFAULT 2000000
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
define HAL_SERIAL3_PROTOCOL SerialProtocol_Sbus1
|
||||
define HAL_SERIAL4_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL0_BAUD 2000000
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Sbus1
|
||||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
|
||||
# only use pulse input for PPM, other protocols
|
||||
|
@ -75,7 +75,7 @@ PB14 USART1_TX USART1
|
||||
# USART2 (RCIN)
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2 ALT(1)
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART3
|
||||
PD9 USART3_RX USART3
|
||||
|
@ -239,8 +239,8 @@ define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
|
||||
# setup serial port defaults for ESP8266
|
||||
define HAL_SERIAL5_PROTOCOL SerialProtocol_MAVLink2
|
||||
define HAL_SERIAL5_BAUD 921600
|
||||
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_MAVLink2
|
||||
define DEFAULT_SERIAL5_BAUD 921600
|
||||
|
||||
# We can't share the IO UART (USART6).
|
||||
DMA_NOSHARE USART6_TX USART6_RX ADC1
|
||||
|
@ -54,12 +54,12 @@ PA12 OTG_FS_DP OTG1
|
||||
# USART1 (ELRS)
|
||||
PA10 USART1_RX USART1
|
||||
PB6 USART1_TX USART1
|
||||
define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART2 (GPS)
|
||||
PD5 USART2_TX USART2 NODMA
|
||||
PD6 USART2_RX USART2
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_GPS
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_GPS
|
||||
|
||||
# USART3 (RX)
|
||||
PB10 USART3_TX USART3
|
||||
|
@ -59,21 +59,25 @@ PA12 OTG_FS_DP OTG1
|
||||
# USART1 (RX/SBUS)
|
||||
PA10 USART1_RX USART1
|
||||
PA9 USART1_TX USART1
|
||||
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
|
||||
# USART2 (VTX)
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
PA3 USART2_RX USART2 NODMA
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_Tramp
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_Tramp
|
||||
|
||||
|
||||
# USART3
|
||||
PB10 USART3_TX USART3
|
||||
PB11 USART3_RX USART3
|
||||
define HAL_SERIAL3_PROTOCOL SerialProtocol_None
|
||||
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None
|
||||
|
||||
|
||||
# UART4 (DJI RX/SBUS)
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4
|
||||
define HAL_SERIAL4_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART6 (GPS)
|
||||
PC6 USART6_TX USART6
|
||||
@ -81,6 +85,7 @@ 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
|
||||
@ -90,8 +95,8 @@ define HAL_SERIAL7_BAUD 115
|
||||
# UART8 (ESC)
|
||||
PE0 UART8_RX UART8 NODMA
|
||||
PE1 UART8_TX UART8 NODMA
|
||||
define HAL_SERIAL8_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define HAL_SERIAL8_BAUD 115
|
||||
define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define DEFAULT_SERIAL8_BAUD 115
|
||||
|
||||
# I2C ports
|
||||
I2C_ORDER I2C1
|
||||
|
@ -34,7 +34,7 @@ STM32_VDD 330U
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 OTG2 EMPTY USART3 UART7
|
||||
|
||||
define HAL_SERIAL0_PROTOCOL SerialProtocol_None
|
||||
define DEFAULT_SERIAL0_PROTOCOL SerialProtocol_None
|
||||
|
||||
# USART3 F9
|
||||
PD9 USART3_RX USART3
|
||||
|
@ -8,13 +8,13 @@
|
||||
include ../JHEMCU-GSF405A/hwdef.dat
|
||||
|
||||
undef PD5 PD6 PB10 PB11 PA3 PA2
|
||||
undef HAL_SERIAL1_PROTOCOL
|
||||
undef DEFAULT_SERIAL1_PROTOCOL
|
||||
|
||||
# USART2 - SBUS pad
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2
|
||||
# default Serial2 to RCIN
|
||||
define HAL_SERIAL2_PROTOCOL 23
|
||||
define DEFAULT_SERIAL2_PROTOCOL 23
|
||||
|
||||
# USART3
|
||||
PB10 USART3_TX USART3 NODMA
|
||||
|
@ -37,7 +37,7 @@ PA8 VBUS INPUT OPENDRAIN
|
||||
PB6 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
# default Serial1 to ELRS RX
|
||||
define HAL_SERIAL1_PROTOCOL 23
|
||||
define DEFAULT_SERIAL1_PROTOCOL 23
|
||||
define HAL_RSSI_TYPE 3
|
||||
|
||||
# USART2
|
||||
|
@ -83,7 +83,7 @@ PA9 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
|
||||
# default Serial2 to FrSky telemetry
|
||||
define HAL_SERIAL2_PROTOCOL 10
|
||||
define DEFAULT_SERIAL2_PROTOCOL 10
|
||||
|
||||
# USART6, telem1, SERIAL1
|
||||
PC6 USART6_TX USART6
|
||||
|
@ -8,7 +8,7 @@ undef PB0 PB1 PA3 PA2 PB11 PB10 PD2 PC8
|
||||
undef SERIAL_ORDER
|
||||
undef CH_CFG_ST_RESOLUTION
|
||||
undef STM32_ST_USE_TIMER
|
||||
undef HAL_SERIAL2_PROTOCOL
|
||||
undef DEFAULT_SERIAL2_PROTOCOL
|
||||
|
||||
APJ_BOARD_ID 1030
|
||||
|
||||
@ -20,9 +20,9 @@ SERIAL_ORDER OTG1 USART1 EMPTY USART3 UART4 UART5 USART6
|
||||
PB11 USART3_RX USART3
|
||||
PB10 USART3_TX USART3
|
||||
|
||||
define HAL_SERIAL3_PROTOCOL SerialProtocol_RCIN
|
||||
define HAL_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define HAL_SERIAL5_BAUD 115
|
||||
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define DEFAULT_SERIAL5_BAUD 115
|
||||
|
||||
# UART5 (ESC telemetry sensor), SERIAL5, NODMA for bi-dir dshot
|
||||
PD2 UART5_RX UART5 NODMA
|
||||
|
@ -94,8 +94,8 @@ PA1 UART4_RX UART4 NODMA
|
||||
# RC input defaults to UART to allow for bi-dir dshot
|
||||
PC6 USART6_TX USART6
|
||||
PC7 USART6_RX USART6
|
||||
define HAL_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
define HAL_SERIAL6_BAUD 115
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL6_BAUD 115
|
||||
|
||||
# UART7, RX only for ESC Telemetry
|
||||
# No DMA because SPI2 requires the DMA slot
|
||||
|
@ -7,10 +7,10 @@ undef PB0 PB1 PB3 PB10 PC7
|
||||
# Must use USART6 for RCIN rather than RCINT as timer needed for bi-dir dshot
|
||||
PC7 USART6_RX USART6 NODMA
|
||||
|
||||
define HAL_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
define HAL_SERIAL6_BAUD 115
|
||||
define HAL_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define HAL_SERIAL7_BAUD 115
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL6_BAUD 115
|
||||
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define DEFAULT_SERIAL7_BAUD 115
|
||||
|
||||
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR
|
||||
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51)
|
||||
|
@ -111,10 +111,10 @@ PC6 USART6_TX USART6
|
||||
# UART7 used by ESC, TX is not connected
|
||||
PE7 UART7_RX UART7 NODMA
|
||||
|
||||
define HAL_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
define HAL_SERIAL6_BAUD 115
|
||||
define HAL_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define HAL_SERIAL7_BAUD 115
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL6_BAUD 115
|
||||
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define DEFAULT_SERIAL7_BAUD 115
|
||||
|
||||
# Motors
|
||||
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR
|
||||
|
@ -129,10 +129,10 @@ PE7 UART7_RX UART7
|
||||
PE1 UART8_TX UART8 NODMA
|
||||
PE0 UART8_RX UART8 NODMA
|
||||
|
||||
define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
define HAL_SERIAL1_BAUD 115
|
||||
define HAL_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define HAL_SERIAL6_BAUD 115
|
||||
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL1_BAUD 115
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define DEFAULT_SERIAL6_BAUD 115
|
||||
|
||||
# Motors
|
||||
PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) BIDIR
|
||||
|
@ -207,8 +207,8 @@ define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
|
||||
# setup serial port defaults for ESP8266
|
||||
define HAL_SERIAL5_PROTOCOL SerialProtocol_MAVLink2
|
||||
define HAL_SERIAL5_BAUD 921600
|
||||
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_MAVLink2
|
||||
define DEFAULT_SERIAL5_BAUD 921600
|
||||
|
||||
# two IMUs
|
||||
IMU Invensense SPI:icm20608 ROTATION_ROLL_180_YAW_90
|
||||
|
@ -50,8 +50,8 @@ PB7 USART1_RX USART1
|
||||
PD5 USART2_TX USART2 NODMA
|
||||
PD6 USART2_RX USART2
|
||||
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_MAVLink2
|
||||
define HAL_SERIAL2_BAUD 921600
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_MAVLink2
|
||||
define DEFAULT_SERIAL2_BAUD 921600
|
||||
|
||||
# USART3 for gps1
|
||||
PD8 USART3_TX USART3 NODMA
|
||||
|
@ -83,7 +83,7 @@ PA10 USART1_RX USART1 NODMA
|
||||
# USART2 (RX)
|
||||
PA2 USART2_TX USART2
|
||||
PA3 USART2_RX USART2
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART3
|
||||
PB10 USART3_TX USART3 NODMA
|
||||
|
@ -93,7 +93,7 @@ define HAL_BATT_MONITOR_DEFAULT 4
|
||||
# USART1 (RCIN)
|
||||
PB15 USART1_RX USART1
|
||||
PB14 USART1_TX USART1
|
||||
define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART2 (SmartPort)
|
||||
PD5 USART2_TX USART2
|
||||
|
@ -75,7 +75,7 @@ SERIAL_ORDER USART1 EMPTY EMPTY USART2
|
||||
# USART1 for debug
|
||||
PA9 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
define HAL_SERIAL0_BAUD_DEFAULT 57600
|
||||
define DEFAULT_SERIAL0_BAUD 57600
|
||||
|
||||
# USART2 M9N
|
||||
PA2 USART2_TX USART2 SPEED_HIGH
|
||||
@ -130,3 +130,4 @@ PC7 M9SB INPUT
|
||||
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
||||
|
||||
define DEFAULT_NTF_LED_TYPES 455
|
||||
|
||||
|
@ -40,7 +40,7 @@ SERIAL_ORDER USART1 EMPTY EMPTY USART2
|
||||
# USART1 for debug
|
||||
PA9 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
define HAL_SERIAL0_BAUD_DEFAULT 57600
|
||||
define DEFAULT_SERIAL0_BAUD 57600
|
||||
|
||||
# Enable the sensor voltage pin
|
||||
PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
||||
@ -133,3 +133,4 @@ PC8 GPS_PPS_IN INPUT
|
||||
PC7 M9SB INPUT
|
||||
|
||||
define DEFAULT_NTF_LED_TYPES 455
|
||||
|
||||
|
@ -40,7 +40,7 @@ SERIAL_ORDER USART1 EMPTY EMPTY USART2
|
||||
# USART1 for debug
|
||||
PA9 USART1_TX USART1 NODMA
|
||||
PA10 USART1_RX USART1 NODMA
|
||||
define HAL_SERIAL0_BAUD_DEFAULT 57600
|
||||
define DEFAULT_SERIAL0_BAUD 57600
|
||||
|
||||
# USART2 for GPS
|
||||
PA2 USART2_TX USART2 SPEED_HIGH
|
||||
|
@ -5,7 +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
|
||||
undef DEFAULT_SERIAL6_PROTOCOL DEFAULT_SERIAL6_BAUD
|
||||
|
||||
MCU_CLOCKRATE_MHZ 480
|
||||
|
||||
@ -21,8 +21,8 @@ define RELAY3_PIN_DEFAULT 82 # PIN-EN
|
||||
define HAL_FRAME_TYPE_DEFAULT 12
|
||||
|
||||
# USART1 (RX)
|
||||
define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
define HAL_SERIAL1_BAUD 115
|
||||
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL1_BAUD 115
|
||||
# USART3 (ESC Telem)
|
||||
PD8 USART3_TX USART3 NODMA
|
||||
PD9 USART3_RX USART3 NODMA
|
||||
@ -31,8 +31,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
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_DJI_FPV
|
||||
define DEFAULT_SERIAL6_BAUD 115
|
||||
# UART7
|
||||
# UART8
|
||||
PE0 UART8_RX UART8 NODMA
|
||||
|
@ -156,8 +156,8 @@ PE8 UART7_TX UART7
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
define HAL_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
define HAL_SERIAL6_BAUD 115
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL6_BAUD 115
|
||||
|
||||
# Motors
|
||||
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50)
|
||||
|
@ -108,7 +108,7 @@ PD2 UART5_RX UART5 NODMA
|
||||
# UART6 (onboard Telemetry)
|
||||
PC6 USART6_TX USART6
|
||||
PC7 USART6_RX USART6
|
||||
define HAL_SERIAL6_BAUD 115
|
||||
define DEFAULT_SERIAL6_BAUD 115
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
@ -169,8 +169,8 @@ define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
|
||||
# setup serial port defaults for ESP8266
|
||||
define HAL_SERIAL5_PROTOCOL SerialProtocol_MAVLink2
|
||||
define HAL_SERIAL5_BAUD 921600
|
||||
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_MAVLink2
|
||||
define DEFAULT_SERIAL5_BAUD 921600
|
||||
|
||||
# Set one or two IMUs
|
||||
#IMU Invensense SPI:icm20608 ROTATION_YAW_180
|
||||
|
@ -206,8 +206,8 @@ define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
|
||||
# setup serial port defaults for ESP8266
|
||||
define HAL_SERIAL5_PROTOCOL SerialProtocol_MAVLink
|
||||
define HAL_SERIAL5_BAUD 921600
|
||||
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_MAVLink
|
||||
define DEFAULT_SERIAL5_BAUD 921600
|
||||
|
||||
# two IMUs
|
||||
#IMU Invensense SPI:icm20608 ROTATION_YAW_180
|
||||
|
@ -174,8 +174,8 @@ define HAL_SPEKTRUM_PWR_ENABLED 1
|
||||
|
||||
# setup for RCIN on USUART6, will auto-baud for 100000 and 115200 and
|
||||
# auto-switch inversion as needed
|
||||
define HAL_SERIAL6_PROTOCOL 23
|
||||
define HAL_SERIAL6_BAUD 115200
|
||||
define DEFAULT_SERIAL6_PROTOCOL 23
|
||||
define DEFAULT_SERIAL6_BAUD 115200
|
||||
|
||||
# UART7 Telem 1, TELEM_UART_4W
|
||||
PE7 UART7_RX UART7
|
||||
|
@ -1913,8 +1913,8 @@ INCLUDE common.ld
|
||||
#ifndef HAL_OTG2_PROTOCOL
|
||||
#define HAL_OTG2_PROTOCOL SerialProtocol_SLCAN
|
||||
#endif
|
||||
#define HAL_SERIAL%d_PROTOCOL HAL_OTG2_PROTOCOL
|
||||
#define HAL_SERIAL%d_BAUD 115200
|
||||
#define DEFAULT_SERIAL%d_PROTOCOL HAL_OTG2_PROTOCOL
|
||||
#define DEFAULT_SERIAL%d_BAUD 115200
|
||||
#endif
|
||||
''' % (OTG2_index, OTG2_index))
|
||||
|
||||
@ -3000,10 +3000,10 @@ INCLUDE common.ld
|
||||
#endif
|
||||
|
||||
// default to no protocols, AP_Periph enables with params
|
||||
#define HAL_SERIAL1_PROTOCOL -1
|
||||
#define HAL_SERIAL2_PROTOCOL -1
|
||||
#define HAL_SERIAL3_PROTOCOL -1
|
||||
#define HAL_SERIAL4_PROTOCOL -1
|
||||
#define DEFAULT_SERIAL1_PROTOCOL -1
|
||||
#define DEFAULT_SERIAL2_PROTOCOL -1
|
||||
#define DEFAULT_SERIAL3_PROTOCOL -1
|
||||
#define DEFAULT_SERIAL4_PROTOCOL -1
|
||||
|
||||
#ifndef HAL_LOGGING_MAVLINK_ENABLED
|
||||
#define HAL_LOGGING_MAVLINK_ENABLED 0
|
||||
|
@ -67,34 +67,34 @@ define BOARD_RSSI_ANA_PIN 12
|
||||
# USART1 (DJI / VTX)
|
||||
PA9 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
define HAL_SERIAL1_PROTOCOL SerialProtocol_DJI_FPV
|
||||
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_DJI_FPV
|
||||
|
||||
# USART2 (RCIN)
|
||||
PA2 USART2_TX USART2
|
||||
PA3 USART2_RX USART2
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART3 (CAM)
|
||||
PC10 USART3_TX USART3 NODMA
|
||||
PC11 USART3_RX USART3 NODMA
|
||||
define HAL_SERIAL3_PROTOCOL SerialProtocol_None
|
||||
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None
|
||||
|
||||
# UART4 (Bluetooth)
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
define HAL_SERIAL4_PROTOCOL SerialProtocol_None
|
||||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None
|
||||
|
||||
# UART5 (ESC Telemetry)
|
||||
PC12 UART5_TX UART5 NODMA
|
||||
PD2 UART5_RX UART5 NODMA
|
||||
define HAL_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define HAL_SERIAL5_BAUD 19200
|
||||
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define DEFAULT_SERIAL5_BAUD 19200
|
||||
|
||||
# UART6 (GPS)
|
||||
PC6 USART6_TX USART6
|
||||
PC7 USART6_RX USART6
|
||||
define HAL_SERIAL6_PROTOCOL SerialProtocol_GPS
|
||||
define HAL_SERIAL6_BAUD AP_SERIALMANAGER_GPS_BAUD
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_GPS
|
||||
define DEFAULT_SERIAL6_BAUD AP_SERIALMANAGER_GPS_BAUD
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
Loading…
Reference in New Issue
Block a user