ChibiOS: UARTDriver: EVT_TRANSMIT_END
is never seen resulting in slow half duplex TX to RX switch
#26908
Labels
EVT_TRANSMIT_END
is never seen resulting in slow half duplex TX to RX switch
#26908
I have been poking about in the UART driver trying to get RS485 driver enable pin working, in the end I was able to use the hardware support. I was not able to get it to function acceptably in software because I discovered the
EVT_TRANSMIT_END
event is never triggered. This event is also used for the switch from TX to RX for half duplex support.This is where we wait for the event in the UART thread:
ardupilot/libraries/AP_HAL_ChibiOS/UARTDriver.cpp
Line 128 in 0a3ff72
Because it never triggers we wait for the timeout resulting in upto 1ms of delay in switching from TX to RX.
The event is checked again here:
ardupilot/libraries/AP_HAL_ChibiOS/UARTDriver.cpp
Line 146 in 0a3ff72
This commit adds a simple check if the event has ever been seen and reports in the
@SYS/uarts.txt
: IamPete1@6e3f29fI have tested on a CubeOrangePlus using a range of serial protocols with and without the half duplex serial option set, I always get 0 for TX_end:
The text was updated successfully, but these errors were encountered: