From b9b503328b093842e4c94f90f48b2593953010fe Mon Sep 17 00:00:00 2001 From: Patrick Menschel Date: Wed, 4 Dec 2024 21:28:44 +0100 Subject: [PATCH] AP_VideoTX: Tramp: Add half-duplex to port config Tramp is half-duplex, so this should be set automatically like already done for SmartAudio. Already set pull-down for consistency with SmartAudio. --- libraries/AP_VideoTX/AP_Tramp.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AP_VideoTX/AP_Tramp.cpp b/libraries/AP_VideoTX/AP_Tramp.cpp index afe6f07ac7bc2..6f3efca2103d6 100644 --- a/libraries/AP_VideoTX/AP_Tramp.cpp +++ b/libraries/AP_VideoTX/AP_Tramp.cpp @@ -532,8 +532,11 @@ bool AP_Tramp::init(void) port->configure_parity(0); port->set_stop_bits(1); port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); - port->set_options((port->get_options() & ~AP_HAL::UARTDriver::OPTION_RXINV)); - + port->set_options((port->get_options() & ~AP_HAL::UARTDriver::OPTION_RXINV) + | AP_HAL::UARTDriver::OPTION_HDPLEX + | AP_HAL::UARTDriver::OPTION_PULLDOWN_TX + | AP_HAL::UARTDriver::OPTION_PULLDOWN_RX + ); port->begin(AP_TRAMP_UART_BAUD, AP_TRAMP_UART_BUFSIZE_RX, AP_TRAMP_UART_BUFSIZE_TX); debug("port opened");