AP_EFI: fixed bug in Lutan driver

we need to send an initial request pkt if no data from Lutan
This commit is contained in:
Andrew Tridgell 2022-06-04 13:18:23 +10:00
parent 9ddd1afb34
commit d85fe81537

View File

@ -53,9 +53,9 @@ void AP_EFI_Serial_Lutan::update()
if (n + pkt_nbytes > sizeof(pkt)) { if (n + pkt_nbytes > sizeof(pkt)) {
pkt_nbytes = 0; pkt_nbytes = 0;
} }
const ssize_t nread = port->read(&pkt[pkt_nbytes], n); ssize_t nread = port->read(&pkt[pkt_nbytes], n);
if (nread <= 0) { if (nread < 0) {
return; nread = 0;
} }
pkt_nbytes += nread; pkt_nbytes += nread;
if (pkt_nbytes > 2) { if (pkt_nbytes > 2) {