mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_HAL_ChibiOS: support uartI, allowing a total of 9 uarts
this allows for OTG2 on the MatekH743 board, which makes SLCAN much easier
This commit is contained in:
parent
52b8b95a72
commit
4d171ec19a
@ -45,6 +45,7 @@ static HAL_UARTE_DRIVER;
|
||||
static HAL_UARTF_DRIVER;
|
||||
static HAL_UARTG_DRIVER;
|
||||
static HAL_UARTH_DRIVER;
|
||||
static HAL_UARTI_DRIVER;
|
||||
#else
|
||||
static Empty::UARTDriver uartADriver;
|
||||
static Empty::UARTDriver uartBDriver;
|
||||
@ -54,6 +55,7 @@ static Empty::UARTDriver uartEDriver;
|
||||
static Empty::UARTDriver uartFDriver;
|
||||
static Empty::UARTDriver uartGDriver;
|
||||
static Empty::UARTDriver uartHDriver;
|
||||
static Empty::UARTDriver uartIDriver;
|
||||
#endif
|
||||
|
||||
#if HAL_USE_I2C == TRUE && defined(HAL_I2C_DEVICE_LIST)
|
||||
@ -124,6 +126,7 @@ HAL_ChibiOS::HAL_ChibiOS() :
|
||||
&uartFDriver,
|
||||
&uartGDriver,
|
||||
&uartHDriver,
|
||||
&uartIDriver,
|
||||
&i2cDeviceManager,
|
||||
&spiDeviceManager,
|
||||
&analogIn,
|
||||
|
@ -25,8 +25,8 @@
|
||||
#define RX_BOUNCE_BUFSIZE 64U
|
||||
#define TX_BOUNCE_BUFSIZE 64U
|
||||
|
||||
// enough for uartA to uartH, plus IOMCU
|
||||
#define UART_MAX_DRIVERS 9
|
||||
// enough for uartA to uartI, plus IOMCU
|
||||
#define UART_MAX_DRIVERS 10
|
||||
|
||||
class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
|
||||
public:
|
||||
|
@ -23,7 +23,7 @@ define CH_CFG_ST_RESOLUTION 16
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6
|
||||
SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6 UART5
|
||||
|
||||
# tonealarm support
|
||||
PB9 TIM11_CH1 TIM11 GPIO(32) ALARM
|
||||
@ -108,8 +108,8 @@ PD8 USART3_TX USART3 NODMA
|
||||
PD1 UART4_TX UART4 NODMA
|
||||
PD0 UART4_RX UART4 NODMA
|
||||
|
||||
# UART5 (RX only, for ESC telem), disabled for now until we add uartH support
|
||||
# PB8 UART5_RX UART5 NODMA
|
||||
# UART5 (RX only, for ESC telem)
|
||||
PB8 UART5_RX UART5 NODMA
|
||||
|
||||
# USART6 (RC input), SERIAL7
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
|
@ -97,7 +97,7 @@ define HAL_GPIO_B_LED_PIN 90
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6
|
||||
SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6 OTG2
|
||||
|
||||
# USART1 (telem2)
|
||||
PA10 USART1_RX USART1
|
||||
|
@ -1154,7 +1154,7 @@ def write_UART_config(f):
|
||||
f.write('\n// UART configuration\n')
|
||||
|
||||
# write out driver declarations for HAL_ChibOS_Class.cpp
|
||||
devnames = "ABCDEFGH"
|
||||
devnames = "ABCDEFGHI"
|
||||
sdev = 0
|
||||
idx = 0
|
||||
num_empty_uarts = 0
|
||||
@ -1262,8 +1262,8 @@ def write_UART_config(f):
|
||||
num_uarts = len(devlist)
|
||||
if 'IOMCU_UART' in config:
|
||||
num_uarts -= 1
|
||||
if num_uarts > 8:
|
||||
error("Exceeded max num UARTs of 8 (%u)" % num_uarts)
|
||||
if num_uarts > 9:
|
||||
error("Exceeded max num UARTs of 9 (%u)" % num_uarts)
|
||||
f.write('#define HAL_UART_NUM_SERIAL_PORTS %u\n' % (num_uarts+num_empty_uarts))
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user