mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
HAL_ChibiOS: convert all hwdef from UART_ORDER to SERIAL_ORDER
much easier to understand
This commit is contained in:
parent
a52070d226
commit
32cdfddf12
libraries/AP_HAL_ChibiOS/hwdef
CUAV-Nora
CUAV-X7
CUAV_GPS
CUAVv5Nano
CubeOrange
CubeYellow
DrotekP3Pro
Durandal
F35Lightning
F4BY
KakuteF4
KakuteF7
KakuteF7Mini
MatekF405-Wing
MatekF405
MatekF765-Wing
MatekH743
NucleoH743
OMNIBUSF7V2
OmnibusNanoV6
PH4-mini
R9Pilot
SuccexF4
TBS-Colibri-F7
VRBrain-v51
VRBrain-v52
VRBrain-v54
VRCore-v10
VRUBrain-v51
ZubaxGNSS
airbotf4
crazyflie2
f103-periph
f303-periph
fmuv3
fmuv4
fmuv5
iomcu
luminousbee4
mRoControlZeroF7
mRoNexus
mRoX21-777
mindpx-v2
mini-pix
omnibusf4pro
omnibusf4v6
revo-mini
skyviper-f412-rev1
skyviper-journey
skyviper-v2450
sparky2
speedybeef4
@ -29,7 +29,7 @@ PC6 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
|
@ -21,7 +21,7 @@ STM32_ST_USE_TIMER 2
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART2 USART6 UART4 UART8 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
@ -29,7 +29,7 @@ PI6 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
|
@ -21,7 +21,7 @@ STM32_ST_USE_TIMER 2
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART2 USART6 UART4 UART8 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
@ -25,7 +25,7 @@ STDOUT_SERIAL SD1
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER
|
||||
SERIAL_ORDER
|
||||
|
||||
# use safety button to stay in bootloader
|
||||
PB3 STAY_IN_BOOTLOADER INPUT PULLDOWN
|
||||
|
@ -34,7 +34,7 @@ STDOUT_SERIAL SD1
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER USART1 USART2
|
||||
SERIAL_ORDER USART1 EMPTY EMPTY USART2
|
||||
|
||||
# a LED to flash
|
||||
PB12 LED OUTPUT LOW
|
||||
|
@ -27,7 +27,7 @@ PC7 LED_ACTIVITY OUTPUT HIGH
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 UART7
|
||||
SERIAL_ORDER OTG1 USART2 UART7
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
|
@ -13,7 +13,7 @@ undef PE3
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
||||
# order of UARTs (and USB).
|
||||
UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2
|
||||
|
||||
# enable TX on USART6 (disabled for fmuv5 with iomcu)
|
||||
PG14 USART6_TX USART6 NODMA
|
||||
|
@ -29,7 +29,7 @@ FLASH_BOOTLOADER_LOAD_KB 128
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters).
|
||||
PE7 UART7_RX UART7
|
||||
|
@ -29,7 +29,7 @@ define HAL_STORAGE_SIZE 16384
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2
|
||||
|
||||
# If the board has an IOMCU connected via a UART then this defines the
|
||||
# UART to talk to that MCU. Leave it out for boards with no IOMCU.
|
||||
|
@ -20,7 +20,7 @@ USB_STRING_PRODUCT "CubeYellow-BL"
|
||||
USB_STRING_SERIAL "%SERIAL%"
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 USART3 UART7
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART7
|
||||
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2
|
||||
|
@ -55,7 +55,7 @@ FLASH_SIZE_KB 2048
|
||||
# serial port for stdout. This is optional. If you leave it out then
|
||||
# output from printf() lines will be thrown away (you can stil use
|
||||
# hal.console->printf() for the ArduPilot console, which is the first
|
||||
# UART in the UART_ORDER list). The value for STDOUT_SERIAL is a
|
||||
# UART in the SERIAL_ORDER list). The value for STDOUT_SERIAL is a
|
||||
# serial device name, and must be for a serial device for which pins
|
||||
# are defined in this file. For example, SD7 is for UART7 (SD7 ==
|
||||
# "serial device 7" in ChibiOS).
|
||||
@ -100,7 +100,7 @@ I2C_ORDER I2C2 I2C1
|
||||
# 6) SERIAL5: extra UART (usually RTOS debug console)
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2
|
||||
|
||||
# if the board has an IOMCU connected via a UART then this defines the
|
||||
# UART to talk to that MCU. Leave it out for boards with no IOMCU
|
||||
|
@ -23,7 +23,7 @@ FLASH_BOOTLOADER_LOAD_KB 16
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# uarts and USB to run bootloader protocol on
|
||||
UART_ORDER OTG1 USART2 USART3
|
||||
SERIAL_ORDER OTG1 USART2 USART3
|
||||
|
||||
# this is the pin that senses USB being connected. It is an input pin
|
||||
# setup as OPENDRAIN
|
||||
|
@ -40,7 +40,7 @@ I2C_ORDER I2C1 I2C2
|
||||
# 6) SERIAL5: extra UART (usually RTOS debug console)
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7
|
||||
|
||||
# UART for IOMCU
|
||||
IOMCU_UART USART6
|
||||
|
@ -34,7 +34,7 @@ define HAL_LED_ON 0
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
|
@ -26,7 +26,7 @@ FLASH_RESERVE_START_KB 128
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
@ -23,7 +23,7 @@ define STORAGE_FLASH_PAGE 1
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART1 USART2 UART5
|
||||
SERIAL_ORDER OTG1 USART1 USART2 UART5
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -25,7 +25,7 @@ FLASH_RESERVE_START_KB 64
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (UART3RX used for RCInput, UART4RX and USART6RX not pinned out)
|
||||
UART_ORDER OTG1 USART2 USART1 UART5 EMPTY UART4 USART6
|
||||
SERIAL_ORDER OTG1 USART1 UART5 USART2 EMPTY UART4 USART6
|
||||
|
||||
# USB sensing
|
||||
#PA9 VBUS INPUT OPENDRAIN
|
||||
|
@ -13,7 +13,7 @@ STM32_ST_USE_TIMER 5
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2
|
||||
SERIAL_ORDER OTG1 USART2
|
||||
|
||||
PE3 LED_BOOTLOADER OUTPUT
|
||||
PE2 LED_ACTIVITY OUTPUT
|
||||
|
@ -48,7 +48,7 @@ PA14 JTCK-SWCLK SWD
|
||||
# setup as OPENDRAIN
|
||||
PA9 VBUS INPUT OPENDRAIN
|
||||
|
||||
UART_ORDER OTG1 USART3 USART2 USART1 UART5
|
||||
SERIAL_ORDER OTG1 USART2 USART1 USART3 UART5
|
||||
|
||||
# UART1 as board 2.1.5 for serial 3 gps
|
||||
PB6 USART1_TX USART1
|
||||
|
@ -23,7 +23,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -68,7 +68,7 @@ define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART6 USART1 UART5 USART3
|
||||
SERIAL_ORDER OTG1 USART6 USART1 UART4 UART5 USART3
|
||||
|
||||
# rcinput is PB11
|
||||
PB11 TIM2_CH4 TIM2 RCININT FLOAT LOW
|
||||
|
@ -23,7 +23,7 @@ FLASH_BOOTLOADER_LOAD_KB 96
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
@ -21,7 +21,7 @@ FLASH_RESERVE_START_KB 96
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB), USART3 should be in second place to map order with the board's silk screen
|
||||
UART_ORDER OTG1 USART3 USART1 USART2 UART4 UART7 USART6
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART7 USART6
|
||||
|
||||
# buzzer
|
||||
PD15 TIM4_CH4 TIM4 GPIO(77) ALARM
|
||||
|
@ -21,7 +21,7 @@ FLASH_RESERVE_START_KB 96
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB), USART3 should be in second place to map order with the board's silk screen
|
||||
UART_ORDER OTG1 USART3 USART1 USART2 UART4 EMPTY USART6 UART7
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7
|
||||
|
||||
# buzzer
|
||||
PD15 TIM4_CH4 TIM4 GPIO(77) ALARM
|
||||
|
@ -23,7 +23,7 @@ define STORAGE_FLASH_PAGE 1
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART1 USART3 UART4 UART5 USART6
|
||||
SERIAL_ORDER OTG1 USART1 USART3 UART4 UART5 USART6
|
||||
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
|
@ -43,7 +43,7 @@ define STORAGE_FLASH_PAGE 1
|
||||
I2C_ORDER I2C1 I2C2
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6 USART2
|
||||
SERIAL_ORDER OTG1 USART1 EMPTY USART3 UART4 UART5 USART6 USART2
|
||||
|
||||
#################################################
|
||||
### PIN DEFINITIONS ###
|
||||
|
@ -25,7 +25,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -22,7 +22,7 @@ FLASH_SIZE_KB 1024
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 UART4 UART5 USART2
|
||||
SERIAL_ORDER OTG1 USART3 UART4 USART1 UART5 USART2
|
||||
|
||||
# LEDs
|
||||
PB9 LED_BLUE OUTPUT LOW GPIO(0)
|
||||
|
@ -20,7 +20,7 @@ FLASH_BOOTLOADER_LOAD_KB 96
|
||||
|
||||
|
||||
# order of UARTs (and USB). Allow bootloading on USB and telem1
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 (telem1)
|
||||
PE7 UART7_RX UART7
|
||||
|
@ -23,7 +23,7 @@ define CH_CFG_ST_RESOLUTION 16
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 UART7 USART1 USART3 UART8 UART4 USART6
|
||||
SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6
|
||||
|
||||
# tonealarm support
|
||||
PB9 TIM11_CH1 TIM11 GPIO(32) ALARM
|
||||
|
@ -24,7 +24,7 @@ FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
|
||||
# order of UARTs (and USB). Allow bootloading on USB and telem1
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 (telem1)
|
||||
PE7 UART7_RX UART7 NODMA
|
||||
|
@ -94,7 +94,7 @@ define HAL_GPIO_B_LED_PIN 90
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 UART7 USART1 USART3 UART8 UART4 USART6
|
||||
SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6
|
||||
|
||||
# USART1 (telem2)
|
||||
PA10 USART1_RX USART1
|
||||
|
@ -24,7 +24,7 @@ FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
|
@ -19,7 +19,7 @@ FLASH_RESERVE_START_KB 128
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 EMPTY EMPTY UART7
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -19,7 +19,7 @@ FLASH_RESERVE_START_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 96
|
||||
|
||||
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
@ -21,7 +21,7 @@ FLASH_RESERVE_START_KB 96
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART6 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART1 USART3 USART6 USART2
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -27,7 +27,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -20,7 +20,7 @@ FLASH_RESERVE_START_KB 64
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART6 USART1 UART4
|
||||
SERIAL_ORDER OTG1 USART1 UART4 USART6
|
||||
|
||||
#adc
|
||||
PC1 BAT_CURR_SENS ADC1 SCALE(1)
|
||||
|
@ -9,7 +9,7 @@ include ../fmuv5/hwdef.dat
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
# order of UARTs (and USB). Telem2 is UART4 on the mini, USART3 is not available
|
||||
UART_ORDER OTG1 USART1 USART2 UART4 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 UART4 USART1 USART6 UART7 OTG2
|
||||
|
||||
# enable TX on USART6 (disabled for fmuv5 with iomcu)
|
||||
PG14 USART6_TX USART6 NODMA
|
||||
|
@ -20,7 +20,7 @@ FLASH_BOOTLOADER_LOAD_KB 96
|
||||
|
||||
|
||||
# order of UARTs (and USB). Allow bootloading on USB
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
@ -20,7 +20,7 @@ FLASH_RESERVE_START_KB 96
|
||||
I2C_ORDER I2C3
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART2 USART3 UART5 USART6 UART7 UART8
|
||||
SERIAL_ORDER OTG1 USART2 USART3 USART1 UART5 USART6 UART7 UART8
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
@ -27,7 +27,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -52,7 +52,7 @@ PC12 SPI3_MOSI SPI3
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# UART ports and I2C bus
|
||||
UART_ORDER OTG1 USART3 USART1 USART2 USART6
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 USART6
|
||||
|
||||
# Note that this board needs pull-ups on I2C pins
|
||||
PB8 I2C1_SCL I2C1 PULLUP
|
||||
|
@ -33,7 +33,7 @@ define HAL_LED_ON 0
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 UART7
|
||||
SERIAL_ORDER OTG1 USART2 UART7
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
|
@ -13,7 +13,7 @@ undef PE3
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
||||
# order of UARTs (and USB). Telem2 is UART4 on the mini, USART3 is not available
|
||||
UART_ORDER OTG1 USART1 USART2 UART4 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 UART4 USART1 USART6 UART7 OTG2
|
||||
|
||||
# enable TX on USART6 (disabled for fmuv5 with iomcu)
|
||||
PG14 USART6_TX USART6 NODMA
|
||||
|
@ -35,7 +35,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -29,7 +29,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
|
@ -35,7 +35,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -29,7 +29,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
|
@ -36,7 +36,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -30,7 +30,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
|
@ -35,7 +35,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -29,7 +29,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
|
@ -35,7 +35,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -29,7 +29,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
|
@ -120,7 +120,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
||||
PA2 USART2_TX USART2 SPEED_HIGH NODMA
|
||||
PA3 USART2_RX USART2 SPEED_HIGH NODMA
|
||||
|
||||
UART_ORDER
|
||||
SERIAL_ORDER
|
||||
|
||||
define HAL_STORAGE_SIZE 800
|
||||
|
||||
|
@ -91,7 +91,7 @@ PC12 SPI3_MOSI SPI3 SPEED_HIGH
|
||||
|
||||
#########################
|
||||
# order of UARTs
|
||||
UART_ORDER USART3 USART2
|
||||
SERIAL_ORDER USART3 EMPTY EMPTY USART2
|
||||
|
||||
SPIDEV ms5611 SPI3 DEVID1 BARO_CS MODE3 8*MHZ 8*MHZ
|
||||
SPIDEV lis3mdl SPI3 DEVID2 MAG_CS MODE3 500*KHZ 500*KHZ
|
||||
|
@ -27,7 +27,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -22,7 +22,7 @@ FLASH_RESERVE_START_KB 64
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART6 USART1
|
||||
SERIAL_ORDER OTG1 USART1 EMPTY USART6
|
||||
|
||||
#adc
|
||||
PC1 BAT_CURR_SENS ADC1 SCALE(1)
|
||||
|
@ -30,7 +30,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -90,7 +90,7 @@ I2C_ORDER I2C3 I2C1
|
||||
define HAL_I2C_MAX_CLOCK 400000
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 USART3 USART6
|
||||
SERIAL_ORDER OTG1 USART3 USART6 USART2
|
||||
|
||||
define HAL_STORAGE_SIZE 15360
|
||||
define STORAGE_FLASH_PAGE 1
|
||||
|
@ -25,7 +25,7 @@ STDOUT_BAUDRATE 57600
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER
|
||||
SERIAL_ORDER
|
||||
define HAL_USE_UART FALSE
|
||||
|
||||
PA4 LED_BOOTLOADER OUTPUT LOW
|
||||
|
@ -29,7 +29,7 @@ FLASH_SIZE_KB 128
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER EMPTY USART1
|
||||
SERIAL_ORDER EMPTY EMPTY EMPTY USART1
|
||||
|
||||
# a LED to flash
|
||||
PA4 LED OUTPUT LOW
|
||||
|
@ -25,7 +25,7 @@ STDOUT_BAUDRATE 57600
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER
|
||||
SERIAL_ORDER
|
||||
define HAL_USE_UART FALSE
|
||||
|
||||
PA4 LED_BOOTLOADER OUTPUT LOW
|
||||
|
@ -30,7 +30,7 @@ FLASH_SIZE_KB 256
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER USART2 USART1
|
||||
SERIAL_ORDER USART2 EMPTY EMPTY USART1
|
||||
|
||||
# a LED to flash
|
||||
PA4 LED OUTPUT LOW
|
||||
|
@ -31,7 +31,7 @@ USB_STRING_SERIAL "%SERIAL%"
|
||||
define BOOTLOADER_BAUDRATE 115200
|
||||
|
||||
# uarts and USB to run bootloader protocol on
|
||||
UART_ORDER OTG1 USART2 USART3 UART7
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART7
|
||||
|
||||
# this is the pin that senses USB being connected. It is an input pin
|
||||
# setup as OPENDRAIN
|
||||
|
@ -96,7 +96,7 @@ FLASH_SIZE_KB 2048
|
||||
|
||||
# Serial port for stdout. This is optional. If you leave it out then
|
||||
# output from printf() lines will go to the ArduPilot console, which is the
|
||||
# first UART in the UART_ORDER list. But note that some startup code
|
||||
# first UART in the SERIAL_ORDER list. But note that some startup code
|
||||
# runs before USB is set up.
|
||||
# The value for STDOUT_SERIAL is a serial device name, and must be for a
|
||||
# serial device for which pins are defined in this file. For example, SD7
|
||||
@ -125,21 +125,21 @@ USB_STRING_PRODUCT "%BOARD%"
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# Now the UART order. These map to the hal.uartA to hal.uartF
|
||||
# objects. If you use a shorter list then HAL_Empty::UARTDriver
|
||||
# Now the serial ordering. These map to the SERIALn_ parameter numbers
|
||||
# If you use a shorter list then HAL_Empty::UARTDriver
|
||||
# objects are substituted for later UARTs, or you can leave a gap by
|
||||
# listing one or more of the uarts as EMPTY.
|
||||
|
||||
# The normal usage of this ordering is:
|
||||
# 1) SERIAL0: console (primary mavlink, usually USB)
|
||||
# 2) SERIAL3: primary GPS
|
||||
# 3) SERIAL1: telem1
|
||||
# 4) SERIAL2: telem2
|
||||
# 2) SERIAL1: telem1
|
||||
# 3) SERIAL2: telem2
|
||||
# 4) SERIAL3: primary GPS
|
||||
# 5) SERIAL4: GPS2
|
||||
# 6) SERIAL5: extra UART (usually RTOS debug console)
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7
|
||||
|
||||
# If the board has an IOMCU connected via a UART then this defines the
|
||||
# UART to talk to that MCU. Leave it out for boards with no IOMCU.
|
||||
|
@ -18,7 +18,7 @@ STM32_ST_USE_TIMER 5
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2
|
||||
SERIAL_ORDER OTG1 USART2
|
||||
|
||||
PB1 LED_BOOTLOADER OUTPUT
|
||||
PB3 LED_ACTIVITY OUTPUT
|
||||
|
@ -33,7 +33,7 @@ define HAL_I2C_BUS_BASE 1
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7
|
||||
|
||||
# UART4 is GPS
|
||||
PA0 UART4_TX UART4
|
||||
|
@ -24,7 +24,7 @@ define HAL_LED_ON 0
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 UART7
|
||||
SERIAL_ORDER OTG1 USART2 UART7
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
|
@ -23,7 +23,7 @@ FLASH_SIZE_KB 2048
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
@ -20,7 +20,7 @@ FLASH_SIZE_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER EMPTY
|
||||
SERIAL_ORDER EMPTY EMPTY EMPTY EMPTY
|
||||
define HAL_USE_UART TRUE
|
||||
|
||||
# UART connected to FMU, uses DMA
|
||||
|
@ -29,7 +29,7 @@ define HAL_I2C_BUS_BASE 1
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7
|
||||
|
||||
# UART4 is GPS
|
||||
PA0 UART4_TX UART4
|
||||
|
@ -32,7 +32,7 @@ define HAL_LED_ON 0
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters).
|
||||
PE7 UART7_RX UART7
|
||||
|
@ -63,7 +63,7 @@ define HAL_I2C_INTERNAL_MASK 0
|
||||
# USART6 FC
|
||||
# UART7 DEBUG
|
||||
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART6 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
@ -34,7 +34,7 @@ define HAL_LED_ON 0
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
|
@ -38,7 +38,7 @@ I2C_ORDER I2C4
|
||||
# UART7 SERIAL1
|
||||
# OTG2 SERIAL2
|
||||
|
||||
UART_ORDER OTG1 UART4 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 UART7 OTG2 UART4
|
||||
|
||||
# UART4 SERIAL0 (GPS)
|
||||
PD0 UART4_RX UART4
|
||||
|
@ -25,7 +25,7 @@ USB_STRING_PRODUCT "X2.1-777"
|
||||
USB_STRING_SERIAL "%SERIAL%"
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 USART3 UART7
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART7
|
||||
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2
|
||||
|
@ -61,7 +61,7 @@ env OPTIMIZE -O2
|
||||
# serial port for stdout. This is optional. If you leave it out then
|
||||
# output from printf() lines will be thrown away (you can stil use
|
||||
# hal.console->printf() for the ArduPilot console, which is the first
|
||||
# UART in the UART_ORDER list). The value for STDOUT_SERIAL is a
|
||||
# UART in the SERIAL_ORDER list). The value for STDOUT_SERIAL is a
|
||||
# serial device name, and must be for a serial device for which pins
|
||||
# are defined in this file. For example, SD7 is for UART7 (SD7 ==
|
||||
# "serial device 7" in ChibiOS).
|
||||
@ -99,7 +99,7 @@ I2C_ORDER I2C1
|
||||
# 6) SERIAL5: extra UART (usually RTOS debug console)
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
@ -25,7 +25,7 @@ FLASH_BOOTLOADER_LOAD_KB 16
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2
|
||||
SERIAL_ORDER OTG1 USART2
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -31,7 +31,7 @@ FLASH_RESERVE_END_KB 0
|
||||
I2C_ORDER I2C1 I2C2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7 USART6
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7 USART6
|
||||
|
||||
# UART4 is GPS
|
||||
PA0 UART4_TX UART4
|
||||
|
@ -29,7 +29,7 @@ FLASH_BOOTLOADER_LOAD_KB 16
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# USB pins
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
@ -24,7 +24,7 @@ FLASH_SIZE_KB 1024
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART3 USART2 USART6
|
||||
SERIAL_ORDER OTG1 USART3 USART2 UART4 USART6
|
||||
|
||||
# UART4 serial GPS
|
||||
PA0 UART4_TX UART4
|
||||
|
@ -27,7 +27,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -22,7 +22,7 @@ FLASH_RESERVE_START_KB 64
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART6 USART1 USART3 UART4
|
||||
SERIAL_ORDER OTG1 USART1 USART3 USART6 UART4
|
||||
|
||||
#adc
|
||||
PC1 BAT_CURR_SENS ADC1 SCALE(1)
|
||||
|
@ -27,7 +27,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -24,7 +24,7 @@ I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs
|
||||
|
||||
UART_ORDER OTG1 USART6 USART1 UART4 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART1 UART4 USART6 USART3 USART2
|
||||
|
||||
|
||||
#PINS
|
||||
|
@ -28,7 +28,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -23,7 +23,7 @@ FLASH_SIZE_KB 1024
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART3 USART1
|
||||
SERIAL_ORDER OTG1 USART1 EMPTY USART3
|
||||
|
||||
# rcinput is PC6, which is the 3rd "PWM IN" pin (the yellow wire on a
|
||||
# revolution board)
|
||||
|
@ -33,7 +33,7 @@ STDOUT_BAUDRATE 115200
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER USART2 USART6 USART3
|
||||
SERIAL_ORDER USART2 USART3 EMPTY USART6
|
||||
|
||||
PC0 MGND ADC1
|
||||
PC1 PWM4_SENSE ADC1
|
||||
|
@ -39,7 +39,7 @@ define HAL_I2C_MAX_CLOCK 400000
|
||||
define APM_I2C_PRIORITY 181
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER USART1 USART6 USART2
|
||||
SERIAL_ORDER USART1 USART2 EMPTY USART6
|
||||
|
||||
PC0 MGND ADC1
|
||||
PC1 PWM4_SENSE ADC1
|
||||
|
@ -27,7 +27,7 @@ undef SDIO
|
||||
undef HAL_BOARD_LOG_DIRECTORY
|
||||
undef HAL_BOARD_TERRAIN_DIRECTORY
|
||||
|
||||
UART_ORDER OTG1 UART4 USART2
|
||||
SERIAL_ORDER OTG1 USART2 EMPTY UART4
|
||||
|
||||
# enable AP_Radio support
|
||||
define HAL_RCINPUT_WITH_AP_RADIO 1
|
||||
|
@ -28,7 +28,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -45,7 +45,7 @@ PA8 VBUS INPUT OPENDRAIN
|
||||
|
||||
# ---------UARTS-----------
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3
|
||||
SERIAL_ORDER OTG1 USART3 EMPTY USART1
|
||||
|
||||
# Main PORT
|
||||
PA9 USART1_TX USART1
|
||||
|
@ -27,7 +27,7 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -21,7 +21,7 @@ FLASH_SIZE_KB 1024
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART3 USART1 UART4 UART5
|
||||
SERIAL_ORDER OTG1 USART1 UART4 USART3 UART5
|
||||
|
||||
# LEDs
|
||||
PB9 LED_BLUE OUTPUT LOW GPIO(0)
|
||||
|
Loading…
Reference in New Issue
Block a user