AP_Camera: use new UARTDriver discard_input method
This commit is contained in:
parent
a073469423
commit
d012cf8d47
@ -748,10 +748,7 @@ void AP_RunCam::drain()
|
||||
return;
|
||||
}
|
||||
|
||||
uint32_t avail = uart->available();
|
||||
while (avail-- > 0) {
|
||||
uart->read();
|
||||
}
|
||||
uart->discard_input();
|
||||
}
|
||||
|
||||
// get the device info (firmware version, protocol version and features)
|
||||
|
Loading…
Reference in New Issue
Block a user