|
|
|
@ -96,7 +96,7 @@ FLASH_SIZE_KB 2048
@@ -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%"
@@ -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. |
|
|
|
|