From d85fe81537e08a22cdf3d50b37883fad12c34e8f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 Jun 2022 13:18:23 +1000 Subject: [PATCH] AP_EFI: fixed bug in Lutan driver we need to send an initial request pkt if no data from Lutan --- libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp b/libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp index f4315c5047..89eade4ee9 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp @@ -53,9 +53,9 @@ void AP_EFI_Serial_Lutan::update() if (n + pkt_nbytes > sizeof(pkt)) { pkt_nbytes = 0; } - const ssize_t nread = port->read(&pkt[pkt_nbytes], n); - if (nread <= 0) { - return; + ssize_t nread = port->read(&pkt[pkt_nbytes], n); + if (nread < 0) { + nread = 0; } pkt_nbytes += nread; if (pkt_nbytes > 2) {