AP_CANManager: fixed owner of SLCAN UART

this broke when we moved to the unified AP_HAL locking system for
UARTs. The SLCAN code relied on the fact that the thread owner check
was not done for the read_locked() path. Now that we have a higher
level consistent API that check is done and SLCAN broke
This commit is contained in:
Andrew Tridgell 2023-08-01 17:19:44 +10:00
parent 0ed33653fc
commit 1723cca023
1 changed files with 3 additions and 0 deletions

View File

@ -658,6 +658,9 @@ bool SLCAN::CANIface::select(bool &read, bool &write, const AP_HAL::CANFrame* co
return ret;
}
// ensure we own the UART. Locking is handled at the CAN interface level
_port->begin_locked(0, 0, 0, _serial_lock_key);
// if under passthrough, we only do send when can_iface also allows it
if (_port->available_locked(_serial_lock_key) || rx_queue_.available()) {
// allow for receiving messages over slcan