AP_RangeFinder: change comment about fall through LEDDARONE_MODBUS_INIT case

This commit is contained in:
Shingo Matsuura 2016-11-06 09:42:19 +09:00 committed by Tom Pittenger
parent 3b8d36314c
commit 4329cdbf2c
1 changed files with 2 additions and 2 deletions

View File

@ -62,8 +62,8 @@ 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
// FALL THROUGH
// 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