Browse Source

AP_Camera: use new UARTDriver discard_input method

c415-sdk
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
d012cf8d47
  1. 5
      libraries/AP_Camera/AP_RunCam.cpp

5
libraries/AP_Camera/AP_RunCam.cpp

@ -748,10 +748,7 @@ void AP_RunCam::drain()
return; return;
} }
uint32_t avail = uart->available(); uart->discard_input();
while (avail-- > 0) {
uart->read();
}
} }
// get the device info (firmware version, protocol version and features) // get the device info (firmware version, protocol version and features)

Loading…
Cancel
Save