From f6c96062c12ca6e122c820de7cc733f674daf19d Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 17 Jul 2024 16:42:52 +1000 Subject: [PATCH] AP_HAL_ChibiOS: add support for PPP between CubeRed Primary and Secondary --- .../hwdef/CubeRedPrimary/defaults.parm | 19 +++++++++++++++++++ .../hwdef/CubeRedPrimary/hwdef.dat | 19 +++++++++++-------- .../hwdef/CubeRedSecondary/defaults.parm | 10 ++++++++++ .../hwdef/CubeRedSecondary/hwdef.dat | 16 +++++++++++----- 4 files changed, 51 insertions(+), 13 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/defaults.parm index cdd83a642efe87..22f785c1a3b188 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/defaults.parm @@ -6,3 +6,22 @@ ADSB_TYPE 1 SERIAL5_BAUD 57 SERIAL5_PROTOCOL 1 EK3_PRIMARY 1 + +NET_ENABLE 1 +NET_OPTIONS 1 +NET_DHCP 0 +NET_P1_TYPE 1 +NET_P1_PROTOCOL 2 +NET_P1_IP0 192 +NET_P1_IP1 168 +NET_P1_IP2 144 +NET_P1_IP3 10 +NET_P1_PORT 14553 + +NET_P2_TYPE 4 +NET_P2_PROTOCOL 2 +NET_P2_IP0 192 +NET_P2_IP1 168 +NET_P2_IP2 144 +NET_P2_IP3 100 +NET_P2_PORT 14554 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat index d6e7dfa8e38aad..5bd8d3c71c6394 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat @@ -274,17 +274,20 @@ PG15 USART6_CTS USART6 PG8 USART6_RTS USART6 # primary <-> secondary -PE7 UART7_RX UART7 -PE8 UART7_TX UART7 +PE7 UART7_RX UART7 SPEED_VERYLOW LOW_NOISE +PE8 UART7_TX UART7 SPEED_VERYLOW # order of UARTs (and USB) -SERIAL_ORDER OTG1 USART2 USART6 USART3 UART4 UART8 EMPTY UART7 +SERIAL_ORDER OTG1 USART2 USART6 USART3 UART4 UART8 OTG2 UART7 EXT_FLASH_SIZE_MB 32 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 DEFAULT_SERIAL7_PROTOCOL SerialProtocol_MAVLink2 -define DEFAULT_SERIAL7_BAUD 2000000 +# set protocol for UART7 to SerialProtocol_PPP +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_PPP +define DEFAULT_SERIAL7_BAUD 8000000 + +define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR "192.168.144.100" +define AP_NETWORKING_DEFAULT_STATIC_NETMASK "255.255.255.0" +define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR "192.168.144.11" +define AP_NETWORKING_BACKEND_PPP 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/defaults.parm index 3be7684ba40cad..342b61b6d584b8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/defaults.parm @@ -1,2 +1,12 @@ SERIAL3_OPTIONS 8 SERIAL4_OPTIONS 8 +NET_ENABLE 1 +NET_P1_TYPE 3 +NET_P1_PROTOCOL 2 +NET_P1_IP0 192 +NET_P1_IP1 168 +NET_P1_IP2 144 +NET_P1_IP3 100 +NET_P1_PORT 14554 + +SYSID_THISMAV 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat index bd77ac79c934f3..e24d8c5299effb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat @@ -7,6 +7,8 @@ MCU STM32H7xx STM32H757xx define CORE_CM7 define SMPS_PWR +env OPTIMIZE -Os + # crystal frequency OSCILLATOR_HZ 24000000 @@ -39,7 +41,8 @@ PA6 RSSI_IN ADC1 SCALE(2) # CAN config PB14 GPIOCAN2_TERM OUTPUT HIGH - +PC12 GPIOCAN1_SHUTDOWN OUTPUT LOW +PF1 GPIOCAN2_SHUTDOWN OUTPUT LOW PA12 CAN1_TX CAN1 PB8 CAN1_RX CAN1 @@ -118,8 +121,8 @@ PA7 HP_UNIDIR_ENABLED OUTPUT HIGH GPIO(5) # UART connected to FMU, uses DMA -PE7 UART7_RX UART7 SPEED_HIGH -PE8 UART7_TX UART7 SPEED_HIGH +PE7 UART7_RX UART7 SPEED_VERYLOW LOW_NOISE +PE8 UART7_TX UART7 SPEED_VERYLOW # UART for SBUS out PC7 USART6_RX USART6 SPEED_HIGH LOW @@ -144,13 +147,16 @@ PD4 USART2_RTS USART2 SPEED_HIGH PD3 USART2_CTS USART2 SPEED_HIGH # order of UARTs -SERIAL_ORDER UART7 UART8 USART3 USART6 UART4 USART2 +SERIAL_ORDER UART8 UART7 USART3 USART6 UART4 USART2 # use 2 MBaud when talking to primary controller -define DEFAULT_SERIAL0_BAUD 2000000 +define DEFAULT_SERIAL1_BAUD 8000000 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_PPP define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Sbus1 define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_RCIN +define AP_NETWORKING_BACKEND_PPP 1 + # only use pulse input for PPM, other protocols # are on serial define HAL_RCIN_PULSE_PPM_ONLY