mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Hott_Telem: use new UARTDriver discard_input method
This commit is contained in:
parent
de2055b57f
commit
67e4756f19
@ -419,10 +419,7 @@ void AP_Hott_Telem::loop(void)
|
|||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (n > 2) {
|
if (n > 2) {
|
||||||
while (n--) {
|
uart->discard_input();
|
||||||
uart->read();
|
|
||||||
hal.scheduler->delay_microseconds(100);
|
|
||||||
}
|
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user