mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
hwdef: enable CAN multicast support in PPP gateways
This commit is contained in:
parent
cd14b2e1c5
commit
f065548866
@ -5,6 +5,7 @@ define HAL_PERIPH_ENABLE_RTC
|
||||
|
||||
define HAL_PERIPH_ENABLE_SERIAL_OPTIONS
|
||||
define AP_NETWORKING_BACKEND_PPP 1
|
||||
define AP_NETWORKING_CAN_MCAST_ENABLED 1
|
||||
|
||||
define AP_PERIPH_NET_PPP_PORT_DEFAULT 1
|
||||
define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000
|
||||
|
@ -11,6 +11,7 @@ define CH_CFG_USE_DYNAMIC 1
|
||||
define CH_CFG_USE_WAITEXIT 1
|
||||
|
||||
define AP_NETWORKING_ENABLED 1
|
||||
define AP_NETWORKING_CAN_MCAST_ENABLED 1
|
||||
|
||||
ROMFS_WILDCARD Tools/AP_Bootloader/Web/*.html
|
||||
env ROMFS_UNCOMPRESSED True
|
||||
|
@ -38,9 +38,9 @@
|
||||
|
||||
// less LWIP functionality in the bootloader
|
||||
#define LWIP_DHCP 0
|
||||
#define LWIP_UDP 0
|
||||
#define LWIP_UDP 1
|
||||
#define LWIP_PPP 0
|
||||
#define LWIP_IGMP 0
|
||||
#define LWIP_IGMP 1
|
||||
#define LWIP_ALTCP 0
|
||||
#define IP_FORWARD 0
|
||||
#define LWIP_SINGLE_NETIF 1
|
||||
|
Loading…
Reference in New Issue
Block a user