mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_EFI: prevent flood of Lutan serial port
send request at max 5Hz
This commit is contained in:
parent
54280c2ae0
commit
4585c9fdc1
@ -91,7 +91,7 @@ void AP_EFI_Serial_Lutan::update()
|
|||||||
pkt_nbytes = 0;
|
pkt_nbytes = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (n == 0 || now - last_request_ms > 200) {
|
if (now - last_request_ms > 200) {
|
||||||
last_request_ms = now;
|
last_request_ms = now;
|
||||||
port->discard_input();
|
port->discard_input();
|
||||||
send_request();
|
send_request();
|
||||||
|
Loading…
Reference in New Issue
Block a user