mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
AP_EFI: use new UARTDriver discard_input method
This commit is contained in:
parent
d012cf8d47
commit
71f6262294
@ -44,11 +44,7 @@ void AP_EFI_Serial_MS::update()
|
||||
}
|
||||
|
||||
if (port->available() == 0 || now - last_response_ms > 200) {
|
||||
// clear the input buffer
|
||||
uint32_t buffered_data_size = port->available();
|
||||
for (uint32_t i = 0; i < buffered_data_size; i++) {
|
||||
port->read();
|
||||
}
|
||||
port->discard_input();
|
||||
// Request an update from the realtime table (7).
|
||||
// The data we need start at offset 6 and ends at 129
|
||||
send_request(7, RT_FIRST_OFFSET, RT_LAST_OFFSET);
|
||||
|
Loading…
Reference in New Issue
Block a user