From 6254787186d0d04308291ff8745f7ca1c1272349 Mon Sep 17 00:00:00 2001 From: Shingo Matsuura Date: Sat, 5 Nov 2016 03:07:42 +0900 Subject: [PATCH] AP_RangeFinder: remove break in LEDDARONE_MODOBUS_INIT case and and use () around (read_len == 0) for clarity --- libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp index 47791f1937..8ac5baac36 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp @@ -62,7 +62,6 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm) memset(read_buffer, 0, sizeof(read_buffer)); read_len = 0; modbus_status = LEDDARONE_MODBUS_PRE_SEND_REQUEST; - break; case LEDDARONE_MODBUS_PRE_SEND_REQUEST: // send a request message for Modbus function 4 @@ -82,7 +81,7 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm) if (AP_HAL::millis() - last_sending_request_ms > 200) { // reset mod_bus status to read new buffer // if read_len is zero, send request without initialize - modbus_status = read_len == 0 ? LEDDARONE_MODBUS_PRE_SEND_REQUEST : LEDDARONE_MODBUS_INIT; + modbus_status = (read_len == 0) ? LEDDARONE_MODBUS_PRE_SEND_REQUEST : LEDDARONE_MODBUS_INIT; } } break; @@ -102,7 +101,7 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm) // if status is not reading buffer, reset mod_bus status to read new buffer else if (leddarone_status != LEDDARONE_READING_BUFFER) { // if read_len is zero, send request without initialize - modbus_status = read_len == 0 ? LEDDARONE_MODBUS_PRE_SEND_REQUEST : LEDDARONE_MODBUS_INIT; + modbus_status = (read_len == 0) ? LEDDARONE_MODBUS_PRE_SEND_REQUEST : LEDDARONE_MODBUS_INIT; } break; }