From 3b8d36314c2c90cf96d6b818ca8718cc4fd7f6e7 Mon Sep 17 00:00:00 2001 From: Shingo Matsuura Date: Sun, 6 Nov 2016 09:27:00 +0900 Subject: [PATCH] AP_RangeFinder: add comment about no break at LEDDARONE_MODBUS_INIT case --- libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp index 9c422d89ec..37c9d7fd78 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp @@ -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) {