Browse Source

AP_EFI: fixed bug in Lutan driver

we need to send an initial request pkt if no data from Lutan
apm_2208
Andrew Tridgell 3 years ago
parent
commit
d85fe81537
  1. 6
      libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp

6
libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp

@ -53,9 +53,9 @@ void AP_EFI_Serial_Lutan::update() @@ -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) {

Loading…
Cancel
Save