From 0dd7e78c2b4af696b2cddcc901205cd65a4a4967 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 12 Dec 2016 21:37:52 +0900 Subject: [PATCH] RangeFinder: fix to suppressing comment for case fall through no functional change eclipse stops complaining if no-break is used in place of fall-through --- libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp index b770955ba5..22e941a14d 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp @@ -71,18 +71,15 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm) memset(read_buffer, 0, sizeof(read_buffer)); read_len = 0; modbus_status = LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST; - - // FALL THROUGH + } // no break to fall through to next state LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST immediately - } case LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST: // send a request message for Modbus function 4 uart->write(send_request_buffer, sizeof(send_request_buffer)); modbus_status = LEDDARONE_MODBUS_STATE_SENT_REQUEST; last_sending_request_ms = AP_HAL::millis(); - - // FALL THROUGH + // no break case LEDDARONE_MODBUS_STATE_SENT_REQUEST: if (uart->available()) {