AP_RangeFinder: add comment about no break at LEDDARONE_MODBUS_INIT case

This commit is contained in:
Shingo Matsuura 2016-11-06 09:27:00 +09:00 committed by Tom Pittenger
parent 0eeca3ee0b
commit 3b8d36314c

View File

@ -62,6 +62,9 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm)
read_len = 0;
modbus_status = LEDDARONE_MODBUS_PRE_SEND_REQUEST;
// no "break;"
// to fall through to next state LEDDARONE_MODBUS_PRE_SEND_REQUEST immediately
case LEDDARONE_MODBUS_PRE_SEND_REQUEST:
// send a request message for Modbus function 4
if (send_request() != LEDDARONE_OK) {