mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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:
parent
9ddd1afb34
commit
d85fe81537
@ -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…
Reference in New Issue
Block a user