AP_RangeFinder: remove move-to-error-state for LeddarOne driver

Just because there's a lot in your input buffer doesn't necessarily mean
the rangefinder is faulty.
This commit is contained in:
Peter Barker 2020-05-24 11:36:34 +10:00 committed by Andrew Tridgell
parent 3bf1ac5918
commit af80c4a29f
1 changed files with 0 additions and 5 deletions

View File

@ -32,11 +32,6 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm)
switch (modbus_status) {
case LEDDARONE_MODBUS_STATE_INIT: {
uint32_t nbytes = uart->available();
if (nbytes > LEDDARONE_SERIAL_PORT_MAX) {
// LEDDARONE_STATE_ERR_SERIAL_PORT
return false;
}
uart->discard_input();
// clear buffer and buffer_len