AP_VideoTX: Tramp: Add half-duplex to port config

Tramp is half-duplex, so this should be set
automatically like already done for SmartAudio.

Also set pull-down options for consistency with
SmartAudio.
This commit is contained in:
Patrick Menschel 2024-12-04 21:28:44 +01:00
parent 9a5f81aa95
commit c98707e905
1 changed files with 5 additions and 2 deletions

View File

@ -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");