From ed3ed7270c23211c982957cedfea099cf2829f0f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 19 Nov 2018 10:31:24 +0900 Subject: [PATCH] RangeFinder: benewake buffer uses uint8_t --- libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp | 10 +++++++--- libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h | 2 +- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp index e3e366495d..bf2ef6b2fb 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp @@ -85,7 +85,11 @@ bool AP_RangeFinder_Benewake::get_reading(uint16_t &reading_cm) // read any available lines from the lidar int16_t nbytes = uart->available(); while (nbytes-- > 0) { - char c = uart->read(); + int16_t r = uart->read(); + if (r < 0) { + continue; + } + uint8_t c = (uint8_t)r; // if buffer is empty and this byte is 0x59, add to buffer if (linebuf_len == 0) { if (c == BENEWAKE_FRAME_HEADER) { @@ -107,10 +111,10 @@ bool AP_RangeFinder_Benewake::get_reading(uint16_t &reading_cm) // calculate checksum uint8_t checksum = 0; for (uint8_t i=0; i= BENEWAKE_DIST_MAX_CM) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h index a5ff303c00..db984ccb01 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h @@ -40,6 +40,6 @@ private: AP_HAL::UARTDriver *uart = nullptr; benewake_model_type model_type; uint32_t last_reading_ms; - char linebuf[10]; + uint8_t linebuf[10]; uint8_t linebuf_len; };