hwdef: added CubePilot-PPPGW
This commit is contained in:
parent
44bc523db8
commit
280d7c6d15
@ -0,0 +1,5 @@
|
||||
NET_ENABLED 1
|
||||
|
||||
# enable hw flow control
|
||||
UART1_RTSCTS 1
|
||||
|
@ -0,0 +1 @@
|
||||
include ../CubePilot-CANMod/hwdef-bl.dat
|
21
libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat
Normal file
21
libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat
Normal file
@ -0,0 +1,21 @@
|
||||
include ../CubePilot-CANMod/hwdef.dat
|
||||
|
||||
# we need RTS/CTS for the PPP link
|
||||
undef PD14
|
||||
undef PD13
|
||||
undef PE0
|
||||
undef PE1
|
||||
|
||||
# need to use UART8 to get RTS/CTS
|
||||
PE1 UART8_TX UART8
|
||||
PE0 UART8_RX UART8
|
||||
PD13 UART8_RTS UART8
|
||||
PD14 UART8_CTS UART8
|
||||
|
||||
SERIAL_ORDER OTG1 UART8
|
||||
|
||||
define HAL_PERIPH_ENABLE_SERIAL_OPTIONS
|
||||
define AP_NETWORKING_BACKEND_PPP 1
|
||||
|
||||
define AP_PERIPH_NET_PPP_PORT_DEFAULT 1
|
||||
define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000
|
Loading…
Reference in New Issue
Block a user