From a1db65ea4d5e1b6f0e56ace1739d211d84f83e3d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 8 Sep 2024 19:13:55 +1000 Subject: [PATCH] hwdef: default CAN MCAST enabled for PPPGW builds --- libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/defaults.parm | 2 +- libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm | 2 +- .../AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/defaults.parm | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/defaults.parm index 323395899706ef..0327366dcabc51 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/defaults.parm @@ -1,5 +1,5 @@ NET_ENABLE 1 -NET_OPTIONS 1 +NET_OPTIONS 3 # enable hw flow control UART1_RTSCTS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm index 5f23d5515f0ea8..65718aac21df7e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm @@ -1,5 +1,5 @@ NET_ENABLE 1 -NET_OPTIONS 1 +NET_OPTIONS 3 # enable hw flow control UART1_RTSCTS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/defaults.parm index 5f23d5515f0ea8..65718aac21df7e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/defaults.parm @@ -1,5 +1,5 @@ NET_ENABLE 1 -NET_OPTIONS 1 +NET_OPTIONS 3 # enable hw flow control UART1_RTSCTS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm index 89ab4beebb035b..d67da7a5fd6e36 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm @@ -1,5 +1,5 @@ NET_ENABLED 1 -NET_OPTIONS 1 +NET_OPTIONS 3 # enable hw flow control UART1_RTSCTS 1