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
This commit is contained in:
Randy Mackay 2016-12-12 21:37:52 +09:00
parent a2474667a8
commit 0dd7e78c2b

View File

@ -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()) {