Ardupilot2/libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/hwdef.dat
Hayden Donald a29b8a4f5a AP_HAL_ChibiOS: CubeNode-ETH fix incorrect pin for CTS
Fixed an incorrect pin for UART8_CTS (PC11 should be PC12)
2024-11-27 11:53:25 +11:00

32 lines
573 B
Plaintext

include ../CubeNode/hwdef.dat
# we need RTS/CTS for the PPP link
undef PE0
undef PE1
undef PC12
undef HAL_PERIPH_ENABLE_IMU
undef HAL_GCS_ENABLED
# need to use UART8 to get RTS/CTS
PE1 UART8_TX UART8
PE0 UART8_RX UART8
PA10 UART8_RTS UART8
PC12 UART8_CTS_GPIO UART8
SERIAL_ORDER OTG1 UART8
PA4 VDD_5V_SENS ADC1 SCALE(2)
undef HAL_USE_ADC
define HAL_USE_ADC TRUE
define HAL_WITH_MCU_MONITORING 1
# can optionally run at half clock
# MCU_CLOCKRATE_MHZ 200
include ../include/network_PPPGW.inc
define HAL_MONITOR_THREAD_ENABLED 1
define AP_NETWORKING_TESTS_ENABLED 1