From 95f97690410573fac3622c47a4835ddd512e607c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 23 May 2020 10:24:32 +1000 Subject: [PATCH] AP_RangeFinder: use new UARTDriver discard_input method --- .../AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp index d1a699c85f..b9aadb3296 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp @@ -32,16 +32,13 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm) switch (modbus_status) { case LEDDARONE_MODBUS_STATE_INIT: { - uint8_t index = 0; - // clear read buffer uint32_t nbytes = uart->available(); - while (nbytes-- > 0) { - uart->read(); - if (++index > LEDDARONE_SERIAL_PORT_MAX) { - // LEDDARONE_STATE_ERR_SERIAL_PORT - return false; - } + if (nbytes > LEDDARONE_SERIAL_PORT_MAX) { + // LEDDARONE_STATE_ERR_SERIAL_PORT + return false; } + uart->discard_input(); + // clear buffer and buffer_len memset(read_buffer, 0, sizeof(read_buffer)); read_len = 0;